diff --git a/src/arm_on_rail_sim/CMakeLists.txt b/src/arm_on_rail_sim/CMakeLists.txt deleted file mode 100644 index aa924c51..00000000 --- a/src/arm_on_rail_sim/CMakeLists.txt +++ /dev/null @@ -1,48 +0,0 @@ -cmake_minimum_required(VERSION 3.22) -project(arm_on_rail_sim) - -find_package(ament_cmake REQUIRED) -find_package(picknik_accessories REQUIRED) - - -# Install all XML files in directory -set(PICKNIK_ACCESSORIES_SHARE_DIR -"${CMAKE_INSTALL_PREFIX}/../picknik_accessories/share/picknik_accessories/mujoco_assets/" -) -# Destination directory -set(DEST_DIR "${CMAKE_INSTALL_PREFIX}/share/${PROJECT_NAME}/description/") - -install(DIRECTORY "${PICKNIK_ACCESSORIES_SHARE_DIR}" - DESTINATION "${DEST_DIR}" - FILES_MATCHING PATTERN "*") - -# Install individual XML files -# -# set(EXTERNAL_XML_FILES -# "${PICKNIK_ACCESSORIES_SHARE_DIR}/ur5e/ur5e_globals.xml" -# "${PICKNIK_ACCESSORIES_SHARE_DIR}/ur5e/ur5e.xml" -# # Add additional files here if desired -# ) -# foreach(xml_file IN LISTS EXTERNAL_XML_FILES) -# install(FILES "${xml_file}" -# DESTINATION "${DEST_DIR}" -# ) -# endforeach() - -install( - DIRECTORY - config - description - launch - objectives - waypoints - DESTINATION - share/${PROJECT_NAME} -) - -if(BUILD_TESTING) - find_package(ament_lint_auto REQUIRED) - ament_lint_auto_find_test_dependencies() -endif() - -ament_package() diff --git a/src/arm_on_rail_sim/LICENSE b/src/arm_on_rail_sim/LICENSE deleted file mode 100644 index 574ef079..00000000 --- a/src/arm_on_rail_sim/LICENSE +++ /dev/null @@ -1,25 +0,0 @@ -Redistribution and use in source and binary forms, with or without -modification, are permitted provided that the following conditions are met: - - * Redistributions of source code must retain the above copyright - notice, this list of conditions and the following disclaimer. - - * Redistributions in binary form must reproduce the above copyright - notice, this list of conditions and the following disclaimer in the - documentation and/or other materials provided with the distribution. - - * Neither the name of the copyright holder nor the names of its - contributors may be used to endorse or promote products derived from - this software without specific prior written permission. - -THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -POSSIBILITY OF SUCH DAMAGE. diff --git a/src/arm_on_rail_sim/README.md b/src/arm_on_rail_sim/README.md deleted file mode 100644 index 8de6e87c..00000000 --- a/src/arm_on_rail_sim/README.md +++ /dev/null @@ -1,5 +0,0 @@ -# arm_on_rail_sim - -A MoveIt Pro MuJoCo simulation for PickNik's Universal Robots (UR) arms. - -For detailed documentation see: [MoveIt Pro Documentation](https://docs.picknik.ai/) diff --git a/src/arm_on_rail_sim/config/config.yaml b/src/arm_on_rail_sim/config/config.yaml deleted file mode 100644 index 292dfd10..00000000 --- a/src/arm_on_rail_sim/config/config.yaml +++ /dev/null @@ -1,84 +0,0 @@ -# -# This contains information for a unique instance of a robot. -# - -# Name of the package to specialize -based_on_package: "picknik_ur_base_config" -hardware: - # Parameters used to configure the robot description through XACRO. - # A URDF and SRDF are both required. - # [Required] - robot_description: - urdf: - package: "arm_on_rail_sim" - path: "description/picknik_ur.xacro" - srdf: - package: "arm_on_rail_sim" - path: "config/moveit/picknik_ur.srdf" - urdf_params: - - mujoco_model: "description/scene.xml" - -moveit_params: - servo: - package: "arm_on_rail_sim" - path: "config/moveit/ur_servo.yaml" - joint_limits: - package: "arm_on_rail_sim" - path: "config/moveit/joint_limits.yaml" - servo_joint_limits: - package: "arm_on_rail_sim" - path: "config/moveit/hard_joint_limits.yaml" - -# Configuration for loading behaviors and objectives. -# [Required] -objectives: - # List of plugins for loading custom behaviors. - # [Required] - behavior_loader_plugins: - # This plugin will load the core MoveIt Pro Behaviors. - # Add additional plugin loaders as needed. - core: - - "moveit_studio::behaviors::CoreBehaviorsLoader" - - "moveit_studio::behaviors::MTCCoreBehaviorsLoader" - - "moveit_studio::behaviors::ServoBehaviorsLoader" - - "moveit_studio::behaviors::VisionBehaviorsLoader" - - "picknik_registration::PicknikRegistrationBehaviorsLoader" - # Specify source folder for objectives - # [Required] - objective_library_paths: - sim_objectives: - package_name: "arm_on_rail_sim" - relative_path: "objectives" - # Specify the location of the saved waypoints file. - # [Required] - waypoints_file: - package_name: "arm_on_rail_sim" - relative_path: "waypoints/ur_waypoints.yaml" - - -# Configuration for launching ros2_control processes. -# [Required, if using ros2_control] -ros2_control: - config: - package: "arm_on_rail_sim" - path: "config/control/picknik_ur.ros2_control.yaml" - # MoveIt Pro will load and activate these controllers at start up to ensure they are available. - # If not specified, it is up to the user to ensure the appropriate controllers are active and available - # for running the application. - # [Optional, default=[]] - controllers_active_at_startup: - - "force_torque_sensor_broadcaster" - - "robotiq_gripper_controller" - - "joint_state_broadcaster" - - "servo_controller" - # Load but do not start these controllers so they can be activated later if needed. - controllers_inactive_at_startup: - - "joint_trajectory_controller" - - "joint_trajectory_admittance_controller" - - "velocity_force_controller" - # Any controllers here will not be spawned by MoveIt Pro. - # [Optional, default=[]] - controllers_not_managed: [] - # Optionally configure remapping rules to let multiple controllers receive commands on the same topic. - # [Optional, default=[]] - controller_shared_topics: [] diff --git a/src/arm_on_rail_sim/config/control/picknik_ur.ros2_control.yaml b/src/arm_on_rail_sim/config/control/picknik_ur.ros2_control.yaml deleted file mode 100644 index 10a994ff..00000000 --- a/src/arm_on_rail_sim/config/control/picknik_ur.ros2_control.yaml +++ /dev/null @@ -1,229 +0,0 @@ -controller_manager: - ros__parameters: - update_rate: 600 # Hz - joint_state_broadcaster: - type: joint_state_broadcaster/JointStateBroadcaster - joint_trajectory_controller: - type: joint_trajectory_controller/JointTrajectoryController - robotiq_gripper_controller: - type: position_controllers/GripperActionController - servo_controller: - type: joint_trajectory_controller/JointTrajectoryController - force_torque_sensor_broadcaster: - type: force_torque_sensor_broadcaster/ForceTorqueSensorBroadcaster - joint_trajectory_admittance_controller: - type: joint_trajectory_admittance_controller/JointTrajectoryAdmittanceController - velocity_force_controller: - type: velocity_force_controller/VelocityForceController - - -joint_state_broadcaster: - ros__parameters: - use_local_topics: false - joints: - - linear_rail_joint - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - - robotiq_85_left_knuckle_joint - interfaces: - - position - - velocity - - effort - -joint_trajectory_controller: - ros__parameters: - joints: - - linear_rail_joint - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - command_interfaces: - - position - state_interfaces: - - position - - velocity - command_joints: - - linear_rail_joint - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - state_publish_rate: 100.0 - action_monitor_rate: 20.0 - allow_partial_joints_goal: false - constraints: - stopped_velocity_tolerance: 0.0 - goal_time: 0.0 - linear_rail_joint: - goal: 0.05 - shoulder_pan_joint: - goal: 0.05 - shoulder_lift_joint: - goal: 0.05 - elbow_joint: - goal: 0.05 - wrist_1_joint: - goal: 0.05 - wrist_2_joint: - goal: 0.05 - wrist_3_joint: - goal: 0.05 - acceleration_limits: - linear_rail_joint: 10.0 - shoulder_pan_joint: 10.0 - shoulder_lift_joint: 10.0 - elbow_joint: 10.0 - wrist_1_joint: 10.0 - wrist_2_joint: 10.0 - wrist_3_joint: 10.0 - -robotiq_gripper_controller: - ros__parameters: - default: true - joint: robotiq_85_left_knuckle_joint - allow_stalling: true -servo_controller: - ros__parameters: - joints: - - linear_rail_joint - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - - command_interfaces: - - position - state_interfaces: - - position - - velocity - command_joints: - - linear_rail_joint - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - state_publish_rate: 100.0 - action_monitor_rate: 20.0 - allow_partial_joints_goal: false - constraints: - stopped_velocity_tolerance: 0.0 - goal_time: 0.0 - linear_rail_joint: - goal: 0.05 - shoulder_pan_joint: - goal: 0.05 - shoulder_lift_joint: - goal: 0.05 - elbow_joint: - goal: 0.05 - wrist_1_joint: - goal: 0.05 - wrist_2_joint: - goal: 0.05 - wrist_3_joint: - goal: 0.05 - acceleration_limits: - linear_rail_joint: 10.0 - shoulder_pan_joint: 10.0 - shoulder_lift_joint: 10.0 - elbow_joint: 10.0 - wrist_1_joint: 10.0 - wrist_2_joint: 10.0 - wrist_3_joint: 10.0 - -force_torque_sensor_broadcaster: - ros__parameters: - sensor_name: robotiq_ft_sensor - state_interface_names: - - force.x - - force.y - - force.z - - torque.x - - torque.y - - torque.z - frame_id: robotiq_ft_sensor - - -joint_trajectory_admittance_controller: - ros__parameters: - joints: - - linear_rail_joint - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - base_frame: base_link - sensor_frame: tool0 - ee_frame: grasp_link - ft_sensor_name: robotiq_ft_sensor - # Joint accelerations chosen to match MoveIt configs. - stop_accelerations: - - 30.0 - - 30.0 - - 30.0 - - 30.0 - - 30.0 - - 30.0 - - 30.0 - -velocity_force_controller: - ros__parameters: - joints: - - linear_rail_joint - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - base_frame: base_link - sensor_frame: tool0 - ee_frame: grasp_link - ft_sensor_name: robotiq_ft_sensor - ft_force_deadband: 2.0 - ft_torque_deadband: 1.0 - max_joint_velocity: - - 0.524 - - 0.524 - - 0.524 - - 0.524 - - 1.047 - - 1.047 - - 1.047 - max_joint_acceleration: - - 0.524 - - 0.524 - - 0.524 - - 0.524 - - 0.524 - - 0.524 - - 0.524 - max_cartesian_velocity: - - 0.25 - - 0.25 - - 0.25 - - 1.5707 - - 1.5707 - - 1.5707 - max_cartesian_acceleration: - - 2.0 - - 2.0 - - 2.0 - - 4.0 - - 4.0 - - 4.0 diff --git a/src/arm_on_rail_sim/config/moveit/hard_joint_limits.yaml b/src/arm_on_rail_sim/config/moveit/hard_joint_limits.yaml deleted file mode 100644 index 53b218df..00000000 --- a/src/arm_on_rail_sim/config/moveit/hard_joint_limits.yaml +++ /dev/null @@ -1,97 +0,0 @@ -# Joints limits -# -# Sources: -# -# - Universal Robots e-Series, User Manual, UR5e, Version 5.8 -# https://s3-eu-west-1.amazonaws.com/ur-support-site/69091/99404_UR5e_User_Manual_en_Global.pdf -# - Support > Articles > UR articles > Max. joint torques -# https://www.universal-robots.com/articles/ur-articles/max-joint-torques -# retrieved: 2020-06-16, last modified: 2020-06-09 -# -# NOTE: Acceleration limits are not publicly available so we have picked a reasonable upper limit -joint_limits: - linear_rail_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: 10.0 - max_effort: 150.0 - max_position: 2.9 - max_velocity: 0.175 - min_position: -2.1 - shoulder_pan_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 180.0 - max_effort: 150.0 - max_position: !degrees 180.0 - max_velocity: !degrees 30.0 - min_position: !degrees -180.0 - shoulder_lift_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 180.0 - max_effort: 150.0 - max_position: !degrees 90.0 - max_velocity: !degrees 30.0 - min_position: !degrees -270.0 - elbow_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 180.0 - max_effort: 150.0 - # we artificially limit this joint to half its actual joint position limit - # to avoid (MoveIt/OMPL) planning problems, as due to the physical - # construction of the robot, it's impossible to rotate the 'elbow_joint' - # over more than approx +- 1 pi (the shoulder lift joint gets in the way). - # - # This leads to planning problems as the search space will be divided into - # two sections, with no connections from one to the other. - # - # Refer to https://github.com/ros-industrial/universal_robot/issues/265 for - # more information. - max_position: !degrees 180.0 - max_velocity: !degrees 30.0 - min_position: !degrees -180.0 - wrist_1_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 180.0 - max_effort: 28.0 - max_position: !degrees 180.0 - max_velocity: !degrees 60.0 - min_position: !degrees -180.0 - wrist_2_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 180.0 - max_effort: 28.0 - max_position: !degrees 180.0 - max_velocity: !degrees 60.0 - min_position: !degrees -180.0 - wrist_3_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 180.0 - max_effort: 28.0 - max_position: !degrees 360.0 - max_velocity: !degrees 60.0 - min_position: !degrees -360.0 - robotiq_85_left_knuckle_joint: - has_velocity_limits: true - max_velocity: 0.5 - has_acceleration_limits: true - max_acceleration: 1.0 diff --git a/src/arm_on_rail_sim/config/moveit/joint_limits.yaml b/src/arm_on_rail_sim/config/moveit/joint_limits.yaml deleted file mode 100644 index d6cdcf6f..00000000 --- a/src/arm_on_rail_sim/config/moveit/joint_limits.yaml +++ /dev/null @@ -1,97 +0,0 @@ -# Joints limits -# -# Sources: -# -# - Universal Robots e-Series, User Manual, UR5e, Version 5.8 -# https://s3-eu-west-1.amazonaws.com/ur-support-site/69091/99404_UR5e_User_Manual_en_Global.pdf -# - Support > Articles > UR articles > Max. joint torques -# https://www.universal-robots.com/articles/ur-articles/max-joint-torques -# retrieved: 2020-06-16, last modified: 2020-06-09 -# -# NOTE: Acceleration limits are not publicly available so we have picked a reasonable upper limit -joint_limits: - linear_rail_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: 10.0 - max_effort: 1500.0 - max_position: 2.9 - max_velocity: 1.0 - min_position: -2.1 - shoulder_pan_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 30.0 - max_effort: 150.0 - max_position: !degrees 180.0 - max_velocity: !degrees 30.0 - min_position: !degrees -180.0 - shoulder_lift_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 30.0 - max_effort: 150.0 - max_position: !degrees 90.0 - max_velocity: !degrees 30.0 - min_position: !degrees -270.0 - elbow_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 30.0 - max_effort: 150.0 - # we artificially limit this joint to half its actual joint position limit - # to avoid (MoveIt/OMPL) planning problems, as due to the physical - # construction of the robot, it's impossible to rotate the 'elbow_joint' - # over more than approx +- 1 pi (the shoulder lift joint gets in the way). - # - # This leads to planning problems as the search space will be divided into - # two sections, with no connections from one to the other. - # - # Refer to https://github.com/ros-industrial/universal_robot/issues/265 for - # more information. - max_position: !degrees 180.0 - max_velocity: !degrees 30.0 - min_position: !degrees -180.0 - wrist_1_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 30.0 - max_effort: 28.0 - max_position: !degrees 180.0 - max_velocity: !degrees 60.0 - min_position: !degrees -180.0 - wrist_2_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 30.0 - max_effort: 28.0 - max_position: !degrees 180.0 - max_velocity: !degrees 60.0 - min_position: !degrees -180.0 - wrist_3_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 30.0 - max_effort: 28.0 - max_position: !degrees 360.0 - max_velocity: !degrees 60.0 - min_position: !degrees -360.0 - robotiq_85_left_knuckle_joint: - has_velocity_limits: true - max_velocity: 0.5 - has_acceleration_limits: true - max_acceleration: 1.0 diff --git a/src/arm_on_rail_sim/config/moveit/ompl_planning.yaml b/src/arm_on_rail_sim/config/moveit/ompl_planning.yaml deleted file mode 100644 index 186158d5..00000000 --- a/src/arm_on_rail_sim/config/moveit/ompl_planning.yaml +++ /dev/null @@ -1,32 +0,0 @@ -planning_plugins: - - ompl_interface/OMPLPlanner -# The order of the elements in the adapter corresponds to the order they are processed by the motion planning pipeline. -request_adapters: - - default_planning_request_adapters/ResolveConstraintFrames - - default_planning_request_adapters/ValidateWorkspaceBounds - - default_planning_request_adapters/CheckStartStateBounds - - default_planning_request_adapters/CheckStartStateCollision -response_adapters: - - default_planning_response_adapters/AddTimeOptimalParameterization - - default_planning_response_adapters/ValidateSolution - -planner_configs: - APSConfigDefault: - type: geometric::AnytimePathShortening - shortcut: 1 # Attempt to shortcut all new solution paths - hybridize: 1 # Compute hybrid solution trajectories - max_hybrid_paths: 32 # Number of hybrid paths generated per iteration - num_planners: 16 # The number of default planners to use for planning - planners: "RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect" # A comma-separated list of planner types (e.g., "PRM,EST,RRTConnect"Optionally, planner parameters can be passed to change the default:"PRM[max_nearest_neighbors=5],EST[goal_bias=.5],RRT[range=10. goal_bias=.1]" - RRTConnectkConfigDefault: - type: geometric::RRTConnect - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() -manipulator: - default_planner_config: RRTConnectkConfigDefault - planner_configs: - - APSConfigDefault - - RRTConnectkConfigDefault - enforce_constrained_state_space: true - ##Note: commenting the following line lets moveit chose RRTConnect as default planner rather than LBKPIECE - projection_evaluator: joints(shoulder_pan_joint,shoulder_lift_joint) - longest_valid_segment_fraction: 0.01 diff --git a/src/arm_on_rail_sim/config/moveit/picknik_ur.srdf b/src/arm_on_rail_sim/config/moveit/picknik_ur.srdf deleted file mode 100644 index c24efd02..00000000 --- a/src/arm_on_rail_sim/config/moveit/picknik_ur.srdf +++ /dev/null @@ -1,198 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/arm_on_rail_sim/config/moveit/pilz_cartesian_limits.yaml b/src/arm_on_rail_sim/config/moveit/pilz_cartesian_limits.yaml deleted file mode 100644 index 1633938e..00000000 --- a/src/arm_on_rail_sim/config/moveit/pilz_cartesian_limits.yaml +++ /dev/null @@ -1,6 +0,0 @@ -# Cartesian limits for the Pilz planner -cartesian_limits: - max_trans_vel: 0.1 - max_trans_acc: 0.1 - max_trans_dec: -0.1 - max_rot_vel: 0.1 diff --git a/src/arm_on_rail_sim/config/moveit/pilz_industrial_motion_planner_planning.yaml b/src/arm_on_rail_sim/config/moveit/pilz_industrial_motion_planner_planning.yaml deleted file mode 100644 index dd179d2d..00000000 --- a/src/arm_on_rail_sim/config/moveit/pilz_industrial_motion_planner_planning.yaml +++ /dev/null @@ -1,13 +0,0 @@ -planning_plugins: - - pilz_industrial_motion_planner/CommandPlanner -default_planner_config: LIN -request_adapters: - - default_planning_request_adapters/ResolveConstraintFrames - - default_planning_request_adapters/ValidateWorkspaceBounds - - default_planning_request_adapters/CheckStartStateBounds - - default_planning_request_adapters/CheckStartStateCollision -response_adapters: - - default_planning_response_adapters/ValidateSolution -capabilities: >- - pilz_industrial_motion_planner/MoveGroupSequenceAction - pilz_industrial_motion_planner/MoveGroupSequenceService diff --git a/src/arm_on_rail_sim/config/moveit/sensors_3d.yaml b/src/arm_on_rail_sim/config/moveit/sensors_3d.yaml deleted file mode 100644 index 12ac1297..00000000 --- a/src/arm_on_rail_sim/config/moveit/sensors_3d.yaml +++ /dev/null @@ -1,25 +0,0 @@ -sensors: - - scene_scan_camera -scene_scan_camera: - # The name of the Octomap updater plugin that we are using. - sensor_plugin: "moveit_studio_plugins/PointCloudServiceOctomapUpdater" - # Specifies the topic to listen on for a point cloud. - # Set to an empty topic to disable. - point_cloud_service_name: "/point_cloud_service" - # Points further than this will not be used (in meters). - max_range: 1.5 - # Choose one of every 'point_subsample' points (select all if set to 1). - point_subsample: 1 - # Should always be >= 1.0. Scale up collision shapes in the scene before excluding them from the octomap. - padding_scale: 1.0 - # Absolute padding around scaled collision shapes when excluding them from the octomap (in meters). - padding_offset: 0.01 - # The octomap representation will be updated at rate less than or equal to this value. - max_update_rate: 0.1 - -# Specifies the resolution at which the octomap is maintained (in meters). -octomap_resolution: 0.01 -# Specifies the coordinate frame in which the Octomap representation will be stored. -# Note! When an OccupancyMonitor instance is initialized by the PlanningSceneMonitor, -# this frame parameter will not be used. Instead, the frame defaults to the planning frame. -octomap_frame: "base_link" diff --git a/src/arm_on_rail_sim/config/moveit/stomp_planning.yaml b/src/arm_on_rail_sim/config/moveit/stomp_planning.yaml deleted file mode 100644 index 7447a8ff..00000000 --- a/src/arm_on_rail_sim/config/moveit/stomp_planning.yaml +++ /dev/null @@ -1,21 +0,0 @@ -planning_plugins: - - stomp_moveit/StompPlanner -# The order of the elements in the adapter corresponds to the order they are processed by the motion planning pipeline. -request_adapters: - - default_planning_request_adapters/ResolveConstraintFrames - - default_planning_request_adapters/ValidateWorkspaceBounds - - default_planning_request_adapters/CheckStartStateBounds - - default_planning_request_adapters/CheckStartStateCollision -response_adapters: - - default_planning_response_adapters/AddTimeOptimalParameterization - - default_planning_response_adapters/ValidateSolution - -stomp_moveit: - num_timesteps: 60 - num_iterations: 40 - num_iterations_after_valid: 0 - num_rollouts: 30 - max_rollouts: 30 - exponentiated_cost_sensitivity: 0.8 - control_cost_weight: 0.1 - delta_t: 0.1 diff --git a/src/arm_on_rail_sim/config/moveit/trac_ik_kinematics_distance.yaml b/src/arm_on_rail_sim/config/moveit/trac_ik_kinematics_distance.yaml deleted file mode 100644 index 65f77d5c..00000000 --- a/src/arm_on_rail_sim/config/moveit/trac_ik_kinematics_distance.yaml +++ /dev/null @@ -1,6 +0,0 @@ -manipulator: - kinematics_solver: trac_ik_kinematics_plugin/TRAC_IKKinematicsPlugin - kinematics_solver_timeout: 0.005 - kinematics_solver_attempts: 3 - epsilon: 0.0001 - solve_type: "Distance" diff --git a/src/arm_on_rail_sim/config/moveit/trac_ik_kinematics_speed.yaml b/src/arm_on_rail_sim/config/moveit/trac_ik_kinematics_speed.yaml deleted file mode 100644 index 90559540..00000000 --- a/src/arm_on_rail_sim/config/moveit/trac_ik_kinematics_speed.yaml +++ /dev/null @@ -1,6 +0,0 @@ -manipulator: - kinematics_solver: trac_ik_kinematics_plugin/TRAC_IKKinematicsPlugin - kinematics_solver_timeout: 0.005 - kinematics_solver_attempts: 3 - epsilon: 0.0001 - solve_type: "Speed" diff --git a/src/arm_on_rail_sim/config/moveit/ur_servo.yaml b/src/arm_on_rail_sim/config/moveit/ur_servo.yaml deleted file mode 100644 index ecc69118..00000000 --- a/src/arm_on_rail_sim/config/moveit/ur_servo.yaml +++ /dev/null @@ -1,64 +0,0 @@ -############################################### -# Modify all parameters related to servoing here -############################################### - -# Enable dynamic parameter updates -enable_parameter_update: true - -## Properties of incoming commands -command_in_type: "speed_units" # "unitless"> in the range [-1:1], as if from joystick. "speed_units"> cmds are in m/s and rad/s -scale: - # Scale parameters are only used if command_in_type=="unitless" - linear: 2.0 # Max linear velocity. Meters per publish_period. Unit is [m/s]. Only used for Cartesian commands. - rotational: 3.0 # Max angular velocity. Rads per publish_period. Unit is [rad/s]. Only used for Cartesian commands. - # Max joint angular/linear velocity. Rads or Meters per publish period. Only used for joint commands on joint_command_in_topic. - joint: 2.0 - -# Default to driving the arm at 50% maximum speed. -override_velocity_scaling_factor: 0.5 - -## Properties of outgoing commands -publish_period: 0.01 # 1/Nominal publish rate [seconds] -max_expected_latency: 0.1 # delay between sending a command and the robot executing it [seconds] - -# What type of topic does your robot driver expect? -# Currently supported are std_msgs/Float64MultiArray or trajectory_msgs/JointTrajectory -command_out_type: trajectory_msgs/JointTrajectory - -# What to publish? Can save some bandwidth as most robots only require positions or velocities -publish_joint_positions: true -publish_joint_velocities: true -publish_joint_accelerations: false - -## Plugins for smoothing outgoing commands -use_smoothing: true -smoothing_filter_plugin_name: "online_signal_smoothing::AccelerationLimitedPlugin" -acceleration_filter_update_period: 0.01 # [seconds] Must match the publish_period parameter - -## MoveIt properties -move_group_name: manipulator # Often 'manipulator' or 'arm' -acceleration_filter_planning_group_name: manipulator # Often 'manipulator' or 'arm' -is_primary_planning_scene_monitor: false # The MoveGroup node maintains the planning scene, so Servo needs to get its world info from there. -monitored_planning_scene_topic: /monitored_planning_scene - -## Stopping behaviour -incoming_command_timeout: 0.1 # Stop servoing if X seconds elapse without a new command - -## Configure handling of singularities and joint limits -lower_singularity_threshold: 30.0 # Start decelerating when the condition number hits this (close to singularity) -hard_stop_singularity_threshold: 50.0 # Stop when the condition number hits this -joint_limit_margins: [0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] # added as a buffer to joint limits [radians]. If moving quickly, make this larger. - -## Topic names -cartesian_command_in_topic: ~/delta_twist_cmds # Topic for incoming Cartesian twist commands -joint_command_in_topic: ~/delta_joint_cmds # Topic for incoming joint angle commands -joint_topic: /joint_states -status_topic: ~/status # Publish status to this topic -command_out_topic: /servo_controller/joint_trajectory # Publish outgoing commands here - -## Collision checking for the entire robot body -check_collisions: true # Check collisions? -check_octomap_collisions: false # Check collisions with octomap? -collision_check_rate: 10.0 # [Hz] Collision-checking can easily bog down a CPU if done too often. -self_collision_proximity_threshold: 0.006 # Start decelerating when a self-collision is this far [m] -scene_collision_proximity_threshold: 0.02 # Start decelerating when a scene collision is this far [m] diff --git a/src/arm_on_rail_sim/description/LICENSE b/src/arm_on_rail_sim/description/LICENSE deleted file mode 100644 index f24e07cb..00000000 --- a/src/arm_on_rail_sim/description/LICENSE +++ /dev/null @@ -1,26 +0,0 @@ -Copyright 2018 ROS Industrial Consortium - -Redistribution and use in source and binary forms, with or without modification, -are permitted provided that the following conditions are met: - -1. Redistributions of source code must retain the above copyright notice, this -list of conditions and the following disclaimer. - -2. Redistributions in binary form must reproduce the above copyright notice, -this list of conditions and the following disclaimer in the documentation and/or -other materials provided with the distribution. - -3. Neither the name of the copyright holder nor the names of its contributors -may be used to endorse or promote products derived from this software without -specific prior written permission. - -THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND -ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED -WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE -DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR -ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES -(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; -LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON -ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT -(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS -SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. diff --git a/src/arm_on_rail_sim/description/lab_scene.xml b/src/arm_on_rail_sim/description/lab_scene.xml deleted file mode 100644 index 9e7726e7..00000000 --- a/src/arm_on_rail_sim/description/lab_scene.xml +++ /dev/null @@ -1,81 +0,0 @@ - - - - - - - - - diff --git a/src/arm_on_rail_sim/description/picknik_ur.xacro b/src/arm_on_rail_sim/description/picknik_ur.xacro deleted file mode 100644 index 9e9c5512..00000000 --- a/src/arm_on_rail_sim/description/picknik_ur.xacro +++ /dev/null @@ -1,1246 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - 1.047 - - 640 - 480 - RGB_INT8 - - - 0.1 - 5 - - - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 -
0.5 0.5
-
- - - 554.25469 - 554.25469 - 320.5 - 240.5 - 0 - - - - 554.25469 - 554.25469 - 320.5 - 240.5 - 0 - 0 - - - - gaussian - 0 - 0.00 - - - - 0.25 - 5 - - - - wrist_mounted_camera_color_optical_frame - -
- wrist_mounted_camera_color_frame - 1 - 6 - false - wrist_mounted_camera - false -
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - 100000.0 - 100000.0 - - - - - 1e+5 - 1 - 0 - 0.2 - 0.002 - 0 - - - - - - - - - - - - - - - - - - - - - - - - 100000.0 - 100000.0 - - - - - 1e+5 - 1 - 0 - 0.2 - 0.002 - 0 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - picknik_mujoco_ros/MujocoSystem - $(arg mujoco_model) - arm_on_rail_sim - 10 - 60 - 10 - - -
diff --git a/src/arm_on_rail_sim/description/scene.xml b/src/arm_on_rail_sim/description/scene.xml deleted file mode 100644 index f0bcdcfe..00000000 --- a/src/arm_on_rail_sim/description/scene.xml +++ /dev/null @@ -1,83 +0,0 @@ - - - - - - - - - diff --git a/src/arm_on_rail_sim/launch/agent_bridge.launch.xml b/src/arm_on_rail_sim/launch/agent_bridge.launch.xml deleted file mode 100644 index b2aa7543..00000000 --- a/src/arm_on_rail_sim/launch/agent_bridge.launch.xml +++ /dev/null @@ -1,6 +0,0 @@ - - - - diff --git a/src/arm_on_rail_sim/objectives/3_waypoint_pick_and_place.xml b/src/arm_on_rail_sim/objectives/3_waypoint_pick_and_place.xml deleted file mode 100644 index d04d5927..00000000 --- a/src/arm_on_rail_sim/objectives/3_waypoint_pick_and_place.xml +++ /dev/null @@ -1,122 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/arm_on_rail_sim/objectives/apriltag_detection_config.yaml b/src/arm_on_rail_sim/objectives/apriltag_detection_config.yaml deleted file mode 100644 index f1a96237..00000000 --- a/src/arm_on_rail_sim/objectives/apriltag_detection_config.yaml +++ /dev/null @@ -1,9 +0,0 @@ -DetectAprilTags: - apriltag_family_name: 36h11 - apriltag_size: 0.04 - max_hamming: 0 - n_threads: 1 - quad_decimate: 1 - quad_sigma: 0.1 - refine_edges: false - z_up: false diff --git a/src/arm_on_rail_sim/objectives/apriltag_pick_object.xml b/src/arm_on_rail_sim/objectives/apriltag_pick_object.xml deleted file mode 100644 index b9a35cc5..00000000 --- a/src/arm_on_rail_sim/objectives/apriltag_pick_object.xml +++ /dev/null @@ -1,72 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/arm_on_rail_sim/objectives/constrained_pick_place.xml b/src/arm_on_rail_sim/objectives/constrained_pick_place.xml deleted file mode 100644 index 52b0b1bc..00000000 --- a/src/arm_on_rail_sim/objectives/constrained_pick_place.xml +++ /dev/null @@ -1,151 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/arm_on_rail_sim/objectives/cycle_between_waypoints.xml b/src/arm_on_rail_sim/objectives/cycle_between_waypoints.xml deleted file mode 100644 index 450bc7a2..00000000 --- a/src/arm_on_rail_sim/objectives/cycle_between_waypoints.xml +++ /dev/null @@ -1,28 +0,0 @@ - - - - - - - - - - diff --git a/src/arm_on_rail_sim/objectives/force_relaxation.xml b/src/arm_on_rail_sim/objectives/force_relaxation.xml deleted file mode 100644 index a62429fe..00000000 --- a/src/arm_on_rail_sim/objectives/force_relaxation.xml +++ /dev/null @@ -1,55 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/arm_on_rail_sim/objectives/joint_diagnostic.xml b/src/arm_on_rail_sim/objectives/joint_diagnostic.xml deleted file mode 100644 index 01fb1984..00000000 --- a/src/arm_on_rail_sim/objectives/joint_diagnostic.xml +++ /dev/null @@ -1,38 +0,0 @@ - - - - - - - - - - - - - - - - diff --git a/src/arm_on_rail_sim/objectives/load_mesh_as_green_poincloud.xml b/src/arm_on_rail_sim/objectives/load_mesh_as_green_poincloud.xml deleted file mode 100644 index 8c84c48d..00000000 --- a/src/arm_on_rail_sim/objectives/load_mesh_as_green_poincloud.xml +++ /dev/null @@ -1,36 +0,0 @@ - - - - - - - - - - - - - - - - - - diff --git a/src/arm_on_rail_sim/objectives/load_mesh_as_red_pointcloud.xml b/src/arm_on_rail_sim/objectives/load_mesh_as_red_pointcloud.xml deleted file mode 100644 index 15161b30..00000000 --- a/src/arm_on_rail_sim/objectives/load_mesh_as_red_pointcloud.xml +++ /dev/null @@ -1,36 +0,0 @@ - - - - - - - - - - - - - - - - - - diff --git a/src/arm_on_rail_sim/objectives/look_at_table.xml b/src/arm_on_rail_sim/objectives/look_at_table.xml deleted file mode 100644 index 3c2d2b2b..00000000 --- a/src/arm_on_rail_sim/objectives/look_at_table.xml +++ /dev/null @@ -1,16 +0,0 @@ - - - - - - - - - diff --git a/src/arm_on_rail_sim/objectives/move_with_velocity_and_force.xml b/src/arm_on_rail_sim/objectives/move_with_velocity_and_force.xml deleted file mode 100644 index 730841b1..00000000 --- a/src/arm_on_rail_sim/objectives/move_with_velocity_and_force.xml +++ /dev/null @@ -1,76 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - diff --git a/src/arm_on_rail_sim/objectives/my_constraints.yaml b/src/arm_on_rail_sim/objectives/my_constraints.yaml deleted file mode 100644 index 36deb8b7..00000000 --- a/src/arm_on_rail_sim/objectives/my_constraints.yaml +++ /dev/null @@ -1,11 +0,0 @@ -AppendOrientationConstraint: - constraint_frame: "world" - link_frame: "grasp_link" - orientation: # radians - x: -3.14 - y: 0.0 - z: -1.57 - tolerance: # radians - x: 0.2 - y: 0.2 - z: 10.0 diff --git a/src/arm_on_rail_sim/objectives/pick_april_tag_object_with_approval.xml b/src/arm_on_rail_sim/objectives/pick_april_tag_object_with_approval.xml deleted file mode 100644 index ba547d46..00000000 --- a/src/arm_on_rail_sim/objectives/pick_april_tag_object_with_approval.xml +++ /dev/null @@ -1,53 +0,0 @@ - - - - - - - - - - - - - - - - - - - - diff --git a/src/arm_on_rail_sim/objectives/pick_first_object_in_vector.xml b/src/arm_on_rail_sim/objectives/pick_first_object_in_vector.xml deleted file mode 100644 index 30bd2bf4..00000000 --- a/src/arm_on_rail_sim/objectives/pick_first_object_in_vector.xml +++ /dev/null @@ -1,48 +0,0 @@ - - - - - - - - - - - - - - - - - - - - diff --git a/src/arm_on_rail_sim/objectives/pick_object.xml b/src/arm_on_rail_sim/objectives/pick_object.xml deleted file mode 100644 index 66dcbacd..00000000 --- a/src/arm_on_rail_sim/objectives/pick_object.xml +++ /dev/null @@ -1,32 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/src/arm_on_rail_sim/objectives/pick_object_config.yaml b/src/arm_on_rail_sim/objectives/pick_object_config.yaml deleted file mode 100644 index 6fe0ef81..00000000 --- a/src/arm_on_rail_sim/objectives/pick_object_config.yaml +++ /dev/null @@ -1,9 +0,0 @@ -SetupMTCPickObject: - approach_distance: 0.05 - arm_group_name: manipulator - end_effector_closed_pose_name: close - end_effector_group_name: gripper - end_effector_name: moveit_ee - hand_frame_name: grasp_link - lift_distance: 0.05 - world_frame_name: world diff --git a/src/arm_on_rail_sim/objectives/pick_up_cube.xml b/src/arm_on_rail_sim/objectives/pick_up_cube.xml deleted file mode 100644 index 73484566..00000000 --- a/src/arm_on_rail_sim/objectives/pick_up_cube.xml +++ /dev/null @@ -1,13 +0,0 @@ - - - - - - - - - - - - - diff --git a/src/arm_on_rail_sim/objectives/place_first_object_in_vector.xml b/src/arm_on_rail_sim/objectives/place_first_object_in_vector.xml deleted file mode 100644 index 0e058131..00000000 --- a/src/arm_on_rail_sim/objectives/place_first_object_in_vector.xml +++ /dev/null @@ -1,45 +0,0 @@ - - - - - - - - - - - - - - - - - diff --git a/src/arm_on_rail_sim/objectives/place_object.xml b/src/arm_on_rail_sim/objectives/place_object.xml deleted file mode 100644 index 77d88884..00000000 --- a/src/arm_on_rail_sim/objectives/place_object.xml +++ /dev/null @@ -1,30 +0,0 @@ - - - - - - - - - - - - - - - - - - diff --git a/src/arm_on_rail_sim/objectives/place_object_config.yaml b/src/arm_on_rail_sim/objectives/place_object_config.yaml deleted file mode 100644 index a8ec6f8a..00000000 --- a/src/arm_on_rail_sim/objectives/place_object_config.yaml +++ /dev/null @@ -1,11 +0,0 @@ -SetupMTCPickObject: - # The lift vector points to the direction of the positive z-axis of the frame marked as the world frame. - world_frame_name: "world" - arm_group_name: "manipulator" - end_effector_group_name: "gripper" - end_effector_name: "moveit_ee" - hand_frame_name: "grasp_link" - end_effector_closed_pose_name: "open" - - approach_distance: 0.05 - lift_distance: 0.05 diff --git a/src/arm_on_rail_sim/objectives/register_cad_part.xml b/src/arm_on_rail_sim/objectives/register_cad_part.xml deleted file mode 100644 index 07a10784..00000000 --- a/src/arm_on_rail_sim/objectives/register_cad_part.xml +++ /dev/null @@ -1,56 +0,0 @@ - - - - - - - - - - - - - - - - - - - - diff --git a/src/arm_on_rail_sim/objectives/take_snap.xml b/src/arm_on_rail_sim/objectives/take_snap.xml deleted file mode 100644 index 7fefe4db..00000000 --- a/src/arm_on_rail_sim/objectives/take_snap.xml +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/src/arm_on_rail_sim/objectives/wrist_snap.xml b/src/arm_on_rail_sim/objectives/wrist_snap.xml deleted file mode 100644 index 80209f36..00000000 --- a/src/arm_on_rail_sim/objectives/wrist_snap.xml +++ /dev/null @@ -1,14 +0,0 @@ - - - - - - - - - - - - - - diff --git a/src/arm_on_rail_sim/package.xml b/src/arm_on_rail_sim/package.xml deleted file mode 100644 index f0769f30..00000000 --- a/src/arm_on_rail_sim/package.xml +++ /dev/null @@ -1,46 +0,0 @@ - - - arm_on_rail_sim - 6.0.0 - - - MuJoCo simulation configuration package for Picknik's UR robot on a linear - rail - - - MoveIt Pro Maintainer - - BSD-3-Clause - - ament_cmake - - admittance_controller - moveit_planners_stomp - moveit_ros_perception - moveit_studio_agent - moveit_studio_behavior - moveit_studio_ur_pstop_manager - picknik_accessories - realsense2_camera - realsense2_description - robotiq_description - robotiq_controllers - trac_ik_kinematics_plugin - ur_description - ur_robot_driver - picknik_mujoco_ros - velocity_force_controller - - ament_lint_auto - - ament_clang_format - ament_clang_tidy - ament_cmake_copyright - ament_cmake_lint_cmake - picknik_ament_copyright - ament_flake8 - - - ament_cmake - - diff --git a/src/arm_on_rail_sim/waypoints/ur_waypoints.yaml b/src/arm_on_rail_sim/waypoints/ur_waypoints.yaml deleted file mode 100644 index 0fd27077..00000000 --- a/src/arm_on_rail_sim/waypoints/ur_waypoints.yaml +++ /dev/null @@ -1,344 +0,0 @@ -- description: '' - favorite: false - joint_group_names: - - gripper - - linear_actuator - - manipulator - joint_state: - effort: [] - header: - frame_id: '' - stamp: - nanosec: 0 - sec: 0 - name: - - robotiq_85_left_knuckle_joint - - linear_rail_joint - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - position: - - 0.06656710337674145 - - 0.1162925924535442 - - 0.2054240147028693 - - -0.987070953194143 - - 1.3146849599773849 - - -1.8698622612624394 - - -1.5707050706852668 - - 0.20529114323213696 - velocity: [] - multi_dof_joint_state: - header: - frame_id: '' - stamp: - nanosec: 0 - sec: 0 - joint_names: [] - transforms: [] - twist: [] - wrench: [] - name: Above Place Cube -- description: '' - favorite: false - joint_group_names: - - gripper - - linear_actuator - - manipulator - joint_state: - effort: [] - header: - frame_id: '' - stamp: - nanosec: 0 - sec: 0 - name: - - robotiq_85_left_knuckle_joint - - linear_rail_joint - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - position: - - 0.06656709575770764 - - 0.2544520984236789 - - 0.00297097958947393 - - -0.5454836524482858 - - 1.028930149174636 - - -2.02088483587436 - - -1.5709145918870968 - - 0.002734726536987722 - velocity: [] - multi_dof_joint_state: - header: - frame_id: '' - stamp: - nanosec: 0 - sec: 0 - joint_names: [] - transforms: [] - twist: [] - wrench: [] - name: Pick Cube -- description: '' - favorite: false - joint_group_names: - - gripper - - linear_actuator - - manipulator - joint_state: - effort: [] - header: - frame_id: '' - stamp: - nanosec: 0 - sec: 0 - name: - - robotiq_85_left_knuckle_joint - - linear_rail_joint - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - position: - - 0.06656709465883658 - - 0.31742962464478663 - - -0.07518824419393247 - - -0.7207568718596512 - - 0.8665668564352057 - - -1.6837956156664982 - - -1.5707507158288945 - - -0.07517349313281775 - velocity: [] - multi_dof_joint_state: - header: - frame_id: '' - stamp: - nanosec: 0 - sec: 0 - joint_names: [] - transforms: [] - twist: [] - wrench: [] - name: Above Pick Cube -- description: '' - favorite: false - joint_group_names: - - gripper - - linear_actuator - - manipulator - joint_state: - effort: [] - header: - frame_id: '' - stamp: - nanosec: 0 - sec: 0 - name: - - robotiq_85_left_knuckle_joint - - linear_rail_joint - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - position: - - 0.36093425387337075 - - 0.3468469487674742 - - -0.08122232656648681 - - -1.1118986430431266 - - 0.7735698103006698 - - -1.2414135949062157 - - -1.5575126426436692 - - -0.0803135811027271 - velocity: [] - multi_dof_joint_state: - header: - frame_id: '' - stamp: - nanosec: 0 - sec: 0 - joint_names: [] - transforms: [] - twist: [] - wrench: [] - name: Look at Table -- description: '' - favorite: false - joint_group_names: - - gripper - - linear_actuator - - manipulator - joint_state: - effort: [] - header: - frame_id: '' - stamp: - nanosec: 0 - sec: 0 - name: - - robotiq_85_left_knuckle_joint - - linear_rail_joint - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - position: - - 0.36093425387337075 - - 0.3468469487674742 - - -0.08122232656648681 - - -1.1118986430431266 - - 0.7735698103006698 - - -1.2414135949062157 - - -3.14 - - -0.0803135811027271 - velocity: [] - multi_dof_joint_state: - header: - frame_id: '' - stamp: - nanosec: 0 - sec: 0 - joint_names: [] - transforms: [] - twist: [] - wrench: [] - name: Wrist 2 Min -- description: '' - favorite: false - joint_group_names: - - gripper - - linear_actuator - - manipulator - joint_state: - effort: [] - header: - frame_id: '' - stamp: - nanosec: 0 - sec: 0 - name: - - robotiq_85_left_knuckle_joint - - linear_rail_joint - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - position: - - 0.06656710453529632 - - -0.026311129005491703 - - 0.391188076851874 - - -0.6421557305136849 - - 1.2200227002982904 - - -2.1172063445999307 - - -1.5707036597762196 - - 0.39119709035689026 - velocity: [] - multi_dof_joint_state: - header: - frame_id: '' - stamp: - nanosec: 0 - sec: 0 - joint_names: [] - transforms: [] - twist: [] - wrench: [] - name: Place Cube -- description: '' - favorite: false - joint_group_names: - - gripper - - linear_actuator - - manipulator - joint_state: - effort: [] - header: - frame_id: '' - stamp: - nanosec: 0 - sec: 0 - name: - - robotiq_85_left_knuckle_joint - - linear_rail_joint - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - position: - - 0.02639307417885356 - - -0.0368978637919646 - - -0.05133733759107817 - - -1.0646673321083444 - - 1.6085719305391477 - - -2.116413476868559 - - -1.5570186007251205 - - -0.04927977068008667 - velocity: [] - multi_dof_joint_state: - header: - frame_id: '' - stamp: - nanosec: 0 - sec: 0 - joint_names: [] - transforms: [] - twist: [] - wrench: [] - name: VFC Start -- description: '' - favorite: false - joint_group_names: - - gripper - - linear_actuator - - manipulator - joint_state: - effort: [] - header: - frame_id: '' - stamp: - nanosec: 0 - sec: 0 - name: - - robotiq_85_left_knuckle_joint - - linear_rail_joint - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - position: - - 0.36093425387337075 - - 0.3468469487674742 - - -0.08122232656648681 - - -1.1118986430431266 - - 0.7735698103006698 - - -1.2414135949062157 - - 3.14 - - -0.0803135811027271 - velocity: [] - multi_dof_joint_state: - header: - frame_id: '' - stamp: - nanosec: 0 - sec: 0 - joint_names: [] - transforms: [] - twist: [] - wrench: [] - name: Wrist 2 Max diff --git a/src/lab_sim/config/config.yaml b/src/lab_sim/config/config.yaml index d302c077..18461a71 100644 --- a/src/lab_sim/config/config.yaml +++ b/src/lab_sim/config/config.yaml @@ -3,7 +3,7 @@ # # Name of the package to specialize -based_on_package: "arm_on_rail_sim" +based_on_package: "picknik_ur_sim_config" hardware: robot_description: urdf_params: diff --git a/src/picknik_ur_base_config/CMakeLists.txt b/src/picknik_ur_base_config/CMakeLists.txt deleted file mode 100644 index 10699021..00000000 --- a/src/picknik_ur_base_config/CMakeLists.txt +++ /dev/null @@ -1,22 +0,0 @@ -cmake_minimum_required(VERSION 3.22) -project(picknik_ur_base_config) - -find_package(ament_cmake REQUIRED) - -install( - DIRECTORY - config - description - launch - objectives - waypoints - DESTINATION - share/${PROJECT_NAME} -) - -if(BUILD_TESTING) - find_package(ament_lint_auto REQUIRED) - ament_lint_auto_find_test_dependencies() -endif() - -ament_package() diff --git a/src/picknik_ur_base_config/LICENSE b/src/picknik_ur_base_config/LICENSE deleted file mode 100644 index 574ef079..00000000 --- a/src/picknik_ur_base_config/LICENSE +++ /dev/null @@ -1,25 +0,0 @@ -Redistribution and use in source and binary forms, with or without -modification, are permitted provided that the following conditions are met: - - * Redistributions of source code must retain the above copyright - notice, this list of conditions and the following disclaimer. - - * Redistributions in binary form must reproduce the above copyright - notice, this list of conditions and the following disclaimer in the - documentation and/or other materials provided with the distribution. - - * Neither the name of the copyright holder nor the names of its - contributors may be used to endorse or promote products derived from - this software without specific prior written permission. - -THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -POSSIBILITY OF SUCH DAMAGE. diff --git a/src/picknik_ur_base_config/README.md b/src/picknik_ur_base_config/README.md deleted file mode 100644 index e541275b..00000000 --- a/src/picknik_ur_base_config/README.md +++ /dev/null @@ -1,5 +0,0 @@ -# picknik_ur_base_config - -A MoveIt Pro base configuration for PickNik's Universal Robots (UR) arms. - -For detailed documentation see: [MoveIt Pro Documentation](https://docs.picknik.ai/) diff --git a/src/picknik_ur_base_config/config/config.yaml b/src/picknik_ur_base_config/config/config.yaml deleted file mode 100644 index 5d09c7c9..00000000 --- a/src/picknik_ur_base_config/config/config.yaml +++ /dev/null @@ -1,190 +0,0 @@ -############################################################### -# -# This configures the robot to work with MoveIt Pro -# -############################################################### - -# Baseline hardware configuration parameters for MoveIt Pro. -# [Required] -hardware: - # Set simulated to false if you are using this as a configuration for real hardware. - # This allows users to switch between mock and real hardware by changing a single parameter with config inheritance. - # [Required] - simulated: true - - # If the MoveIt Pro Agent should launch the ros2 controller node. - # [Optional, default=True] - launch_control_node: True - - # If the MoveIt Pro Agent should launch the robot state publisher. - # This should be false if you are launching the robot state publisher as part of drivers. - # [Optional, default=True] - launch_robot_state_publisher: True - - # Specify additional launch files for running the robot with real hardware. - # [Optional, defaults to a blank launch file if not specified] - robot_driver_persist_launch_file: - package: "picknik_ur_base_config" - path: "launch/robot_drivers_to_persist.launch.py" - - # Specify any additional launch files for running the robot in simulation mode. - # Used when hardware.simulated is True. - # [Optional, defaults to a blank launch file if not specified] - simulated_robot_driver_persist_launch_file: - package: "picknik_ur_base_config" - path: "launch/sim/robot_drivers_to_persist_sim.launch.py" - simulated_hardware_launch_file: - package: "moveit_studio_agent" - path: "launch/blank.launch.py" - - # Parameters used to configure the robot description through XACRO. - # A URDF and SRDF are both required. - # [Required] - robot_description: - urdf: - package: "picknik_ur_base_config" - path: "description/picknik_ur.xacro" - srdf: - package: "picknik_ur_base_config" - path: "config/moveit/picknik_ur.srdf" - # Specify any additional parameters required for the URDF. - # Many of these are specific to the UR descriptions packages, and can be customized as needed. - # [Optional] - urdf_params: - - name: "ur5e" - - prefix: "" - - use_fake_hardware: "true" - - use_pinch_links: "true" - - mock_sensor_commands: "false" - - headless_mode: "true" - - robot_ip: "0.0.0.0" - - joint_limits_parameters_file: - package: "picknik_ur_base_config" - path: "config/moveit/joint_limits.yaml" - # The following files are loaded based on the ur_description package layout. - # To use parameters from a different package, place them in a config/ROBOT_NAME/ directory, - # replace ROBOT_NAME with the value used for hardware.type in this file. - - kinematics_parameters_file: - # Load default_kinematics.yaml from ur_description/config/ - package: "ur_description" - path: "config/ur5e/default_kinematics.yaml" - - physical_parameters_file: - # Load physical_parameters.yaml from ur_description/config/ - package: "ur_description" - path: "config/ur5e/physical_parameters.yaml" - - visual_parameters_file: - # Load visual_parameters.yaml from ur_description/config/ - package: "ur_description" - path: "config/ur5e/visual_parameters.yaml" - -# Sets ROS global params for launch. -# [Optional] -ros_global_params: - # Whether or not to use simulated time. - # [Optional, default=False] - use_sim_time: False - -# Configuration files for MoveIt. -# For more information, refer to https://moveit.picknik.ai/main/doc/how_to_guides/moveit_configuration/moveit_configuration_tutorial.html -# [Required] -moveit_params: - # Used by the Waypoint Manager to save joint states from this joint group. - joint_group_name: "manipulator" - - ompl_planning: - package: "picknik_ur_base_config" - path: "config/moveit/ompl_planning.yaml" - stomp_planning: - package: "picknik_ur_base_config" - path: "config/moveit/stomp_planning.yaml" - pilz_planning: - package: "picknik_ur_base_config" - path: "config/moveit/pilz_industrial_motion_planner_planning.yaml" - kinematics: - package: "picknik_ur_base_config" - path: "config/moveit/trac_ik_kinematics_distance.yaml" - servo: - package: "picknik_ur_base_config" - path: "config/moveit/ur_servo.yaml" - sensors_3d: - package: "picknik_ur_base_config" - path: "config/moveit/sensors_3d.yaml" - servo_kinematics: - package: "picknik_ur_base_config" - path: "config/moveit/trac_ik_kinematics_speed.yaml" - joint_limits: - package: "picknik_ur_base_config" - path: "config/moveit/joint_limits.yaml" - servo_joint_limits: - package: "picknik_ur_base_config" - path: "config/moveit/hard_joint_limits.yaml" - pilz_cartesian_limits: - package: "picknik_ur_base_config" - path: "config/moveit/pilz_cartesian_limits.yaml" - - publish: - planning_scene: True - geometry_updates: True - state_updates: True - transforms_updates: True - - trajectory_execution: - manage_controllers: True - allowed_execution_duration_scaling: 2.0 - allowed_goal_duration_margin: 5.0 - allowed_start_tolerance: 0.01 - -# Configuration for launching ros2_control processes. -# [Required, if using ros2_control] -ros2_control: - config: - package: "picknik_ur_base_config" - path: "config/control/picknik_ur.ros2_control.yaml" - # MoveIt Pro will load and activate these controllers at start up to ensure they are available. - # If not specified, it is up to the user to ensure the appropriate controllers are active and available - # for running the application. - # [Optional, default=[]] - controllers_active_at_startup: - - "force_torque_sensor_broadcaster" - - "robotiq_gripper_controller" - - "joint_state_broadcaster" - - "servo_controller" - - "io_and_status_controller" - - "robotiq_activation_controller" - # Load but do not start these controllers so they can be activated later if needed. - # [Optional, default=[]] - controllers_inactive_at_startup: - - "joint_trajectory_controller" - - "joint_trajectory_admittance_controller" - - "velocity_force_controller" - # Any controllers here will not be spawned by MoveIt Pro. - # [Optional, default=[]] - controllers_not_managed: [] - # Optionally configure remapping rules to let multiple controllers receive commands on the same topic. - # [Optional, default=[]] - controller_shared_topics: [] - -# Configuration for loading behaviors and objectives. -# [Required] -objectives: - # List of plugins for loading custom behaviors. - # [Required] - behavior_loader_plugins: - # This plugin will load the core MoveIt Pro Behaviors. - # Add additional plugin loaders as needed. - core: - - "moveit_studio::behaviors::CoreBehaviorsLoader" - - "moveit_studio::behaviors::MTCCoreBehaviorsLoader" - - "moveit_studio::behaviors::ServoBehaviorsLoader" - - "moveit_studio::behaviors::VisionBehaviorsLoader" - # Specify source folder for objectives - # [Required] - objective_library_paths: - core: - package_name: "picknik_ur_base_config" - relative_path: "objectives" - # Specify the location of the saved waypoints file. - # [Required] - waypoints_file: - package_name: "picknik_ur_base_config" - relative_path: "waypoints/ur_waypoints.yaml" diff --git a/src/picknik_ur_base_config/config/control/picknik_ur.ros2_control.yaml b/src/picknik_ur_base_config/config/control/picknik_ur.ros2_control.yaml deleted file mode 100644 index 17851768..00000000 --- a/src/picknik_ur_base_config/config/control/picknik_ur.ros2_control.yaml +++ /dev/null @@ -1,194 +0,0 @@ -controller_manager: - ros__parameters: - update_rate: 600 # Hz - joint_state_broadcaster: - type: joint_state_broadcaster/JointStateBroadcaster - io_and_status_controller: - type: ur_controllers/GPIOController - force_torque_sensor_broadcaster: - type: force_torque_sensor_broadcaster/ForceTorqueSensorBroadcaster - joint_trajectory_controller: - type: joint_trajectory_controller/JointTrajectoryController - robotiq_gripper_controller: - type: position_controllers/GripperActionController - robotiq_activation_controller: - type: robotiq_controllers/RobotiqActivationController - servo_controller: - type: joint_trajectory_controller/JointTrajectoryController - joint_trajectory_admittance_controller: - type: joint_trajectory_admittance_controller/JointTrajectoryAdmittanceController - velocity_force_controller: - type: velocity_force_controller/VelocityForceController - -io_and_status_controller: - ros__parameters: - tf_prefix: "" - -force_torque_sensor_broadcaster: - ros__parameters: - sensor_name: tcp_fts_sensor - state_interface_names: - - force.x - - force.y - - force.z - - torque.x - - torque.y - - torque.z - frame_id: tool0 - topic_name: ft_data - -joint_trajectory_controller: - ros__parameters: - joints: - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - command_interfaces: - - position - state_interfaces: - - position - - velocity - command_joints: - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - state_publish_rate: 100.0 - action_monitor_rate: 20.0 - allow_partial_joints_goal: false - constraints: - stopped_velocity_tolerance: 0.0 - goal_time: 0.0 - shoulder_pan_joint: - goal: 0.05 - shoulder_lift_joint: - goal: 0.05 - elbow_joint: - goal: 0.05 - wrist_1_joint: - goal: 0.05 - wrist_2_joint: - goal: 0.05 - wrist_3_joint: - goal: 0.05 - -servo_controller: - ros__parameters: - joints: - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - command_interfaces: - - position - state_interfaces: - - position - - velocity - command_joints: - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - state_publish_rate: 100.0 - action_monitor_rate: 20.0 - allow_partial_joints_goal: false - constraints: - stopped_velocity_tolerance: 0.0 - goal_time: 0.0 - shoulder_pan_joint: - goal: 0.05 - shoulder_lift_joint: - goal: 0.05 - elbow_joint: - goal: 0.05 - wrist_1_joint: - goal: 0.05 - wrist_2_joint: - goal: 0.05 - wrist_3_joint: - goal: 0.05 - -robotiq_gripper_controller: - ros__parameters: - default: true - joint: robotiq_85_left_knuckle_joint - allow_stalling: true - -robotiq_activation_controller: - ros__parameters: - default: true - -joint_trajectory_admittance_controller: - ros__parameters: - joints: - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - base_frame: base_link - sensor_frame: tool0 - ee_frame: grasp_link - ft_sensor_name: tcp_fts_sensor - # Joint accelerations chosen to match MoveIt configs. - stop_accelerations: - - 30.0 - - 30.0 - - 30.0 - - 30.0 - - 30.0 - - 30.0 - -velocity_force_controller: - ros__parameters: - joints: - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - base_frame: base_link - sensor_frame: tool0 - ee_frame: grasp_link - ft_sensor_name: tcp_fts_sensor - ft_force_deadband: 2.0 - ft_torque_deadband: 1.0 - max_joint_velocity: - - 0.524 - - 0.524 - - 0.524 - - 1.047 - - 1.047 - - 1.047 - max_joint_acceleration: - - 52.4 - - 52.4 - - 52.4 - - 52.4 - - 52.4 - - 52.4 - max_cartesian_velocity: - - 0.25 - - 0.25 - - 0.25 - - 1.5707 - - 1.5707 - - 1.5707 - max_cartesian_acceleration: - - 20.0 - - 20.0 - - 20.0 - - 40.0 - - 40.0 - - 40.0 diff --git a/src/picknik_ur_base_config/config/initial_positions.yaml b/src/picknik_ur_base_config/config/initial_positions.yaml deleted file mode 100644 index 0d8b33f7..00000000 --- a/src/picknik_ur_base_config/config/initial_positions.yaml +++ /dev/null @@ -1,6 +0,0 @@ -shoulder_pan_joint: 0.0 -shoulder_lift_joint: -1.41 -elbow_joint: -0.7 -wrist_1_joint: -2.12 -wrist_2_joint: 1.67 -wrist_3_joint: 0.0 diff --git a/src/picknik_ur_base_config/config/moveit/bioik_kinematics.yaml b/src/picknik_ur_base_config/config/moveit/bioik_kinematics.yaml deleted file mode 100644 index 4ffbf687..00000000 --- a/src/picknik_ur_base_config/config/moveit/bioik_kinematics.yaml +++ /dev/null @@ -1,8 +0,0 @@ -manipulator: - kinematics_solver: bio_ik/BioIKKinematicsPlugin - kinematics_solver_search_resolution: 0.005 - kinematics_solver_timeout: 0.005 - kinematics_solver_attempts: 3 - mode: gd_c - dpos: 0.0001 - drot: 0.0001 diff --git a/src/picknik_ur_base_config/config/moveit/hard_joint_limits.yaml b/src/picknik_ur_base_config/config/moveit/hard_joint_limits.yaml deleted file mode 100644 index 9afb8143..00000000 --- a/src/picknik_ur_base_config/config/moveit/hard_joint_limits.yaml +++ /dev/null @@ -1,87 +0,0 @@ -# Joints limits -# -# Sources: -# -# - Universal Robots e-Series, User Manual, UR5e, Version 5.8 -# https://s3-eu-west-1.amazonaws.com/ur-support-site/69091/99404_UR5e_User_Manual_en_Global.pdf -# - Support > Articles > UR articles > Max. joint torques -# https://www.universal-robots.com/articles/ur-articles/max-joint-torques -# retrieved: 2020-06-16, last modified: 2020-06-09 -# -# NOTE: Acceleration limits are not publicly available so we have picked a reasonable upper limit -joint_limits: - shoulder_pan_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 90.0 - max_effort: 150.0 - max_position: !degrees 180.0 - max_velocity: !degrees 30.0 - min_position: !degrees -180.0 - shoulder_lift_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 90.0 - max_effort: 150.0 - max_position: !degrees 90.0 - max_velocity: !degrees 30.0 - min_position: !degrees -270.0 - elbow_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 90.0 - max_effort: 150.0 - # we artificially limit this joint to half its actual joint position limit - # to avoid (MoveIt/OMPL) planning problems, as due to the physical - # construction of the robot, it's impossible to rotate the 'elbow_joint' - # over more than approx +- 1 pi (the shoulder lift joint gets in the way). - # - # This leads to planning problems as the search space will be divided into - # two sections, with no connections from one to the other. - # - # Refer to https://github.com/ros-industrial/universal_robot/issues/265 for - # more information. - max_position: !degrees 180.0 - max_velocity: !degrees 30.0 - min_position: !degrees -180.0 - wrist_1_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 90.0 - max_effort: 28.0 - max_position: !degrees 180.0 - max_velocity: !degrees 60.0 - min_position: !degrees -180.0 - wrist_2_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 180.0 - max_effort: 28.0 - max_position: !degrees 180.0 - max_velocity: !degrees 60.0 - min_position: !degrees -180.0 - wrist_3_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 180.0 - max_effort: 28.0 - max_position: !degrees 360.0 - max_velocity: !degrees 60.0 - min_position: !degrees -360.0 - robotiq_85_left_knuckle_joint: - has_velocity_limits: true - max_velocity: 0.5 - has_acceleration_limits: true - max_acceleration: 1.0 diff --git a/src/picknik_ur_base_config/config/moveit/joint_limits.yaml b/src/picknik_ur_base_config/config/moveit/joint_limits.yaml deleted file mode 100644 index e80edbda..00000000 --- a/src/picknik_ur_base_config/config/moveit/joint_limits.yaml +++ /dev/null @@ -1,87 +0,0 @@ -# Joints limits -# -# Sources: -# -# - Universal Robots e-Series, User Manual, UR5e, Version 5.8 -# https://s3-eu-west-1.amazonaws.com/ur-support-site/69091/99404_UR5e_User_Manual_en_Global.pdf -# - Support > Articles > UR articles > Max. joint torques -# https://www.universal-robots.com/articles/ur-articles/max-joint-torques -# retrieved: 2020-06-16, last modified: 2020-06-09 -# -# NOTE: Acceleration limits are not publicly available so we have picked a reasonable upper limit -joint_limits: - shoulder_pan_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 30.0 - max_effort: 150.0 - max_position: !degrees 180.0 - max_velocity: !degrees 30.0 - min_position: !degrees -180.0 - shoulder_lift_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 30.0 - max_effort: 150.0 - max_position: !degrees 90.0 - max_velocity: !degrees 30.0 - min_position: !degrees -270.0 - elbow_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 30.0 - max_effort: 150.0 - # we artificially limit this joint to half its actual joint position limit - # to avoid (MoveIt/OMPL) planning problems, as due to the physical - # construction of the robot, it's impossible to rotate the 'elbow_joint' - # over more than approx +- 1 pi (the shoulder lift joint gets in the way). - # - # This leads to planning problems as the search space will be divided into - # two sections, with no connections from one to the other. - # - # Refer to https://github.com/ros-industrial/universal_robot/issues/265 for - # more information. - max_position: !degrees 180.0 - max_velocity: !degrees 30.0 - min_position: !degrees -180.0 - wrist_1_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 30.0 - max_effort: 28.0 - max_position: !degrees 180.0 - max_velocity: !degrees 60.0 - min_position: !degrees -180.0 - wrist_2_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 30.0 - max_effort: 28.0 - max_position: !degrees 180.0 - max_velocity: !degrees 60.0 - min_position: !degrees -180.0 - wrist_3_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 30.0 - max_effort: 28.0 - max_position: !degrees 360.0 - max_velocity: !degrees 60.0 - min_position: !degrees -360.0 - robotiq_85_left_knuckle_joint: - has_velocity_limits: true - max_velocity: 0.5 - has_acceleration_limits: true - max_acceleration: 1.0 diff --git a/src/picknik_ur_base_config/config/moveit/ompl_planning.yaml b/src/picknik_ur_base_config/config/moveit/ompl_planning.yaml deleted file mode 100644 index 7c7b6bca..00000000 --- a/src/picknik_ur_base_config/config/moveit/ompl_planning.yaml +++ /dev/null @@ -1,106 +0,0 @@ -planning_plugins: - - ompl_interface/OMPLPlanner -# The order of the elements in the adapter corresponds to the order they are processed by the motion planning pipeline. -request_adapters: - - default_planning_request_adapters/ResolveConstraintFrames - - default_planning_request_adapters/ValidateWorkspaceBounds - - default_planning_request_adapters/CheckStartStateBounds - - default_planning_request_adapters/CheckStartStateCollision -response_adapters: - - default_planning_response_adapters/AddTimeOptimalParameterization - - default_planning_response_adapters/ValidateSolution - - default_planning_response_adapters/DisplayMotionPath - -planner_configs: - APSConfigDefault: - type: geometric::AnytimePathShortening - shortcut: 1 # Attempt to shortcut all new solution paths - hybridize: 1 # Compute hybrid solution trajectories - max_hybrid_paths: 32 # Number of hybrid paths generated per iteration - num_planners: 16 # The number of default planners to use for planning - planners: "RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect" # A comma-separated list of planner types (e.g., "PRM,EST,RRTConnect"Optionally, planner parameters can be passed to change the default:"PRM[max_nearest_neighbors=5],EST[goal_bias=.5],RRT[range=10. goal_bias=.1]" - SBLkConfigDefault: - type: geometric::SBL - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - ESTkConfigDefault: - type: geometric::EST - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0 setup() - goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 - LBKPIECEkConfigDefault: - type: geometric::LBKPIECE - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 - min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 - BKPIECEkConfigDefault: - type: geometric::BKPIECE - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 - failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5 - min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 - KPIECEkConfigDefault: - type: geometric::KPIECE - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 - border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 (0.0,1.] - failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5 - min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 - RRTkConfigDefault: - type: geometric::RRT - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 - RRTConnectkConfigDefault: - type: geometric::RRTConnect - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - RRTstarkConfigDefault: - type: geometric::RRTstar - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 - delay_collision_checking: 1 # Stop collision checking as soon as C-free parent found. default 1 - TRRTkConfigDefault: - type: geometric::TRRT - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 - max_states_failed: 10 # when to start increasing temp. default: 10 - temp_change_factor: 2.0 # how much to increase or decrease temp. default: 2.0 - min_temperature: 10e-10 # lower limit of temp change. default: 10e-10 - init_temperature: 10e-6 # initial temperature. default: 10e-6 - frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() - frountierNodeRatio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1 - k_constant: 0.0 # value used to normalize expression. default: 0.0 set in setup() - PRMkConfigDefault: - type: geometric::PRM - max_nearest_neighbors: 10 # use k nearest neighbors. default: 10 - PRMstarkConfigDefault: - type: geometric::PRMstar -manipulator: - default_planner_config: RRTConnectkConfigDefault - planner_configs: - - APSConfigDefault - - SBLkConfigDefault - - ESTkConfigDefault - - LBKPIECEkConfigDefault - - BKPIECEkConfigDefault - - KPIECEkConfigDefault - - RRTkConfigDefault - - RRTConnectkConfigDefault - - RRTstarkConfigDefault - - TRRTkConfigDefault - - PRMkConfigDefault - - PRMstarkConfigDefault - enforce_constrained_state_space: true - ##Note: commenting the following line lets moveit chose RRTConnect as default planner rather than LBKPIECE - projection_evaluator: joints(shoulder_pan_joint,shoulder_lift_joint) - longest_valid_segment_fraction: 0.01 -gripper: - planner_configs: - - SBLkConfigDefault - - ESTkConfigDefault - - LBKPIECEkConfigDefault - - BKPIECEkConfigDefault - - KPIECEkConfigDefault - - RRTkConfigDefault - - RRTConnectkConfigDefault - - RRTstarkConfigDefault - - TRRTkConfigDefault - - PRMkConfigDefault - - PRMstarkConfigDefault diff --git a/src/picknik_ur_base_config/config/moveit/picknik_ur.srdf b/src/picknik_ur_base_config/config/moveit/picknik_ur.srdf deleted file mode 100644 index 8e97d152..00000000 --- a/src/picknik_ur_base_config/config/moveit/picknik_ur.srdf +++ /dev/null @@ -1,201 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_base_config/config/moveit/pilz_cartesian_limits.yaml b/src/picknik_ur_base_config/config/moveit/pilz_cartesian_limits.yaml deleted file mode 100644 index 1633938e..00000000 --- a/src/picknik_ur_base_config/config/moveit/pilz_cartesian_limits.yaml +++ /dev/null @@ -1,6 +0,0 @@ -# Cartesian limits for the Pilz planner -cartesian_limits: - max_trans_vel: 0.1 - max_trans_acc: 0.1 - max_trans_dec: -0.1 - max_rot_vel: 0.1 diff --git a/src/picknik_ur_base_config/config/moveit/pilz_industrial_motion_planner_planning.yaml b/src/picknik_ur_base_config/config/moveit/pilz_industrial_motion_planner_planning.yaml deleted file mode 100644 index 6d791384..00000000 --- a/src/picknik_ur_base_config/config/moveit/pilz_industrial_motion_planner_planning.yaml +++ /dev/null @@ -1,14 +0,0 @@ -planning_plugins: - - pilz_industrial_motion_planner/CommandPlanner -default_planner_config: LIN -request_adapters: - - default_planning_request_adapters/ResolveConstraintFrames - - default_planning_request_adapters/ValidateWorkspaceBounds - - default_planning_request_adapters/CheckStartStateBounds - - default_planning_request_adapters/CheckStartStateCollision -response_adapters: - - default_planning_response_adapters/ValidateSolution - - default_planning_response_adapters/DisplayMotionPath -capabilities: >- - pilz_industrial_motion_planner/MoveGroupSequenceAction - pilz_industrial_motion_planner/MoveGroupSequenceService diff --git a/src/picknik_ur_base_config/config/moveit/sensors_3d.yaml b/src/picknik_ur_base_config/config/moveit/sensors_3d.yaml deleted file mode 100644 index 12ac1297..00000000 --- a/src/picknik_ur_base_config/config/moveit/sensors_3d.yaml +++ /dev/null @@ -1,25 +0,0 @@ -sensors: - - scene_scan_camera -scene_scan_camera: - # The name of the Octomap updater plugin that we are using. - sensor_plugin: "moveit_studio_plugins/PointCloudServiceOctomapUpdater" - # Specifies the topic to listen on for a point cloud. - # Set to an empty topic to disable. - point_cloud_service_name: "/point_cloud_service" - # Points further than this will not be used (in meters). - max_range: 1.5 - # Choose one of every 'point_subsample' points (select all if set to 1). - point_subsample: 1 - # Should always be >= 1.0. Scale up collision shapes in the scene before excluding them from the octomap. - padding_scale: 1.0 - # Absolute padding around scaled collision shapes when excluding them from the octomap (in meters). - padding_offset: 0.01 - # The octomap representation will be updated at rate less than or equal to this value. - max_update_rate: 0.1 - -# Specifies the resolution at which the octomap is maintained (in meters). -octomap_resolution: 0.01 -# Specifies the coordinate frame in which the Octomap representation will be stored. -# Note! When an OccupancyMonitor instance is initialized by the PlanningSceneMonitor, -# this frame parameter will not be used. Instead, the frame defaults to the planning frame. -octomap_frame: "base_link" diff --git a/src/picknik_ur_base_config/config/moveit/stomp_planning.yaml b/src/picknik_ur_base_config/config/moveit/stomp_planning.yaml deleted file mode 100644 index dc6fd444..00000000 --- a/src/picknik_ur_base_config/config/moveit/stomp_planning.yaml +++ /dev/null @@ -1,22 +0,0 @@ -planning_plugins: - - stomp_moveit/StompPlanner -# The order of the elements in the adapter corresponds to the order they are processed by the motion planning pipeline. -request_adapters: - - default_planning_request_adapters/ResolveConstraintFrames - - default_planning_request_adapters/ValidateWorkspaceBounds - - default_planning_request_adapters/CheckStartStateBounds - - default_planning_request_adapters/CheckStartStateCollision -response_adapters: - - default_planning_response_adapters/AddTimeOptimalParameterization - - default_planning_response_adapters/ValidateSolution - - default_planning_response_adapters/DisplayMotionPath - -stomp_moveit: - num_timesteps: 60 - num_iterations: 40 - num_iterations_after_valid: 0 - num_rollouts: 30 - max_rollouts: 30 - exponentiated_cost_sensitivity: 0.8 - control_cost_weight: 0.1 - delta_t: 0.1 diff --git a/src/picknik_ur_base_config/config/moveit/trac_ik_kinematics_distance.yaml b/src/picknik_ur_base_config/config/moveit/trac_ik_kinematics_distance.yaml deleted file mode 100644 index 65f77d5c..00000000 --- a/src/picknik_ur_base_config/config/moveit/trac_ik_kinematics_distance.yaml +++ /dev/null @@ -1,6 +0,0 @@ -manipulator: - kinematics_solver: trac_ik_kinematics_plugin/TRAC_IKKinematicsPlugin - kinematics_solver_timeout: 0.005 - kinematics_solver_attempts: 3 - epsilon: 0.0001 - solve_type: "Distance" diff --git a/src/picknik_ur_base_config/config/moveit/trac_ik_kinematics_speed.yaml b/src/picknik_ur_base_config/config/moveit/trac_ik_kinematics_speed.yaml deleted file mode 100644 index 90559540..00000000 --- a/src/picknik_ur_base_config/config/moveit/trac_ik_kinematics_speed.yaml +++ /dev/null @@ -1,6 +0,0 @@ -manipulator: - kinematics_solver: trac_ik_kinematics_plugin/TRAC_IKKinematicsPlugin - kinematics_solver_timeout: 0.005 - kinematics_solver_attempts: 3 - epsilon: 0.0001 - solve_type: "Speed" diff --git a/src/picknik_ur_base_config/config/moveit/ur_servo.yaml b/src/picknik_ur_base_config/config/moveit/ur_servo.yaml deleted file mode 100644 index 13d58e8a..00000000 --- a/src/picknik_ur_base_config/config/moveit/ur_servo.yaml +++ /dev/null @@ -1,64 +0,0 @@ -############################################### -# Modify all parameters related to servoing here -############################################### - -# Enable dynamic parameter updates -enable_parameter_update: true - -## Properties of incoming commands -command_in_type: "speed_units" # "unitless"> in the range [-1:1], as if from joystick. "speed_units"> cmds are in m/s and rad/s -scale: - # Scale parameters are only used if command_in_type=="unitless" - linear: 2.0 # Max linear velocity. Meters per publish_period. Unit is [m/s]. Only used for Cartesian commands. - rotational: 3.0 # Max angular velocity. Rads per publish_period. Unit is [rad/s]. Only used for Cartesian commands. - # Max joint angular/linear velocity. Rads or Meters per publish period. Only used for joint commands on joint_command_in_topic. - joint: 2.0 - -# Default to driving the arm at 50% maximum speed. -override_velocity_scaling_factor: 0.5 - -## Properties of outgoing commands -publish_period: 0.01 # 1/Nominal publish rate [seconds] -max_expected_latency: 0.1 # delay between sending a command and the robot executing it [seconds] - -# What type of topic does your robot driver expect? -# Currently supported are std_msgs/Float64MultiArray or trajectory_msgs/JointTrajectory -command_out_type: trajectory_msgs/JointTrajectory - -# What to publish? Can save some bandwidth as most robots only require positions or velocities -publish_joint_positions: true -publish_joint_velocities: true -publish_joint_accelerations: false - -## Plugins for smoothing outgoing commands -use_smoothing: true -smoothing_filter_plugin_name: "online_signal_smoothing::AccelerationLimitedPlugin" -acceleration_filter_update_period: 0.01 # [seconds] Must match the publish_period parameter - -## MoveIt properties -move_group_name: manipulator # Often 'manipulator' or 'arm' -acceleration_filter_planning_group_name: manipulator # Often 'manipulator' or 'arm' -is_primary_planning_scene_monitor: false # The MoveGroup node maintains the planning scene, so Servo needs to get its world info from there. -monitored_planning_scene_topic: /monitored_planning_scene - -## Stopping behaviour -incoming_command_timeout: 0.1 # Stop servoing if X seconds elapse without a new command - -## Configure handling of singularities and joint limits -lower_singularity_threshold: 30.0 # Start decelerating when the condition number hits this (close to singularity) -hard_stop_singularity_threshold: 50.0 # Stop when the condition number hits this -joint_limit_margins: [0.1, 0.1, 0.1, 0.1, 0.1, 0.1] # added as a buffer to joint limits [radians]. If moving quickly, make this larger. - -## Topic names -cartesian_command_in_topic: ~/delta_twist_cmds # Topic for incoming Cartesian twist commands -joint_command_in_topic: ~/delta_joint_cmds # Topic for incoming joint angle commands -joint_topic: /joint_states -status_topic: ~/status # Publish status to this topic -command_out_topic: /servo_controller/joint_trajectory # Publish outgoing commands here - -## Collision checking for the entire robot body -check_collisions: true # Check collisions? -check_octomap_collisions: false # Check collisions with octomap? -collision_check_rate: 10.0 # [Hz] Collision-checking can easily bog down a CPU if done too often. -self_collision_proximity_threshold: 0.006 # Start decelerating when a self-collision is this far [m] -scene_collision_proximity_threshold: 0.02 # Start decelerating when a scene collision is this far [m] diff --git a/src/picknik_ur_base_config/config/realsense_config_high_accuracy.json b/src/picknik_ur_base_config/config/realsense_config_high_accuracy.json deleted file mode 100644 index 2a3ce516..00000000 --- a/src/picknik_ur_base_config/config/realsense_config_high_accuracy.json +++ /dev/null @@ -1,48 +0,0 @@ -{ - "ignoreSAD": "0", - "param-censusenablereg-udiameter": "9", - "param-censusenablereg-vdiameter": "9", - "param-censususize": "9", - "param-censusvsize": "9", - "param-disableraucolor": "0", - "param-disablesadcolor": "0", - "param-disablesadnormalize": "0", - "param-disablesloleftcolor": "0", - "param-disableslorightcolor": "1", - "param-lambdaad": "751", - "param-lambdacensus": "6", - "param-leftrightthreshold": "10", - "param-maxscorethreshb": "2893", - "param-medianthreshold": "796", - "param-minscorethresha": "4", - "param-neighborthresh": "108", - "param-raumine": "6", - "param-rauminn": "3", - "param-rauminnssum": "7", - "param-raumins": "2", - "param-rauminw": "2", - "param-rauminwesum": "12", - "param-regioncolorthresholdb": "0.785714", - "param-regioncolorthresholdg": "0.565558", - "param-regioncolorthresholdr": "0.985323", - "param-regionshrinku": "3", - "param-regionshrinkv": "0", - "param-robbinsmonrodecrement": "25", - "param-robbinsmonroincrement": "2", - "param-rsmdiffthreshold": "1.65625", - "param-rsmrauslodiffthreshold": "0.71875", - "param-rsmremovethreshold": "0.809524", - "param-scanlineedgetaub": "13", - "param-scanlineedgetaug": "15", - "param-scanlineedgetaur": "30", - "param-scanlinep1": "155", - "param-scanlinep1onediscon": "160", - "param-scanlinep1twodiscon": "59", - "param-scanlinep2": "190", - "param-scanlinep2onediscon": "507", - "param-scanlinep2twodiscon": "493", - "param-secondpeakdelta": "647", - "param-texturecountthresh": "0", - "param-texturedifferencethresh": "1722", - "param-usersm": "1" -} diff --git a/src/picknik_ur_base_config/description/picknik_ur.xacro b/src/picknik_ur_base_config/description/picknik_ur.xacro deleted file mode 100644 index 1508c40e..00000000 --- a/src/picknik_ur_base_config/description/picknik_ur.xacro +++ /dev/null @@ -1,48 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_base_config/description/picknik_ur_attachments_macro.xacro b/src/picknik_ur_base_config/description/picknik_ur_attachments_macro.xacro deleted file mode 100644 index b142c94e..00000000 --- a/src/picknik_ur_base_config/description/picknik_ur_attachments_macro.xacro +++ /dev/null @@ -1,107 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_base_config/description/picknik_ur_macro.xacro b/src/picknik_ur_base_config/description/picknik_ur_macro.xacro deleted file mode 100644 index 4a9f346e..00000000 --- a/src/picknik_ur_base_config/description/picknik_ur_macro.xacro +++ /dev/null @@ -1,104 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_base_config/description/pinch_links.xacro b/src/picknik_ur_base_config/description/pinch_links.xacro deleted file mode 100644 index fda669eb..00000000 --- a/src/picknik_ur_base_config/description/pinch_links.xacro +++ /dev/null @@ -1,72 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_base_config/launch/agent_bridge.launch.xml b/src/picknik_ur_base_config/launch/agent_bridge.launch.xml deleted file mode 100644 index b2aa7543..00000000 --- a/src/picknik_ur_base_config/launch/agent_bridge.launch.xml +++ /dev/null @@ -1,6 +0,0 @@ - - - - diff --git a/src/picknik_ur_base_config/launch/moveit_pro.launch.xml b/src/picknik_ur_base_config/launch/moveit_pro.launch.xml deleted file mode 100644 index 102a8a24..00000000 --- a/src/picknik_ur_base_config/launch/moveit_pro.launch.xml +++ /dev/null @@ -1,11 +0,0 @@ - - - - - diff --git a/src/picknik_ur_base_config/launch/pro_rs_launch.py b/src/picknik_ur_base_config/launch/pro_rs_launch.py deleted file mode 100644 index 7aaec2b2..00000000 --- a/src/picknik_ur_base_config/launch/pro_rs_launch.py +++ /dev/null @@ -1,69 +0,0 @@ -# Copyright 2024 PickNik Inc. -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions are met: -# -# * Redistributions of source code must retain the above copyright -# notice, this list of conditions and the following disclaimer. -# -# * Redistributions in binary form must reproduce the above copyright -# notice, this list of conditions and the following disclaimer in the -# documentation and/or other materials provided with the distribution. -# -# * Neither the name of the PickNik Inc. nor the names of its -# contributors may be used to endorse or promote products derived from -# this software without specific prior written permission. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE. - -import sys - -from ament_index_python import get_package_share_directory -from launch import LaunchDescription -from launch.actions import OpaqueFunction - -# Add the realsense2_camera/launch directory to the user's path so we can import the realsense2_camera rs_launch module. -realsense2_camera_path = get_package_share_directory("realsense2_camera") -sys.path.append(f"{realsense2_camera_path}/launch") - -import rs_launch - - -def generate_launch_description(): - rs_launch.configurable_parameters.extend( - [ - { - "name": "color_qos", - "default": "SENSOR_DATA", - "description": "Color stream QoS settings", - }, - { - "name": "depth_qos", - "default": "SENSOR_DATA", - "description": "Depth stream QoS settings", - }, - ] - ) - return LaunchDescription( - rs_launch.declare_configurable_parameters(rs_launch.configurable_parameters) - + [ - OpaqueFunction( - function=rs_launch.launch_setup, - kwargs={ - "params": rs_launch.set_configurable_parameters( - rs_launch.configurable_parameters - ) - }, - ) - ] - ) diff --git a/src/picknik_ur_base_config/launch/robot_drivers_to_persist.launch.py b/src/picknik_ur_base_config/launch/robot_drivers_to_persist.launch.py deleted file mode 100644 index c4618f26..00000000 --- a/src/picknik_ur_base_config/launch/robot_drivers_to_persist.launch.py +++ /dev/null @@ -1,95 +0,0 @@ -# Copyright 2023 PickNik Inc. -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions are met: -# -# * Redistributions of source code must retain the above copyright -# notice, this list of conditions and the following disclaimer. -# -# * Redistributions in binary form must reproduce the above copyright -# notice, this list of conditions and the following disclaimer in the -# documentation and/or other materials provided with the distribution. -# -# * Neither the name of the PickNik Inc. nor the names of its -# contributors may be used to endorse or promote products derived from -# this software without specific prior written permission. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE. - - -from launch import LaunchDescription -from launch.actions import DeclareLaunchArgument -from launch.actions import IncludeLaunchDescription -from launch.substitutions import LaunchConfiguration -from launch_ros.actions import Node -from launch.substitutions import ThisLaunchFileDir -from launch.launch_description_sources import AnyLaunchDescriptionSource - -from moveit_studio_utils_py.launch_common import empty_gen -from moveit_studio_utils_py.system_config import ( - SystemConfigParser, -) - - -def generate_launch_description(): - system_config_parser = SystemConfigParser() - hardware_config = system_config_parser.get_hardware_config() - controller_config = system_config_parser.get_ros2_control_config() - - declare_robot_ip = DeclareLaunchArgument( - "robot_ip", description="IP address of the robot" - ) - robot_ip = LaunchConfiguration("robot_ip") - - dashboard_client_node = Node( - package="ur_robot_driver", - executable="dashboard_client", - name="dashboard_client", - output="both", - emulate_tty=True, - parameters=[{"robot_ip": robot_ip}], - ) - - protective_stop_manager_node = Node( - package="moveit_studio_ur_pstop_manager", - executable="protective_stop_manager_node", - name="protective_stop_manager_node", - output="both", - parameters=[ - { - "controllers_default_active": controller_config.get( - "controllers_active_at_startup", empty_gen() - ), - "controllers_default_not_active": controller_config.get( - "controllers_inactive_at_startup", empty_gen() - ), - } - ], - ) - - tool_comms_launch = IncludeLaunchDescription( - AnyLaunchDescriptionSource([ThisLaunchFileDir(), "/ur_tool_comms.launch.xml"]), - launch_arguments={ - "robot_ip": robot_ip, - "tool_tcp_port": "54321", - "tool_device_name": "/tmp/ttyUR", - }.items(), - ) - - nodes_to_launch = [ - dashboard_client_node, - protective_stop_manager_node, - tool_comms_launch, - ] - - return LaunchDescription(nodes_to_launch) diff --git a/src/picknik_ur_base_config/launch/rs_cameras.launch.xml b/src/picknik_ur_base_config/launch/rs_cameras.launch.xml deleted file mode 100644 index 285ff314..00000000 --- a/src/picknik_ur_base_config/launch/rs_cameras.launch.xml +++ /dev/null @@ -1,74 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_base_config/launch/sim/robot_drivers_to_persist_sim.launch.py b/src/picknik_ur_base_config/launch/sim/robot_drivers_to_persist_sim.launch.py deleted file mode 100644 index c6596305..00000000 --- a/src/picknik_ur_base_config/launch/sim/robot_drivers_to_persist_sim.launch.py +++ /dev/null @@ -1,43 +0,0 @@ -# Copyright 2023 PickNik Inc. -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions are met: -# -# * Redistributions of source code must retain the above copyright -# notice, this list of conditions and the following disclaimer. -# -# * Redistributions in binary form must reproduce the above copyright -# notice, this list of conditions and the following disclaimer in the -# documentation and/or other materials provided with the distribution. -# -# * Neither the name of the PickNik Inc. nor the names of its -# contributors may be used to endorse or promote products derived from -# this software without specific prior written permission. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE. - - -from launch import LaunchDescription -from launch_ros.actions import Node - - -def generate_launch_description(): - # Mock the UR Dashboard Client - mock_dashboard_client = Node( - package="moveit_studio_ur_pstop_manager", - executable="mock_ur_dashboard_client_node", - name="dashboard_client", - output="both", - ) - - return LaunchDescription([mock_dashboard_client]) diff --git a/src/picknik_ur_base_config/launch/ur_tool_comms.launch.xml b/src/picknik_ur_base_config/launch/ur_tool_comms.launch.xml deleted file mode 100644 index 069c35f2..00000000 --- a/src/picknik_ur_base_config/launch/ur_tool_comms.launch.xml +++ /dev/null @@ -1,17 +0,0 @@ - - - - - - diff --git a/src/picknik_ur_base_config/objectives/clear_snapshot.xml b/src/picknik_ur_base_config/objectives/clear_snapshot.xml deleted file mode 100644 index e8095851..00000000 --- a/src/picknik_ur_base_config/objectives/clear_snapshot.xml +++ /dev/null @@ -1,10 +0,0 @@ - - - - - - - diff --git a/src/picknik_ur_base_config/objectives/close_gripper.xml b/src/picknik_ur_base_config/objectives/close_gripper.xml deleted file mode 100644 index cc90bbe4..00000000 --- a/src/picknik_ur_base_config/objectives/close_gripper.xml +++ /dev/null @@ -1,13 +0,0 @@ - - - - - - - - diff --git a/src/picknik_ur_base_config/objectives/get_imarker_pose_from_mesh_visualization.xml b/src/picknik_ur_base_config/objectives/get_imarker_pose_from_mesh_visualization.xml deleted file mode 100644 index 955ea9b8..00000000 --- a/src/picknik_ur_base_config/objectives/get_imarker_pose_from_mesh_visualization.xml +++ /dev/null @@ -1,32 +0,0 @@ - - - - - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_base_config/objectives/interpolate_to_joint_state.xml b/src/picknik_ur_base_config/objectives/interpolate_to_joint_state.xml deleted file mode 100644 index e9e294e0..00000000 --- a/src/picknik_ur_base_config/objectives/interpolate_to_joint_state.xml +++ /dev/null @@ -1,39 +0,0 @@ - - - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_base_config/objectives/move_to_joint_state.xml b/src/picknik_ur_base_config/objectives/move_to_joint_state.xml deleted file mode 100644 index 0b3c3e9a..00000000 --- a/src/picknik_ur_base_config/objectives/move_to_joint_state.xml +++ /dev/null @@ -1,37 +0,0 @@ - - - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_base_config/objectives/move_to_pose.xml b/src/picknik_ur_base_config/objectives/move_to_pose.xml deleted file mode 100644 index b5e1e6b8..00000000 --- a/src/picknik_ur_base_config/objectives/move_to_pose.xml +++ /dev/null @@ -1,41 +0,0 @@ - - - - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_base_config/objectives/move_to_waypoint.xml b/src/picknik_ur_base_config/objectives/move_to_waypoint.xml deleted file mode 100644 index 4733f815..00000000 --- a/src/picknik_ur_base_config/objectives/move_to_waypoint.xml +++ /dev/null @@ -1,50 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_base_config/objectives/open_gripper.xml b/src/picknik_ur_base_config/objectives/open_gripper.xml deleted file mode 100644 index 10084d1f..00000000 --- a/src/picknik_ur_base_config/objectives/open_gripper.xml +++ /dev/null @@ -1,14 +0,0 @@ - - - - - - - - - diff --git a/src/picknik_ur_base_config/objectives/request_teleoperation.xml b/src/picknik_ur_base_config/objectives/request_teleoperation.xml deleted file mode 100644 index 33c019f1..00000000 --- a/src/picknik_ur_base_config/objectives/request_teleoperation.xml +++ /dev/null @@ -1,169 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_base_config/objectives/reset_planning_scene.xml b/src/picknik_ur_base_config/objectives/reset_planning_scene.xml deleted file mode 100644 index 999da975..00000000 --- a/src/picknik_ur_base_config/objectives/reset_planning_scene.xml +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - diff --git a/src/picknik_ur_base_config/objectives/teleoperate.xml b/src/picknik_ur_base_config/objectives/teleoperate.xml deleted file mode 100644 index c4fdcdab..00000000 --- a/src/picknik_ur_base_config/objectives/teleoperate.xml +++ /dev/null @@ -1,17 +0,0 @@ - - - - - - - diff --git a/src/picknik_ur_base_config/objectives/wait_for_trajectory_approval_if_user_available.xml b/src/picknik_ur_base_config/objectives/wait_for_trajectory_approval_if_user_available.xml deleted file mode 100644 index 97b82b14..00000000 --- a/src/picknik_ur_base_config/objectives/wait_for_trajectory_approval_if_user_available.xml +++ /dev/null @@ -1,18 +0,0 @@ - - - - - - - - - - - diff --git a/src/picknik_ur_base_config/package.xml b/src/picknik_ur_base_config/package.xml deleted file mode 100644 index 9acd1140..00000000 --- a/src/picknik_ur_base_config/package.xml +++ /dev/null @@ -1,44 +0,0 @@ - - - picknik_ur_base_config - 6.0.0 - - - Base configuration package for Picknik's UR robot arms - - - MoveIt Pro Maintainer - - BSD-3-Clause - - ament_cmake - - admittance_controller - kinematics_interface_kdl - moveit_planners_stomp - moveit_ros_perception - moveit_studio_agent - moveit_studio_behavior - moveit_studio_ur_pstop_manager - picknik_accessories - realsense2_camera - realsense2_description - robotiq_description - robotiq_controllers - trac_ik_kinematics_plugin - ur_description - ur_robot_driver - - ament_lint_auto - - ament_clang_format - ament_clang_tidy - ament_cmake_copyright - ament_cmake_lint_cmake - picknik_ament_copyright - ament_flake8 - - - ament_cmake - - diff --git a/src/picknik_ur_base_config/waypoints/ur_waypoints.yaml b/src/picknik_ur_base_config/waypoints/ur_waypoints.yaml deleted file mode 100644 index 14095abc..00000000 --- a/src/picknik_ur_base_config/waypoints/ur_waypoints.yaml +++ /dev/null @@ -1,255 +0,0 @@ -- name: Grab - description: "" - favorite: true - joint_group_names: - - manipulator - joint_state: - header: - frame_id: world - stamp: - sec: 0 - nanosec: 0 - name: [shoulder_pan_joint, shoulder_lift_joint, elbow_joint, wrist_1_joint, wrist_2_joint, wrist_3_joint] - position: [2.7712432925819273, -1.4531914890259676, -1.96615025453015, -1.0617789845470658, 1.5878968566255958, -0.07080028000697597] - velocity: [] - effort: [] -- name: Look at Table - favorite: true - joint_group_names: - - manipulator - joint_state: - header: - frame_id: world - stamp: - sec: 0 - nanosec: 0 - name: [shoulder_pan_joint, shoulder_lift_joint, elbow_joint, wrist_1_joint, wrist_2_joint, wrist_3_joint] - position: [3.03, -0.78, -0.51, -2.39, 1.65, 0] - velocity: [] - effort: [] -- name: Look at Pick and Place Zone - favorite: true - joint_group_names: - - manipulator - joint_state: - header: - frame_id: world - stamp: - sec: 0 - nanosec: 0 - name: [shoulder_pan_joint, shoulder_lift_joint, elbow_joint, wrist_1_joint, wrist_2_joint, wrist_3_joint] - position: [3.03, -0.78, -0.51, -2.39, 1.65, 0] - velocity: [] - effort: [] -- name: Forward Down - favorite: true - joint_group_names: - - manipulator - joint_state: - header: - frame_id: world - stamp: - sec: 0 - nanosec: 0 - name: [shoulder_pan_joint, shoulder_lift_joint, elbow_joint, wrist_1_joint, wrist_2_joint, wrist_3_joint] - position: [0, -1.41, -0.7, -2.12, 1.67, 0] - velocity: [] - effort: [] -- name: Right Corner - favorite: true - joint_group_names: - - manipulator - joint_state: - header: - frame_id: world - stamp: - sec: 0 - nanosec: 0 - name: [shoulder_pan_joint, shoulder_lift_joint, elbow_joint, wrist_1_joint, wrist_2_joint, wrist_3_joint] - position: [-0.61, -0.78, -0.45, -2.49, 1.64, 0] - velocity: [] - effort: [] -- name: Left Corner - favorite: true - joint_group_names: - - manipulator - joint_state: - header: - frame_id: world - stamp: - sec: 0 - nanosec: 0 - name: [shoulder_pan_joint, shoulder_lift_joint, elbow_joint, wrist_1_joint, wrist_2_joint, wrist_3_joint] - position: [0.58, -0.78, -0.45, -2.33, 1.64, 0] - velocity: [] - effort: [] -- name: Home - favorite: true - joint_group_names: - - manipulator - joint_state: - header: - frame_id: world - stamp: - sec: 0 - nanosec: 0 - name: [shoulder_pan_joint, shoulder_lift_joint, elbow_joint, wrist_1_joint, wrist_2_joint, wrist_3_joint] - position: [0, -0.78, -0.51, -2.4, 1.65, 0] - velocity: [] - effort: [] -- name: Place - joint_group_names: - - manipulator - joint_state: - header: - frame_id: world - stamp: - sec: 0 - nanosec: 0 - name: [shoulder_pan_joint, shoulder_lift_joint, elbow_joint, wrist_1_joint, wrist_2_joint, wrist_3_joint] - position: [-0.14017278352846319, -2.0659257374205531, -1.3808614015579224, -1.1930744808963318, 1.6471527814865112, -1.2497900168048304] - velocity: [] - effort: [] -- name: Right Wall - joint_group_names: - - manipulator - joint_state: - header: - frame_id: world - stamp: - sec: 0 - nanosec: 0 - name: [shoulder_pan_joint, shoulder_lift_joint, elbow_joint, wrist_1_joint, wrist_2_joint, wrist_3_joint] - position: [-0.10607844987978154, -0.60454382122073369, -0.53829550743103027, -2.1444779835143031, 1.3706846237182617, -0.03349477449526006] - velocity: [] - effort: [] -- name: Left Wall - joint_group_names: - - manipulator - joint_state: - header: - frame_id: world - stamp: - sec: 0 - nanosec: 0 - name: [shoulder_pan_joint, shoulder_lift_joint, elbow_joint, wrist_1_joint, wrist_2_joint, wrist_3_joint] - position: [-0.090000931416646779, -0.71631135166201787, -0.25595679879188538, -2.3102809391417445, 2.1028439998626709, 0.037132550030946732] - velocity: [] - effort: [] -- name: Left Shelf - joint_group_names: - - manipulator - joint_state: - header: - frame_id: world - stamp: - sec: 0 - nanosec: 0 - name: [shoulder_pan_joint, shoulder_lift_joint, elbow_joint, wrist_1_joint, wrist_2_joint, wrist_3_joint] - position: [-0.13052112260927373, -2.0738541088499964, -1.3867737054824829, -1.2032757264426728, 1.5722750425338745, -1.2421711126910608] - velocity: [] - effort: [] -- name: Right Shelf - joint_group_names: - - manipulator - joint_state: - header: - frame_id: world - stamp: - sec: 0 - nanosec: 0 - name: [shoulder_pan_joint, shoulder_lift_joint, elbow_joint, wrist_1_joint, wrist_2_joint, wrist_3_joint] - position: [-0.3130109945880335, -2.2752829990782679, -0.99421918392181396, -1.4464575362256546, 1.6087517738342285, 0.3333250880241394] - velocity: [] - effort: [] -- name: Drop - joint_group_names: - - manipulator - joint_state: - header: - frame_id: world - stamp: - sec: 0 - nanosec: 0 - name: [shoulder_pan_joint, shoulder_lift_joint, elbow_joint, wrist_1_joint, wrist_2_joint, wrist_3_joint] - position: [-0.14025289217104131, -2.0338388882079066, -1.3048344850540161, -1.3033235830119629, 1.6469297409057617, -1.2498410383807581] - velocity: [] - effort: [] -- name: Place Left - joint_group_names: - - manipulator - joint_state: - header: - frame_id: world - stamp: - sec: 0 - nanosec: 0 - name: [shoulder_pan_joint, shoulder_lift_joint, elbow_joint, wrist_1_joint, wrist_2_joint, wrist_3_joint] - position: [-0.13052112260927373, -2.0738541088499964, -1.3867737054824829, -1.2032757264426728, 1.5722750425338745, -1.2421711126910608] - velocity: [] - effort: [] -- name: Place Right - joint_group_names: - - manipulator - joint_state: - header: - frame_id: world - stamp: - sec: 0 - nanosec: 0 - name: [shoulder_pan_joint, shoulder_lift_joint, elbow_joint, wrist_1_joint, wrist_2_joint, wrist_3_joint] - position: [-0.3130109945880335, -2.2752829990782679, -0.99421918392181396, -1.4464575362256546, 1.6087517738342285, 0.3333250880241394] - velocity: [] - effort: [] -- name: Place Block - joint_group_names: - - manipulator - joint_state: - header: - frame_id: world - stamp: - sec: 0 - nanosec: 0 - name: [shoulder_pan_joint, shoulder_lift_joint, elbow_joint, wrist_1_joint, wrist_2_joint, wrist_3_joint] - position: [0.139626, -2.05949, -1.48353, -1.20428, 1.69297, 0.20944] - velocity: [] - effort: [] -- name: Pick Block - joint_group_names: - - manipulator - joint_state: - header: - frame_id: world - stamp: - sec: 0 - nanosec: 0 - name: [shoulder_pan_joint, shoulder_lift_joint, elbow_joint, wrist_1_joint, wrist_2_joint, wrist_3_joint] - position: [2.89725, -2.0944, -1.50098, -1.0472, 1.69297, 0.20944] - velocity: [] - effort: [] -- name: Wrist 2 Min - joint_group_names: - - manipulator - joint_state: - header: - frame_id: world - stamp: - sec: 0 - nanosec: 0 - name: [shoulder_pan_joint, shoulder_lift_joint, elbow_joint, wrist_1_joint, wrist_2_joint, wrist_3_joint] - position: [-2.2335834056138996e-05, -0.7800858658974525, -0.5100288585397881, -2.399985082258936, -3.141592653589793, 2.282092208042741e-05] - velocity: [] - effort: [] -- name: Wrist 2 Max - joint_group_names: - - manipulator - joint_state: - header: - frame_id: world - stamp: - sec: 0 - nanosec: 0 - name: [shoulder_pan_joint, shoulder_lift_joint, elbow_joint, wrist_1_joint, wrist_2_joint, wrist_3_joint] - position: [-2.2335834056138996e-05, -0.7800858658974525, -0.5100288585397881, -2.399985082258936, 3.141592653589793, 2.282092208042741e-05] - velocity: [] - effort: [] diff --git a/src/picknik_ur_mobile_config/CMakeLists.txt b/src/picknik_ur_mobile_config/CMakeLists.txt deleted file mode 100644 index deb94e57..00000000 --- a/src/picknik_ur_mobile_config/CMakeLists.txt +++ /dev/null @@ -1,35 +0,0 @@ -cmake_minimum_required(VERSION 3.22) -project(picknik_ur_mobile_config) - -find_package(ament_cmake REQUIRED) -find_package(picknik_accessories REQUIRED) - - -# Install all XML files in directory -set(PICKNIK_ACCESSORIES_SHARE_DIR -"${CMAKE_INSTALL_PREFIX}/../picknik_accessories/share/picknik_accessories/mujoco_assets/" -) -# Destination directory -set(DEST_DIR "${CMAKE_INSTALL_PREFIX}/share/${PROJECT_NAME}/description/") - -install(DIRECTORY "${PICKNIK_ACCESSORIES_SHARE_DIR}" - DESTINATION "${DEST_DIR}" - FILES_MATCHING PATTERN "*") - -install( - DIRECTORY - config - description - launch - objectives - waypoints - DESTINATION - share/${PROJECT_NAME} -) - -if(BUILD_TESTING) - find_package(ament_lint_auto REQUIRED) - ament_lint_auto_find_test_dependencies() -endif() - -ament_package() diff --git a/src/picknik_ur_mobile_config/LICENSE b/src/picknik_ur_mobile_config/LICENSE deleted file mode 100644 index 574ef079..00000000 --- a/src/picknik_ur_mobile_config/LICENSE +++ /dev/null @@ -1,25 +0,0 @@ -Redistribution and use in source and binary forms, with or without -modification, are permitted provided that the following conditions are met: - - * Redistributions of source code must retain the above copyright - notice, this list of conditions and the following disclaimer. - - * Redistributions in binary form must reproduce the above copyright - notice, this list of conditions and the following disclaimer in the - documentation and/or other materials provided with the distribution. - - * Neither the name of the copyright holder nor the names of its - contributors may be used to endorse or promote products derived from - this software without specific prior written permission. - -THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -POSSIBILITY OF SUCH DAMAGE. diff --git a/src/picknik_ur_mobile_config/README.md b/src/picknik_ur_mobile_config/README.md deleted file mode 100644 index 7a00d3bc..00000000 --- a/src/picknik_ur_mobile_config/README.md +++ /dev/null @@ -1,5 +0,0 @@ -# picknik_ur_mobile_config - -A MoveIt Pro MuJoCo simulation of a UR5 arm on a mobile Ridgeback base. - -For detailed documentation see: [MoveIt Pro Documentation](https://docs.picknik.ai/) diff --git a/src/picknik_ur_mobile_config/config/config.yaml b/src/picknik_ur_mobile_config/config/config.yaml deleted file mode 100644 index 8af6c561..00000000 --- a/src/picknik_ur_mobile_config/config/config.yaml +++ /dev/null @@ -1,83 +0,0 @@ -# -# This contains information for a unique instance of a robot. -# - -# Name of the package to specialize -based_on_package: "picknik_ur_base_config" -hardware: - # Parameters used to configure the robot description through XACRO. - # A URDF and SRDF are both required. - # [Required] - robot_description: - urdf: - package: "picknik_ur_mobile_config" - path: "description/picknik_ur.xacro" - srdf: - package: "picknik_ur_mobile_config" - path: "config/moveit/picknik_ur.srdf" - urdf_params: - - joint_limits_parameters_file: - package: "picknik_ur_mobile_config" - path: "config/moveit/joint_limits.yaml" - -moveit_params: - servo: - package: "picknik_ur_mobile_config" - path: "config/moveit/ur_servo.yaml" - joint_limits: - package: "picknik_ur_mobile_config" - path: "config/moveit/joint_limits.yaml" - servo_joint_limits: - package: "picknik_ur_mobile_config" - path: "config/moveit/hard_joint_limits.yaml" - -# Configuration for loading behaviors and objectives. -# [Required] -objectives: - # List of plugins for loading custom behaviors. - # [Required] - behavior_loader_plugins: - # This plugin will load the core MoveIt Pro Behaviors. - # Add additional plugin loaders as needed. - core: - - "moveit_studio::behaviors::CoreBehaviorsLoader" - - "moveit_studio::behaviors::MTCCoreBehaviorsLoader" - - "moveit_studio::behaviors::ServoBehaviorsLoader" - - "moveit_studio::behaviors::VisionBehaviorsLoader" - # Specify source folder for objectives - # [Required] - objective_library_paths: - sim_objectives: - package_name: "picknik_ur_mobile_config" - relative_path: "objectives" - # Specify the location of the saved waypoints file. - # [Required] - waypoints_file: - package_name: "picknik_ur_mobile_config" - relative_path: "waypoints/ur_waypoints.yaml" - - -# Configuration for launching ros2_control processes. -# [Required, if using ros2_control] -ros2_control: - config: - package: "picknik_ur_mobile_config" - path: "config/control/picknik_ur.ros2_control.yaml" - # MoveIt Pro will load and activate these controllers at start up to ensure they are available. - # If not specified, it is up to the user to ensure the appropriate controllers are active and available - # for running the application. - # [Optional, default=[]] - controllers_active_at_startup: - - "force_torque_sensor_broadcaster" - - "robotiq_gripper_controller" - - "joint_state_broadcaster" - - "servo_controller" - # Load but do not start these controllers so they can be activated later if needed. - controllers_inactive_at_startup: - - "joint_trajectory_controller" - # Any controllers here will not be spawned by MoveIt Pro. - # [Optional, default=[]] - controllers_not_managed: [] - # Optionally configure remapping rules to let multiple controllers receive commands on the same topic. - # [Optional, default=[]] - controller_shared_topics: [] diff --git a/src/picknik_ur_mobile_config/config/control/picknik_ur.ros2_control.yaml b/src/picknik_ur_mobile_config/config/control/picknik_ur.ros2_control.yaml deleted file mode 100644 index 0411438e..00000000 --- a/src/picknik_ur_mobile_config/config/control/picknik_ur.ros2_control.yaml +++ /dev/null @@ -1,175 +0,0 @@ -controller_manager: - ros__parameters: - update_rate: 600 # Hz - joint_state_broadcaster: - type: joint_state_broadcaster/JointStateBroadcaster - joint_trajectory_controller: - type: joint_trajectory_controller/JointTrajectoryController - robotiq_gripper_controller: - type: position_controllers/GripperActionController - servo_controller: - type: joint_trajectory_controller/JointTrajectoryController - - force_torque_sensor_broadcaster: - type: force_torque_sensor_broadcaster/ForceTorqueSensorBroadcaster - -joint_state_broadcaster: - ros__parameters: - use_local_topics: false - joints: - - linear_x_joint - - linear_y_joint - - rotational_yaw_joint - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - - robotiq_85_left_knuckle_joint - interfaces: - - position - - velocity - - effort - -joint_trajectory_controller: - ros__parameters: - joints: - - linear_x_joint - - linear_y_joint - - rotational_yaw_joint - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - command_interfaces: - - position - state_interfaces: - - position - - velocity - command_joints: - - linear_x_joint - - linear_y_joint - - rotational_yaw_joint - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - state_publish_rate: 100.0 - action_monitor_rate: 20.0 - allow_partial_joints_goal: false - constraints: - stopped_velocity_tolerance: 0.0 - goal_time: 0.0 - linear_x_joint: - goal: 0.05 - linear_y_joint: - goal: 0.05 - rotational_yaw_joint: - goal: 0.05 - shoulder_pan_joint: - goal: 0.05 - shoulder_lift_joint: - goal: 0.05 - elbow_joint: - goal: 0.05 - wrist_1_joint: - goal: 0.05 - wrist_2_joint: - goal: 0.05 - wrist_3_joint: - goal: 0.05 - acceleration_limits: - linear_x_joint: 10.0 - linear_y_joint: 10.0 - rotational_yaw_joint: 10.0 - shoulder_pan_joint: 10.0 - shoulder_lift_joint: 10.0 - elbow_joint: 10.0 - wrist_1_joint: 10.0 - wrist_2_joint: 10.0 - wrist_3_joint: 10.0 - -robotiq_gripper_controller: - ros__parameters: - default: true - joint: robotiq_85_left_knuckle_joint - allow_stalling: true -servo_controller: - ros__parameters: - joints: - - linear_x_joint - - linear_y_joint - - rotational_yaw_joint - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - - command_interfaces: - - position - state_interfaces: - - position - - velocity - command_joints: - - linear_x_joint - - linear_y_joint - - rotational_yaw_joint - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - state_publish_rate: 100.0 - action_monitor_rate: 20.0 - allow_partial_joints_goal: false - constraints: - stopped_velocity_tolerance: 0.0 - goal_time: 0.0 - linear_x_joint: - goal: 0.05 - linear_y_joint: - goal: 0.05 - rotational_yaw_joint: - goal: 0.05 - shoulder_pan_joint: - goal: 0.05 - shoulder_lift_joint: - goal: 0.05 - elbow_joint: - goal: 0.05 - wrist_1_joint: - goal: 0.05 - wrist_2_joint: - goal: 0.05 - wrist_3_joint: - goal: 0.05 - acceleration_limits: - linear_x_joint: 10.0 - linear_y_joint: 10.0 - rotational_yaw_joint: 10.0 - shoulder_pan_joint: 10.0 - shoulder_lift_joint: 10.0 - elbow_joint: 10.0 - wrist_1_joint: 10.0 - wrist_2_joint: 10.0 - wrist_3_joint: 10.0 - -force_torque_sensor_broadcaster: - ros__parameters: - sensor_name: robotiq_ft_sensor - state_interface_names: - - force.x - - force.y - - force.z - - torque.x - - torque.y - - torque.z - frame_id: robotiq_ft_sensor diff --git a/src/picknik_ur_mobile_config/config/initial_positions.yaml b/src/picknik_ur_mobile_config/config/initial_positions.yaml deleted file mode 100644 index ad2d6a73..00000000 --- a/src/picknik_ur_mobile_config/config/initial_positions.yaml +++ /dev/null @@ -1,9 +0,0 @@ -linear_x_joint: 1.5 -linear_y_joint: 1.5 -rotational_yaw_joint: 0.0 -shoulder_pan_joint: 0.0 -shoulder_lift_joint: -1.41 -elbow_joint: -0.7 -wrist_1_joint: -2.12 -wrist_2_joint: 1.67 -wrist_3_joint: 0.0 diff --git a/src/picknik_ur_mobile_config/config/moveit/hard_joint_limits.yaml b/src/picknik_ur_mobile_config/config/moveit/hard_joint_limits.yaml deleted file mode 100644 index 8939a72f..00000000 --- a/src/picknik_ur_mobile_config/config/moveit/hard_joint_limits.yaml +++ /dev/null @@ -1,117 +0,0 @@ -# Joints limits -# -# Sources: -# -# - Universal Robots e-Series, User Manual, UR5e, Version 5.8 -# https://s3-eu-west-1.amazonaws.com/ur-support-site/69091/99404_UR5e_User_Manual_en_Global.pdf -# - Support > Articles > UR articles > Max. joint torques -# https://www.universal-robots.com/articles/ur-articles/max-joint-torques -# retrieved: 2020-06-16, last modified: 2020-06-09 -# -# NOTE: Acceleration limits are not publicly available so we have picked a reasonable upper limit -joint_limits: - linear_x_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: 0.1 - max_effort: 150.0 - max_position: 5.0 - max_velocity: 0.175 - min_position: -5.0 - linear_y_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: 0.1 - max_effort: 150.0 - max_position: 5.0 - max_velocity: 0.175 - min_position: -5.0 - rotational_yaw_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 90.0 - max_effort: 150.0 - max_position: !degrees 180.0 - max_velocity: !degrees 30.0 - min_position: !degrees -180.0 - shoulder_pan_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 90.0 - max_effort: 150.0 - max_position: !degrees 180.0 - max_velocity: !degrees 30.0 - min_position: !degrees -180.0 - shoulder_lift_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 90.0 - max_effort: 150.0 - max_position: !degrees 90.0 - max_velocity: !degrees 30.0 - min_position: !degrees -270.0 - elbow_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 90.0 - max_effort: 150.0 - # we artificially limit this joint to half its actual joint position limit - # to avoid (MoveIt/OMPL) planning problems, as due to the physical - # construction of the robot, it's impossible to rotate the 'elbow_joint' - # over more than approx +- 1 pi (the shoulder lift joint gets in the way). - # - # This leads to planning problems as the search space will be divided into - # two sections, with no connections from one to the other. - # - # Refer to https://github.com/ros-industrial/universal_robot/issues/265 for - # more information. - max_position: !degrees 180.0 - max_velocity: !degrees 30.0 - min_position: !degrees -180.0 - wrist_1_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 90.0 - max_effort: 28.0 - max_position: !degrees 180.0 - max_velocity: !degrees 60.0 - min_position: !degrees -180.0 - wrist_2_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 180.0 - max_effort: 28.0 - max_position: !degrees 180.0 - max_velocity: !degrees 60.0 - min_position: !degrees -180.0 - wrist_3_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 180.0 - max_effort: 28.0 - max_position: !degrees 360.0 - max_velocity: !degrees 60.0 - min_position: !degrees -360.0 - robotiq_85_left_knuckle_joint: - has_velocity_limits: true - max_velocity: 0.5 - has_acceleration_limits: true - max_acceleration: 1.0 diff --git a/src/picknik_ur_mobile_config/config/moveit/joint_limits.yaml b/src/picknik_ur_mobile_config/config/moveit/joint_limits.yaml deleted file mode 100644 index d89a0792..00000000 --- a/src/picknik_ur_mobile_config/config/moveit/joint_limits.yaml +++ /dev/null @@ -1,117 +0,0 @@ -# Joints limits -# -# Sources: -# -# - Universal Robots e-Series, User Manual, UR5e, Version 5.8 -# https://s3-eu-west-1.amazonaws.com/ur-support-site/69091/99404_UR5e_User_Manual_en_Global.pdf -# - Support > Articles > UR articles > Max. joint torques -# https://www.universal-robots.com/articles/ur-articles/max-joint-torques -# retrieved: 2020-06-16, last modified: 2020-06-09 -# -# NOTE: Acceleration limits are not publicly available so we have picked a reasonable upper limit -joint_limits: - linear_x_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: 0.1 - max_effort: 150.0 - max_position: 5.0 - max_velocity: 0.175 - min_position: -5.0 - linear_y_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: 0.1 - max_effort: 150.0 - max_position: 5.0 - max_velocity: 0.175 - min_position: -5.0 - rotational_yaw_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 90.0 - max_effort: 150.0 - max_position: !degrees 180.0 - max_velocity: !degrees 30.0 - min_position: !degrees -180.0 - shoulder_pan_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 30.0 - max_effort: 150.0 - max_position: !degrees 180.0 - max_velocity: !degrees 30.0 - min_position: !degrees -180.0 - shoulder_lift_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 30.0 - max_effort: 150.0 - max_position: !degrees 90.0 - max_velocity: !degrees 30.0 - min_position: !degrees -270.0 - elbow_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 30.0 - max_effort: 150.0 - # we artificially limit this joint to half its actual joint position limit - # to avoid (MoveIt/OMPL) planning problems, as due to the physical - # construction of the robot, it's impossible to rotate the 'elbow_joint' - # over more than approx +- 1 pi (the shoulder lift joint gets in the way). - # - # This leads to planning problems as the search space will be divided into - # two sections, with no connections from one to the other. - # - # Refer to https://github.com/ros-industrial/universal_robot/issues/265 for - # more information. - max_position: !degrees 180.0 - max_velocity: !degrees 30.0 - min_position: !degrees -180.0 - wrist_1_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 30.0 - max_effort: 28.0 - max_position: !degrees 180.0 - max_velocity: !degrees 60.0 - min_position: !degrees -180.0 - wrist_2_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 30.0 - max_effort: 28.0 - max_position: !degrees 180.0 - max_velocity: !degrees 60.0 - min_position: !degrees -180.0 - wrist_3_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 30.0 - max_effort: 28.0 - max_position: !degrees 360.0 - max_velocity: !degrees 60.0 - min_position: !degrees -360.0 - robotiq_85_left_knuckle_joint: - has_velocity_limits: true - max_velocity: 0.5 - has_acceleration_limits: true - max_acceleration: 1.0 diff --git a/src/picknik_ur_mobile_config/config/moveit/ompl_planning.yaml b/src/picknik_ur_mobile_config/config/moveit/ompl_planning.yaml deleted file mode 100644 index 186158d5..00000000 --- a/src/picknik_ur_mobile_config/config/moveit/ompl_planning.yaml +++ /dev/null @@ -1,32 +0,0 @@ -planning_plugins: - - ompl_interface/OMPLPlanner -# The order of the elements in the adapter corresponds to the order they are processed by the motion planning pipeline. -request_adapters: - - default_planning_request_adapters/ResolveConstraintFrames - - default_planning_request_adapters/ValidateWorkspaceBounds - - default_planning_request_adapters/CheckStartStateBounds - - default_planning_request_adapters/CheckStartStateCollision -response_adapters: - - default_planning_response_adapters/AddTimeOptimalParameterization - - default_planning_response_adapters/ValidateSolution - -planner_configs: - APSConfigDefault: - type: geometric::AnytimePathShortening - shortcut: 1 # Attempt to shortcut all new solution paths - hybridize: 1 # Compute hybrid solution trajectories - max_hybrid_paths: 32 # Number of hybrid paths generated per iteration - num_planners: 16 # The number of default planners to use for planning - planners: "RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect" # A comma-separated list of planner types (e.g., "PRM,EST,RRTConnect"Optionally, planner parameters can be passed to change the default:"PRM[max_nearest_neighbors=5],EST[goal_bias=.5],RRT[range=10. goal_bias=.1]" - RRTConnectkConfigDefault: - type: geometric::RRTConnect - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() -manipulator: - default_planner_config: RRTConnectkConfigDefault - planner_configs: - - APSConfigDefault - - RRTConnectkConfigDefault - enforce_constrained_state_space: true - ##Note: commenting the following line lets moveit chose RRTConnect as default planner rather than LBKPIECE - projection_evaluator: joints(shoulder_pan_joint,shoulder_lift_joint) - longest_valid_segment_fraction: 0.01 diff --git a/src/picknik_ur_mobile_config/config/moveit/picknik_ur.srdf b/src/picknik_ur_mobile_config/config/moveit/picknik_ur.srdf deleted file mode 100644 index e0be97c8..00000000 --- a/src/picknik_ur_mobile_config/config/moveit/picknik_ur.srdf +++ /dev/null @@ -1,241 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_mobile_config/config/moveit/pilz_cartesian_limits.yaml b/src/picknik_ur_mobile_config/config/moveit/pilz_cartesian_limits.yaml deleted file mode 100644 index 1633938e..00000000 --- a/src/picknik_ur_mobile_config/config/moveit/pilz_cartesian_limits.yaml +++ /dev/null @@ -1,6 +0,0 @@ -# Cartesian limits for the Pilz planner -cartesian_limits: - max_trans_vel: 0.1 - max_trans_acc: 0.1 - max_trans_dec: -0.1 - max_rot_vel: 0.1 diff --git a/src/picknik_ur_mobile_config/config/moveit/pilz_industrial_motion_planner_planning.yaml b/src/picknik_ur_mobile_config/config/moveit/pilz_industrial_motion_planner_planning.yaml deleted file mode 100644 index dd179d2d..00000000 --- a/src/picknik_ur_mobile_config/config/moveit/pilz_industrial_motion_planner_planning.yaml +++ /dev/null @@ -1,13 +0,0 @@ -planning_plugins: - - pilz_industrial_motion_planner/CommandPlanner -default_planner_config: LIN -request_adapters: - - default_planning_request_adapters/ResolveConstraintFrames - - default_planning_request_adapters/ValidateWorkspaceBounds - - default_planning_request_adapters/CheckStartStateBounds - - default_planning_request_adapters/CheckStartStateCollision -response_adapters: - - default_planning_response_adapters/ValidateSolution -capabilities: >- - pilz_industrial_motion_planner/MoveGroupSequenceAction - pilz_industrial_motion_planner/MoveGroupSequenceService diff --git a/src/picknik_ur_mobile_config/config/moveit/sensors_3d.yaml b/src/picknik_ur_mobile_config/config/moveit/sensors_3d.yaml deleted file mode 100644 index 12ac1297..00000000 --- a/src/picknik_ur_mobile_config/config/moveit/sensors_3d.yaml +++ /dev/null @@ -1,25 +0,0 @@ -sensors: - - scene_scan_camera -scene_scan_camera: - # The name of the Octomap updater plugin that we are using. - sensor_plugin: "moveit_studio_plugins/PointCloudServiceOctomapUpdater" - # Specifies the topic to listen on for a point cloud. - # Set to an empty topic to disable. - point_cloud_service_name: "/point_cloud_service" - # Points further than this will not be used (in meters). - max_range: 1.5 - # Choose one of every 'point_subsample' points (select all if set to 1). - point_subsample: 1 - # Should always be >= 1.0. Scale up collision shapes in the scene before excluding them from the octomap. - padding_scale: 1.0 - # Absolute padding around scaled collision shapes when excluding them from the octomap (in meters). - padding_offset: 0.01 - # The octomap representation will be updated at rate less than or equal to this value. - max_update_rate: 0.1 - -# Specifies the resolution at which the octomap is maintained (in meters). -octomap_resolution: 0.01 -# Specifies the coordinate frame in which the Octomap representation will be stored. -# Note! When an OccupancyMonitor instance is initialized by the PlanningSceneMonitor, -# this frame parameter will not be used. Instead, the frame defaults to the planning frame. -octomap_frame: "base_link" diff --git a/src/picknik_ur_mobile_config/config/moveit/stomp_planning.yaml b/src/picknik_ur_mobile_config/config/moveit/stomp_planning.yaml deleted file mode 100644 index 7447a8ff..00000000 --- a/src/picknik_ur_mobile_config/config/moveit/stomp_planning.yaml +++ /dev/null @@ -1,21 +0,0 @@ -planning_plugins: - - stomp_moveit/StompPlanner -# The order of the elements in the adapter corresponds to the order they are processed by the motion planning pipeline. -request_adapters: - - default_planning_request_adapters/ResolveConstraintFrames - - default_planning_request_adapters/ValidateWorkspaceBounds - - default_planning_request_adapters/CheckStartStateBounds - - default_planning_request_adapters/CheckStartStateCollision -response_adapters: - - default_planning_response_adapters/AddTimeOptimalParameterization - - default_planning_response_adapters/ValidateSolution - -stomp_moveit: - num_timesteps: 60 - num_iterations: 40 - num_iterations_after_valid: 0 - num_rollouts: 30 - max_rollouts: 30 - exponentiated_cost_sensitivity: 0.8 - control_cost_weight: 0.1 - delta_t: 0.1 diff --git a/src/picknik_ur_mobile_config/config/moveit/trac_ik_kinematics_distance.yaml b/src/picknik_ur_mobile_config/config/moveit/trac_ik_kinematics_distance.yaml deleted file mode 100644 index 65f77d5c..00000000 --- a/src/picknik_ur_mobile_config/config/moveit/trac_ik_kinematics_distance.yaml +++ /dev/null @@ -1,6 +0,0 @@ -manipulator: - kinematics_solver: trac_ik_kinematics_plugin/TRAC_IKKinematicsPlugin - kinematics_solver_timeout: 0.005 - kinematics_solver_attempts: 3 - epsilon: 0.0001 - solve_type: "Distance" diff --git a/src/picknik_ur_mobile_config/config/moveit/trac_ik_kinematics_speed.yaml b/src/picknik_ur_mobile_config/config/moveit/trac_ik_kinematics_speed.yaml deleted file mode 100644 index 90559540..00000000 --- a/src/picknik_ur_mobile_config/config/moveit/trac_ik_kinematics_speed.yaml +++ /dev/null @@ -1,6 +0,0 @@ -manipulator: - kinematics_solver: trac_ik_kinematics_plugin/TRAC_IKKinematicsPlugin - kinematics_solver_timeout: 0.005 - kinematics_solver_attempts: 3 - epsilon: 0.0001 - solve_type: "Speed" diff --git a/src/picknik_ur_mobile_config/config/moveit/ur_servo.yaml b/src/picknik_ur_mobile_config/config/moveit/ur_servo.yaml deleted file mode 100644 index b89598cc..00000000 --- a/src/picknik_ur_mobile_config/config/moveit/ur_servo.yaml +++ /dev/null @@ -1,64 +0,0 @@ -############################################### -# Modify all parameters related to servoing here -############################################### - -# Enable dynamic parameter updates -enable_parameter_update: true - -## Properties of incoming commands -command_in_type: "speed_units" # "unitless"> in the range [-1:1], as if from joystick. "speed_units"> cmds are in m/s and rad/s -scale: - # Scale parameters are only used if command_in_type=="unitless" - linear: 2.0 # Max linear velocity. Meters per publish_period. Unit is [m/s]. Only used for Cartesian commands. - rotational: 3.0 # Max angular velocity. Rads per publish_period. Unit is [rad/s]. Only used for Cartesian commands. - # Max joint angular/linear velocity. Rads or Meters per publish period. Only used for joint commands on joint_command_in_topic. - joint: 2.0 - -# Default to driving the arm at 50% maximum speed. -override_velocity_scaling_factor: 0.5 - -## Properties of outgoing commands -publish_period: 0.01 # 1/Nominal publish rate [seconds] -max_expected_latency: 0.1 # delay between sending a command and the robot executing it [seconds] - -# What type of topic does your robot driver expect? -# Currently supported are std_msgs/Float64MultiArray or trajectory_msgs/JointTrajectory -command_out_type: trajectory_msgs/JointTrajectory - -# What to publish? Can save some bandwidth as most robots only require positions or velocities -publish_joint_positions: true -publish_joint_velocities: true -publish_joint_accelerations: false - -## Plugins for smoothing outgoing commands -use_smoothing: true -smoothing_filter_plugin_name: "online_signal_smoothing::AccelerationLimitedPlugin" -acceleration_filter_update_period: 0.01 # [seconds] Must match the publish_period parameter - -## MoveIt properties -move_group_name: manipulator # Often 'manipulator' or 'arm' -acceleration_filter_planning_group_name: manipulator # Often 'manipulator' or 'arm' -is_primary_planning_scene_monitor: false # The MoveGroup node maintains the planning scene, so Servo needs to get its world info from there. -monitored_planning_scene_topic: /monitored_planning_scene - -## Stopping behaviour -incoming_command_timeout: 0.1 # Stop servoing if X seconds elapse without a new command - -## Configure handling of singularities and joint limits -lower_singularity_threshold: 30.0 # Start decelerating when the condition number hits this (close to singularity) -hard_stop_singularity_threshold: 50.0 # Stop when the condition number hits this -joint_limit_margins: [0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] # added as a buffer to joint limits [radians]. If moving quickly, make this larger. - -## Topic names -cartesian_command_in_topic: ~/delta_twist_cmds # Topic for incoming Cartesian twist commands -joint_command_in_topic: ~/delta_joint_cmds # Topic for incoming joint angle commands -joint_topic: /joint_states -status_topic: ~/status # Publish status to this topic -command_out_topic: /servo_controller/joint_trajectory # Publish outgoing commands here - -## Collision checking for the entire robot body -check_collisions: true # Check collisions? -check_octomap_collisions: false # Check collisions with octomap? -collision_check_rate: 10.0 # [Hz] Collision-checking can easily bog down a CPU if done too often. -self_collision_proximity_threshold: 0.006 # Start decelerating when a self-collision is this far [m] -scene_collision_proximity_threshold: 0.02 # Start decelerating when a scene collision is this far [m] diff --git a/src/picknik_ur_mobile_config/description/LICENSE b/src/picknik_ur_mobile_config/description/LICENSE deleted file mode 100644 index f24e07cb..00000000 --- a/src/picknik_ur_mobile_config/description/LICENSE +++ /dev/null @@ -1,26 +0,0 @@ -Copyright 2018 ROS Industrial Consortium - -Redistribution and use in source and binary forms, with or without modification, -are permitted provided that the following conditions are met: - -1. Redistributions of source code must retain the above copyright notice, this -list of conditions and the following disclaimer. - -2. Redistributions in binary form must reproduce the above copyright notice, -this list of conditions and the following disclaimer in the documentation and/or -other materials provided with the distribution. - -3. Neither the name of the copyright holder nor the names of its contributors -may be used to endorse or promote products derived from this software without -specific prior written permission. - -THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND -ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED -WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE -DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR -ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES -(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; -LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON -ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT -(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS -SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. diff --git a/src/picknik_ur_mobile_config/description/picknik_ur.xacro b/src/picknik_ur_mobile_config/description/picknik_ur.xacro deleted file mode 100644 index 7947583f..00000000 --- a/src/picknik_ur_mobile_config/description/picknik_ur.xacro +++ /dev/null @@ -1,118 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_mobile_config/description/picknik_ur_attachments_macro.xacro b/src/picknik_ur_mobile_config/description/picknik_ur_attachments_macro.xacro deleted file mode 100644 index f3279ab2..00000000 --- a/src/picknik_ur_mobile_config/description/picknik_ur_attachments_macro.xacro +++ /dev/null @@ -1,447 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - 100000.0 - 100000.0 - - - - - 1e+5 - 1 - 0 - 0.2 - 0.002 - 0 - - - - - - - - - - - - - - - - - - - - - - - - 100000.0 - 100000.0 - - - - - 1e+5 - 1 - 0 - 0.2 - 0.002 - 0 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_mobile_config/description/picknik_ur_mujoco_ros2_control.xacro b/src/picknik_ur_mobile_config/description/picknik_ur_mujoco_ros2_control.xacro deleted file mode 100644 index dae3c12e..00000000 --- a/src/picknik_ur_mobile_config/description/picknik_ur_mujoco_ros2_control.xacro +++ /dev/null @@ -1,109 +0,0 @@ - - - - - - 1 - - - 0.0 - - - - - 1 - - - 0.0 - - - - - - ${-2*pi} - ${2*pi} - - - 0.0 - - - - - - - -2.41 - 2.41 - -1.57 - - - -1.57 - - - - - - - ${-2*pi} - ${2*pi} - - - -3.14 - - - - - - - -2.66 - 2.66 - - - -2.51 - - - - - - - ${-2*pi} - ${2*pi} - - - 0.0 - - - - - - - -2.23 - 2.23 - - - 0.96 - - - - - - - - 0.7929 - - - - - - - - - picknik_mujoco_ros/MujocoSystem - description/scene.xml - picknik_ur_mobile_config - 10 - 60 - 10 - - - - diff --git a/src/picknik_ur_mobile_config/description/scene.xml b/src/picknik_ur_mobile_config/description/scene.xml deleted file mode 100644 index c7e3b8bc..00000000 --- a/src/picknik_ur_mobile_config/description/scene.xml +++ /dev/null @@ -1,37 +0,0 @@ - - - - - - - - - - diff --git a/src/picknik_ur_mobile_config/description/ur5e.xml b/src/picknik_ur_mobile_config/description/ur5e.xml deleted file mode 100644 index b8283f3e..00000000 --- a/src/picknik_ur_mobile_config/description/ur5e.xml +++ /dev/null @@ -1,917 +0,0 @@ - - - - diff --git a/src/picknik_ur_mobile_config/launch/agent_bridge.launch.xml b/src/picknik_ur_mobile_config/launch/agent_bridge.launch.xml deleted file mode 100644 index b2aa7543..00000000 --- a/src/picknik_ur_mobile_config/launch/agent_bridge.launch.xml +++ /dev/null @@ -1,6 +0,0 @@ - - - - diff --git a/src/picknik_ur_mobile_config/objectives/apriltag_detection_config.yaml b/src/picknik_ur_mobile_config/objectives/apriltag_detection_config.yaml deleted file mode 100644 index f1a96237..00000000 --- a/src/picknik_ur_mobile_config/objectives/apriltag_detection_config.yaml +++ /dev/null @@ -1,9 +0,0 @@ -DetectAprilTags: - apriltag_family_name: 36h11 - apriltag_size: 0.04 - max_hamming: 0 - n_threads: 1 - quad_decimate: 1 - quad_sigma: 0.1 - refine_edges: false - z_up: false diff --git a/src/picknik_ur_mobile_config/objectives/apriltag_pick_object.xml b/src/picknik_ur_mobile_config/objectives/apriltag_pick_object.xml deleted file mode 100644 index 2f4e297d..00000000 --- a/src/picknik_ur_mobile_config/objectives/apriltag_pick_object.xml +++ /dev/null @@ -1,50 +0,0 @@ - - - - - - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_mobile_config/objectives/pick_first_object_in_vector.xml b/src/picknik_ur_mobile_config/objectives/pick_first_object_in_vector.xml deleted file mode 100644 index 08e9b6a6..00000000 --- a/src/picknik_ur_mobile_config/objectives/pick_first_object_in_vector.xml +++ /dev/null @@ -1,41 +0,0 @@ - - - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_mobile_config/objectives/pick_object.xml b/src/picknik_ur_mobile_config/objectives/pick_object.xml deleted file mode 100644 index 9c403326..00000000 --- a/src/picknik_ur_mobile_config/objectives/pick_object.xml +++ /dev/null @@ -1,62 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_mobile_config/objectives/pick_object_config.yaml b/src/picknik_ur_mobile_config/objectives/pick_object_config.yaml deleted file mode 100644 index 09ca7d6e..00000000 --- a/src/picknik_ur_mobile_config/objectives/pick_object_config.yaml +++ /dev/null @@ -1,11 +0,0 @@ -SetupMTCPickObject: - # The lift vector points to the direction of the positive z-axis of the frame marked as the world frame. - world_frame_name: "world" - arm_group_name: "manipulator" - end_effector_group_name: "gripper" - end_effector_name: "moveit_ee" - hand_frame_name: "grasp_link" - end_effector_closed_pose_name: "close" - - approach_distance: 0.1 - lift_distance: 0.1 diff --git a/src/picknik_ur_mobile_config/objectives/pick_up_cube.xml b/src/picknik_ur_mobile_config/objectives/pick_up_cube.xml deleted file mode 100644 index 8bb2bea7..00000000 --- a/src/picknik_ur_mobile_config/objectives/pick_up_cube.xml +++ /dev/null @@ -1,11 +0,0 @@ - - - - - - - - - - - diff --git a/src/picknik_ur_mobile_config/objectives/take_snap.xml b/src/picknik_ur_mobile_config/objectives/take_snap.xml deleted file mode 100644 index 7fefe4db..00000000 --- a/src/picknik_ur_mobile_config/objectives/take_snap.xml +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_mobile_config/objectives/wrist_snap.xml b/src/picknik_ur_mobile_config/objectives/wrist_snap.xml deleted file mode 100644 index 80209f36..00000000 --- a/src/picknik_ur_mobile_config/objectives/wrist_snap.xml +++ /dev/null @@ -1,14 +0,0 @@ - - - - - - - - - - - - - - diff --git a/src/picknik_ur_mobile_config/package.xml b/src/picknik_ur_mobile_config/package.xml deleted file mode 100644 index 70f401ac..00000000 --- a/src/picknik_ur_mobile_config/package.xml +++ /dev/null @@ -1,46 +0,0 @@ - - - picknik_ur_mobile_config - 6.0.0 - - - MuJoCo simulation configuration package for Picknik's UR robot on a mobile - base - - - MoveIt Pro Maintainer - - BSD-3-Clause - - ament_cmake - - admittance_controller - moveit_planners_stomp - moveit_ros_perception - moveit_studio_agent - moveit_studio_behavior - moveit_studio_ur_pstop_manager - picknik_accessories - realsense2_camera - realsense2_description - robotiq_description - robotiq_controllers - trac_ik_kinematics_plugin - ur_description - ur_robot_driver - picknik_mujoco_ros - ridgeback_description - - ament_lint_auto - - ament_clang_format - ament_clang_tidy - ament_cmake_copyright - ament_cmake_lint_cmake - picknik_ament_copyright - ament_flake8 - - - ament_cmake - - diff --git a/src/picknik_ur_mobile_config/waypoints/ur_waypoints.yaml b/src/picknik_ur_mobile_config/waypoints/ur_waypoints.yaml deleted file mode 100644 index 4a325ccb..00000000 --- a/src/picknik_ur_mobile_config/waypoints/ur_waypoints.yaml +++ /dev/null @@ -1,47 +0,0 @@ -- description: '' - favorite: false - joint_group_names: - - gripper - - linear_actuator - - manipulator - joint_state: - effort: [] - header: - frame_id: '' - stamp: - nanosec: 0 - sec: 0 - name: - - robotiq_85_left_knuckle_joint - - linear_x_joint - - linear_y_joint - - rotational_yaw_joint - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - position: - - 0.0 - - 0.4 - - 0.4 - - 1.0 - - 0.0 - - -1.5708 - - 0.785398 - - -1.2948195437205516 - - -1.5708 - - 0.0 - velocity: [] - multi_dof_joint_state: - header: - frame_id: '' - stamp: - nanosec: 0 - sec: 0 - joint_names: [] - transforms: [] - twist: [] - wrench: [] - name: Look at Table diff --git a/src/picknik_ur_mock_hw_config/CMakeLists.txt b/src/picknik_ur_mock_hw_config/CMakeLists.txt deleted file mode 100644 index 77c63461..00000000 --- a/src/picknik_ur_mock_hw_config/CMakeLists.txt +++ /dev/null @@ -1,23 +0,0 @@ -cmake_minimum_required(VERSION 3.22) -project(picknik_ur_mock_hw_config) - -find_package(ament_cmake REQUIRED) - -install( - DIRECTORY - config - description - launch - meshes - objectives - waypoints - DESTINATION - share/${PROJECT_NAME} -) - -if(BUILD_TESTING) - find_package(ament_lint_auto REQUIRED) - ament_lint_auto_find_test_dependencies() -endif() - -ament_package() diff --git a/src/picknik_ur_mock_hw_config/LICENSE b/src/picknik_ur_mock_hw_config/LICENSE deleted file mode 100644 index 574ef079..00000000 --- a/src/picknik_ur_mock_hw_config/LICENSE +++ /dev/null @@ -1,25 +0,0 @@ -Redistribution and use in source and binary forms, with or without -modification, are permitted provided that the following conditions are met: - - * Redistributions of source code must retain the above copyright - notice, this list of conditions and the following disclaimer. - - * Redistributions in binary form must reproduce the above copyright - notice, this list of conditions and the following disclaimer in the - documentation and/or other materials provided with the distribution. - - * Neither the name of the copyright holder nor the names of its - contributors may be used to endorse or promote products derived from - this software without specific prior written permission. - -THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -POSSIBILITY OF SUCH DAMAGE. diff --git a/src/picknik_ur_mock_hw_config/README.md b/src/picknik_ur_mock_hw_config/README.md deleted file mode 100644 index f5d8dd35..00000000 --- a/src/picknik_ur_mock_hw_config/README.md +++ /dev/null @@ -1,5 +0,0 @@ -# picknik_ur_mock_hw_config - -A MoveIt Pro configuration to simulate a UR arm using mock hardware. - -For detailed documentation see: [MoveIt Pro Documentation](https://docs.picknik.ai/) diff --git a/src/picknik_ur_mock_hw_config/config/config.yaml b/src/picknik_ur_mock_hw_config/config/config.yaml deleted file mode 100644 index 0cc6e631..00000000 --- a/src/picknik_ur_mock_hw_config/config/config.yaml +++ /dev/null @@ -1,29 +0,0 @@ -based_on_package: "picknik_ur_base_config" - -hardware: - simulated: True - - # Update robot description for machine tending world. - robot_description: - urdf: - package: "picknik_ur_mock_hw_config" - path: "description/picknik_ur_machine_tending.xacro" - srdf: - package: "picknik_ur_mock_hw_config" - path: "config/moveit/picknik_ur_machine_tending.srdf" - -moveit_params: - servo: - package: "picknik_ur_mock_hw_config" - path: "config/moveit/ur_servo.yaml" - -objectives: - waypoints_file: - package_name: "picknik_ur_mock_hw_config" - relative_path: "waypoints/machine_tending_waypoints.yaml" - objective_library_paths: - # You must use a unique key for each package. - # The picknik_ur_base_config uses "core" - mock_hardware_objectives: - package_name: "picknik_ur_mock_hw_config" - relative_path: "objectives" diff --git a/src/picknik_ur_mock_hw_config/config/initial_positions.yaml b/src/picknik_ur_mock_hw_config/config/initial_positions.yaml deleted file mode 100644 index 0d8b33f7..00000000 --- a/src/picknik_ur_mock_hw_config/config/initial_positions.yaml +++ /dev/null @@ -1,6 +0,0 @@ -shoulder_pan_joint: 0.0 -shoulder_lift_joint: -1.41 -elbow_joint: -0.7 -wrist_1_joint: -2.12 -wrist_2_joint: 1.67 -wrist_3_joint: 0.0 diff --git a/src/picknik_ur_mock_hw_config/config/moveit/picknik_ur_machine_tending.srdf b/src/picknik_ur_mock_hw_config/config/moveit/picknik_ur_machine_tending.srdf deleted file mode 100644 index a0aa14f6..00000000 --- a/src/picknik_ur_mock_hw_config/config/moveit/picknik_ur_machine_tending.srdf +++ /dev/null @@ -1,203 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_mock_hw_config/config/moveit/ur_servo.yaml b/src/picknik_ur_mock_hw_config/config/moveit/ur_servo.yaml deleted file mode 100644 index 49151897..00000000 --- a/src/picknik_ur_mock_hw_config/config/moveit/ur_servo.yaml +++ /dev/null @@ -1,62 +0,0 @@ -# Enable dynamic parameter updates -enable_parameter_update: true - -## Properties of incoming commands -command_in_type: "speed_units" # "unitless"> in the range [-1:1], as if from joystick. "speed_units"> cmds are in m/s and rad/s -scale: - # Scale parameters are only used if command_in_type=="unitless" - linear: 1.0 # Max linear velocity. Meters per publish_period. Unit is [m/s]. Only used for Cartesian commands. - rotational: 1.5 # Max angular velocity. Rads per publish_period. Unit is [rad/s]. Only used for Cartesian commands. - # Max joint angular/linear velocity. Rads or Meters per publish period. Only used for joint commands on joint_command_in_topic. - joint: 1.0 - -# Default to driving the arm at 50% maximum speed. -override_velocity_scaling_factor: 0.5 - -## Properties of outgoing commands -publish_period: 0.01 # 1/Nominal publish rate [seconds] -max_expected_latency: 0.1 # delay between sending a command and the robot executing it [seconds] - -low_latency_mode: false # Set this to true to publish as soon as an incoming Twist command is received (publish_period is ignored) - -# What type of topic does your robot driver expect? -# Currently supported are std_msgs/Float64MultiArray or trajectory_msgs/JointTrajectory -command_out_type: trajectory_msgs/JointTrajectory - -# What to publish? Can save some bandwidth as most robots only require positions or velocities -publish_joint_positions: true -publish_joint_velocities: true -publish_joint_accelerations: false - -## Plugins for smoothing outgoing commands -use_smoothing: true -smoothing_filter_plugin_name: "online_signal_smoothing::AccelerationLimitedPlugin" -acceleration_filter_update_period: 0.01 # [seconds] Must match the publish_period parameter - -## MoveIt properties -move_group_name: manipulator # Often 'manipulator' or 'arm' -acceleration_filter_planning_group_name: manipulator # Often 'manipulator' or 'arm' -is_primary_planning_scene_monitor: false # The MoveGroup node maintains the planning scene, so Servo needs to get its world info from there. -monitored_planning_scene_topic: /monitored_planning_scene - -## Stopping behaviour -incoming_command_timeout: 0.1 # Stop servoing if X seconds elapse without a new command - -## Configure handling of singularities and joint limits -lower_singularity_threshold: 25.0 # Start decelerating when the condition number hits this (close to singularity) -hard_stop_singularity_threshold: 40.0 # Stop when the condition number hits this -joint_limit_margins: [0.1, 0.1, 0.1, 0.1, 0.1, 0.1] # added as a buffer to joint limits [radians]. If moving quickly, make this larger. - -## Topic names -cartesian_command_in_topic: ~/delta_twist_cmds # Topic for incoming Cartesian twist commands -joint_command_in_topic: ~/delta_joint_cmds # Topic for incoming joint angle commands -joint_topic: /joint_states -status_topic: ~/status # Publish status to this topic -command_out_topic: /servo_controller/joint_trajectory # Publish outgoing commands here - -## Collision checking for the entire robot body -check_collisions: true # Check collisions? -check_octomap_collisions: false # Check collisions with octomap? -collision_check_rate: 20.0 # [Hz] Collision-checking can easily bog down a CPU if done too often. -self_collision_proximity_threshold: 0.006 # Start decelerating when a self-collision is this far [m] -scene_collision_proximity_threshold: 0.02 # Start decelerating when a scene collision is this far [m] diff --git a/src/picknik_ur_mock_hw_config/description/environment.xacro b/src/picknik_ur_mock_hw_config/description/environment.xacro deleted file mode 100644 index a264a3a4..00000000 --- a/src/picknik_ur_mock_hw_config/description/environment.xacro +++ /dev/null @@ -1,163 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_mock_hw_config/description/picknik_ur_machine_tending.xacro b/src/picknik_ur_mock_hw_config/description/picknik_ur_machine_tending.xacro deleted file mode 100644 index 601f292b..00000000 --- a/src/picknik_ur_mock_hw_config/description/picknik_ur_machine_tending.xacro +++ /dev/null @@ -1,56 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_mock_hw_config/launch/agent_bridge.launch.xml b/src/picknik_ur_mock_hw_config/launch/agent_bridge.launch.xml deleted file mode 100644 index b2aa7543..00000000 --- a/src/picknik_ur_mock_hw_config/launch/agent_bridge.launch.xml +++ /dev/null @@ -1,6 +0,0 @@ - - - - diff --git a/src/picknik_ur_mock_hw_config/meshes/base.dae b/src/picknik_ur_mock_hw_config/meshes/base.dae deleted file mode 100644 index d5fee37c..00000000 --- a/src/picknik_ur_mock_hw_config/meshes/base.dae +++ /dev/null @@ -1,241 +0,0 @@ - - - - - Blender User - Blender 3.6.1 commit date:2023-07-17, commit time:12:50, hash:8bda729ef4dc - - 2023-07-21T21:09:34 - 2023-07-21T21:09:34 - - Z_UP - - - - - - 0 0 0 - 1 - 0 - 0.001599967 - - - - - 0 - 0 - 1 - 1 - 1 - 1 - 1 - 0 - 0 - 0 - 0 - 25 - 45 - 0.15 - 0 - 1 - 2 - 0.04999995 - 40 - 1 - 512 - 3 - 1 - 0 - 0 - 0.25 - 0.25 - 0.25 - - - - - - - - - - base - - - - - base-surface - - - - - - 0 0 0 1 - - - - - - 1 - - - 1.45 - - - - - - - - - - base - - - - - base-surface - - - - - - 0 0 0 1 - - - - - - 1.45 - - - - - - - - - - base - - - - - base-surface - - - - - - 0 0 0 1 - - - - - - 1 - - - 1.45 - - - - - - - - - base.png - - - - - - - - - - - - - - - - - - -0.1815438 0.1891106 -0.2337593 -0.1777662 0.1887385 -0.2337593 -0.1815438 0.1891106 -0.2235848 -0.1853216 0.1887385 -0.2337593 -0.1889541 0.1876367 -0.2337593 -0.1853216 0.1887385 -0.2235848 -0.1889541 0.1876367 -0.2235848 -0.1923018 0.1858472 -0.2235848 -0.1952361 0.1834391 -0.2235848 -0.1923018 0.1858472 -0.2337593 -0.1952361 0.1834391 -0.2337593 -0.1976442 0.1805048 -0.2337593 -0.1994337 0.1771571 -0.2337593 -0.1976442 0.1805048 -0.2235848 -0.1994337 0.1771571 -0.2235848 -0.2005355 0.1735246 -0.2235848 -0.2009076 0.1697469 -0.2235848 -0.2005355 0.1735246 -0.2337593 -0.2009076 0.1697469 -0.2337593 -0.2005355 0.1659691 -0.2337593 -0.1994337 0.1623367 -0.2337593 -0.2005355 0.1659691 -0.2235848 -0.1994337 0.1623367 -0.2235848 -0.1976442 0.1589889 -0.2235848 -0.1952361 0.1560546 -0.2235848 -0.1976442 0.1589889 -0.2337593 -0.1952361 0.1560546 -0.2337593 -0.1923018 0.1536465 -0.2337593 -0.1889541 0.1518571 -0.2337593 -0.1923018 0.1536465 -0.2235848 -0.1889541 0.1518571 -0.2235848 -0.1853216 0.1507551 -0.2235848 -0.1815438 0.1503831 -0.2235848 -0.1853216 0.1507551 -0.2337593 -0.1815438 0.1503831 -0.2337593 -0.1777662 0.1507551 -0.2337593 -0.1741337 0.1518571 -0.2337593 -0.1777662 0.1507551 -0.2235848 -0.1741337 0.1518571 -0.2235848 -0.1707859 0.1536465 -0.2235848 -0.1678516 0.1560546 -0.2235848 -0.1707859 0.1536465 -0.2337593 -0.1678516 0.1560546 -0.2337593 -0.1654434 0.1589889 -0.2337593 -0.1636541 0.1623367 -0.2337593 -0.1654434 0.1589889 -0.2235848 -0.1636541 0.1623367 -0.2235848 -0.1625521 0.1659691 -0.2235848 -0.1621801 0.1697469 -0.2235848 -0.1625521 0.1659691 -0.2337593 -0.1621801 0.1697469 -0.2337593 -0.1625521 0.1735246 -0.2337593 -0.1636541 0.1771571 -0.2337593 -0.1625521 0.1735246 -0.2235848 -0.1636541 0.1771571 -0.2235848 -0.1654434 0.1805048 -0.2235848 -0.1678516 0.1834391 -0.2235848 -0.1654434 0.1805048 -0.2337593 -0.1678516 0.1834391 -0.2337593 -0.1707859 0.1858472 -0.2337593 -0.1741337 0.1876367 -0.2337593 -0.1707859 0.1858472 -0.2235848 -0.1741337 0.1876367 -0.2235848 -0.1777662 0.1887385 -0.2235848 0 0.2 -0.1720588 0 0.2 0.2248403 0.01960343 0.1990369 -0.1720588 0.01960343 0.1990369 0.2248403 0.03901803 0.196157 -0.1720588 0.03901803 0.196157 0.2248403 0.05805689 0.191388 -0.1720588 0.05805689 0.191388 0.2248403 0.07653665 0.1847759 -0.1720588 0.07653665 0.1847759 0.2248403 0.09427934 0.1763842 -0.1720588 0.09427934 0.1763842 0.2248403 0.111114 0.1662939 -0.1720588 0.111114 0.1662939 0.2248403 0.1268786 0.1546021 -0.1720588 0.1268786 0.1546021 0.2248403 0.1414213 0.1414213 -0.1720588 0.1414213 0.1414213 0.2248403 0.1546021 0.1268786 -0.1720588 0.1546021 0.1268786 0.2248403 0.1662939 0.111114 -0.1720588 0.1662939 0.111114 0.2248403 0.1763842 0.09427934 -0.1720588 0.1763842 0.09427934 0.2248403 0.1847759 0.07653665 -0.1720588 0.1847759 0.07653665 0.2248403 0.191388 0.05805689 -0.1720588 0.191388 0.05805689 0.2248403 0.196157 0.03901803 -0.1720588 0.196157 0.03901803 0.2248403 0.1990369 0.01960343 -0.1720588 0.1990369 0.01960343 0.2248403 0.2 0 -0.1720588 0.2 0 0.2248403 0.1990369 -0.01960343 -0.1720588 0.1990369 -0.01960343 0.2248403 0.196157 -0.03901803 -0.1720588 0.196157 -0.03901803 0.2248403 0.191388 -0.05805689 -0.1720588 0.191388 -0.05805689 0.2248403 0.1847759 -0.07653665 -0.1720588 0.1847759 -0.07653665 0.2248403 0.1763842 -0.09427934 -0.1720588 0.1763842 -0.09427934 0.2248403 0.1662939 -0.111114 -0.1720588 0.1662939 -0.111114 0.2248403 0.1546021 -0.1268786 -0.1720588 0.1546021 -0.1268786 0.2248403 0.1414213 -0.1414213 -0.1720588 0.1414213 -0.1414213 0.2248403 0.1268786 -0.1546021 -0.1720588 0.1268786 -0.1546021 0.2248403 0.111114 -0.1662939 -0.1720588 0.111114 -0.1662939 0.2248403 0.09427934 -0.1763842 -0.1720588 0.09427934 -0.1763842 0.2248403 0.07653665 -0.1847759 -0.1720588 0.07653665 -0.1847759 0.2248403 0.05805689 -0.191388 -0.1720588 0.05805689 -0.191388 0.2248403 0.03901803 -0.196157 -0.1720588 0.03901803 -0.196157 0.2248403 0.01960343 -0.1990369 -0.1720588 0.01960343 -0.1990369 0.2248403 0 -0.2 -0.1720588 0 -0.2 0.2248403 -0.01960343 -0.1990369 -0.1720588 -0.01960343 -0.1990369 0.2248403 -0.03901803 -0.196157 -0.1720588 -0.03901803 -0.196157 0.2248403 -0.05805689 -0.191388 -0.1720588 -0.05805689 -0.191388 0.2248403 -0.07653665 -0.1847759 -0.1720588 -0.07653665 -0.1847759 0.2248403 -0.09427934 -0.1763842 -0.1720588 -0.09427934 -0.1763842 0.2248403 -0.111114 -0.1662939 -0.1720588 -0.111114 -0.1662939 0.2248403 -0.1268786 -0.1546021 -0.1720588 -0.1268786 -0.1546021 0.2248403 -0.1414213 -0.1414213 -0.1720588 -0.1414213 -0.1414213 0.2248403 -0.1546021 -0.1268786 -0.1720588 -0.1546021 -0.1268786 0.2248403 -0.1662939 -0.111114 -0.1720588 -0.1662939 -0.111114 0.2248403 -0.1763842 -0.09427934 -0.1720588 -0.1763842 -0.09427934 0.2248403 -0.1847759 -0.07653665 -0.1720588 -0.1847759 -0.07653665 0.2248403 -0.191388 -0.05805689 -0.1720588 -0.191388 -0.05805689 0.2248403 -0.196157 -0.03901803 -0.1720588 -0.196157 -0.03901803 0.2248403 -0.1990369 -0.01960343 -0.1720588 -0.1990369 -0.01960343 0.2248403 -0.2 0 -0.1720588 -0.2 0 0.2248403 -0.1990369 0.01960343 -0.1720588 -0.1990369 0.01960343 0.2248403 -0.196157 0.03901803 -0.1720588 -0.196157 0.03901803 0.2248403 -0.191388 0.05805689 -0.1720588 -0.191388 0.05805689 0.2248403 -0.1847759 0.07653665 -0.1720588 -0.1847759 0.07653665 0.2248403 -0.1763842 0.09427934 -0.1720588 -0.1763842 0.09427934 0.2248403 -0.1662939 0.111114 -0.1720588 -0.1662939 0.111114 0.2248403 -0.1546021 0.1268786 -0.1720588 -0.1546021 0.1268786 0.2248403 -0.1414213 0.1414213 -0.1720588 -0.1414213 0.1414213 0.2248403 -0.1268786 0.1546021 -0.1720588 -0.1268786 0.1546021 0.2248403 -0.111114 0.1662939 -0.1720588 -0.111114 0.1662939 0.2248403 -0.09427934 0.1763842 -0.1720588 -0.09427934 0.1763842 0.2248403 -0.07653665 0.1847759 -0.1720588 -0.07653665 0.1847759 0.2248403 -0.05805689 0.191388 -0.1720588 -0.05805689 0.191388 0.2248403 -0.03901803 0.196157 -0.1720588 -0.03901803 0.196157 0.2248403 -0.01960343 0.1990369 -0.1720588 -0.01960343 0.1990369 0.2248403 0.1764252 -0.1611644 -0.2337593 0.1802029 -0.1615365 -0.2337593 0.1764252 -0.1611644 -0.2235848 0.1726474 -0.1615365 -0.2337593 0.169015 -0.1626384 -0.2337593 0.1726474 -0.1615365 -0.2235848 0.169015 -0.1626384 -0.2235848 0.1656672 -0.1644278 -0.2235848 0.1627329 -0.1668359 -0.2235848 0.1656672 -0.1644278 -0.2337593 0.1627329 -0.1668359 -0.2337593 0.1603248 -0.1697703 -0.2337593 0.1585354 -0.1731179 -0.2337593 0.1603248 -0.1697703 -0.2235848 0.1585354 -0.1731179 -0.2235848 0.1574335 -0.1767505 -0.2235848 0.1570614 -0.1805281 -0.2235848 0.1574335 -0.1767505 -0.2337593 0.1570614 -0.1805281 -0.2337593 0.1574335 -0.1843059 -0.2337593 0.1585354 -0.1879383 -0.2337593 0.1574335 -0.1843059 -0.2235848 0.1585354 -0.1879383 -0.2235848 0.1603248 -0.191286 -0.2235848 0.1627329 -0.1942204 -0.2235848 0.1603248 -0.191286 -0.2337593 0.1627329 -0.1942204 -0.2337593 0.1656672 -0.1966285 -0.2337593 0.169015 -0.198418 -0.2337593 0.1656672 -0.1966285 -0.2235848 0.169015 -0.198418 -0.2235848 0.1726474 -0.1995198 -0.2235848 0.1764252 -0.1998919 -0.2235848 0.1726474 -0.1995198 -0.2337593 0.1764252 -0.1998919 -0.2337593 0.1802029 -0.1995198 -0.2337593 0.1838355 -0.198418 -0.2337593 0.1802029 -0.1995198 -0.2235848 0.1838355 -0.198418 -0.2235848 0.1871831 -0.1966285 -0.2235848 0.1901174 -0.1942204 -0.2235848 0.1871831 -0.1966285 -0.2337593 0.1901174 -0.1942204 -0.2337593 0.1925256 -0.191286 -0.2337593 0.194315 -0.1879383 -0.2337593 0.1925256 -0.191286 -0.2235848 0.194315 -0.1879383 -0.2235848 0.1954169 -0.1843059 -0.2235848 0.1957889 -0.1805281 -0.2235848 0.1954169 -0.1843059 -0.2337593 0.1957889 -0.1805281 -0.2337593 0.1954169 -0.1767505 -0.2337593 0.194315 -0.1731179 -0.2337593 0.1954169 -0.1767505 -0.2235848 0.194315 -0.1731179 -0.2235848 0.1925256 -0.1697703 -0.2235848 0.1901174 -0.1668359 -0.2235848 0.1925256 -0.1697703 -0.2337593 0.1901174 -0.1668359 -0.2337593 0.1871831 -0.1644278 -0.2337593 0.1838355 -0.1626384 -0.2337593 0.1871831 -0.1644278 -0.2235848 0.1838355 -0.1626384 -0.2235848 0.1802029 -0.1615365 -0.2235848 0.1764252 -0.1444093 -0.2488764 0.1834716 -0.1451033 -0.2488764 0.1764252 -0.1444093 -0.233887 0.1693787 -0.1451033 -0.2488764 0.1626031 -0.1471587 -0.2488764 0.1693787 -0.1451033 -0.233887 0.1626031 -0.1471587 -0.233887 0.1563587 -0.1504964 -0.233887 0.1508853 -0.1549882 -0.233887 0.1563587 -0.1504964 -0.2488764 0.1508853 -0.1549882 -0.2488764 0.1463935 -0.1604616 -0.2488764 0.1430557 -0.1667061 -0.2488764 0.1463935 -0.1604616 -0.233887 0.1430557 -0.1667061 -0.233887 0.1410003 -0.1734818 -0.233887 0.1403063 -0.1805281 -0.233887 0.1410003 -0.1734818 -0.2488764 0.1403063 -0.1805281 -0.2488764 0.1410003 -0.1875746 -0.2488764 0.1430557 -0.1943502 -0.2488764 0.1410003 -0.1875746 -0.233887 0.1430557 -0.1943502 -0.233887 0.1463935 -0.2005947 -0.233887 0.1508853 -0.206068 -0.233887 0.1463935 -0.2005947 -0.2488764 0.1508853 -0.206068 -0.2488764 0.1563587 -0.2105599 -0.2488764 0.1626031 -0.2138977 -0.2488764 0.1563587 -0.2105599 -0.233887 0.1626031 -0.2138977 -0.233887 0.1693787 -0.2159531 -0.233887 0.1764252 -0.216647 -0.233887 0.1693787 -0.2159531 -0.2488764 0.1764252 -0.216647 -0.2488764 0.1834716 -0.2159531 -0.2488764 0.1902472 -0.2138977 -0.2488764 0.1834716 -0.2159531 -0.233887 0.1902472 -0.2138977 -0.233887 0.1964918 -0.2105599 -0.233887 0.2019652 -0.206068 -0.233887 0.1964918 -0.2105599 -0.2488764 0.2019652 -0.206068 -0.2488764 0.206457 -0.2005947 -0.2488764 0.2097947 -0.1943502 -0.2488764 0.206457 -0.2005947 -0.233887 0.2097947 -0.1943502 -0.233887 0.2118501 -0.1875746 -0.233887 0.2125442 -0.1805281 -0.233887 0.2118501 -0.1875746 -0.2488764 0.2125442 -0.1805281 -0.2488764 0.2118501 -0.1734818 -0.2488764 0.2097947 -0.1667061 -0.2488764 0.2118501 -0.1734818 -0.233887 0.2097947 -0.1667061 -0.233887 0.206457 -0.1604616 -0.233887 0.2019652 -0.1549882 -0.233887 0.206457 -0.1604616 -0.2488764 0.2019652 -0.1549882 -0.2488764 0.1964918 -0.1504964 -0.2488764 0.1902472 -0.1471587 -0.2488764 0.1964918 -0.1504964 -0.233887 0.1902472 -0.1471587 -0.233887 0.1834716 -0.1451033 -0.233887 -0.1815438 -0.159002 -0.2337593 -0.1777662 -0.1593741 -0.2337593 -0.1815438 -0.159002 -0.2235848 -0.1853216 -0.1593741 -0.2337593 -0.1889541 -0.160476 -0.2337593 -0.1853216 -0.1593741 -0.2235848 -0.1889541 -0.160476 -0.2235848 -0.1923018 -0.1622654 -0.2235848 -0.1952361 -0.1646735 -0.2235848 -0.1923018 -0.1622654 -0.2337593 -0.1952361 -0.1646735 -0.2337593 -0.1976442 -0.1676078 -0.2337593 -0.1994337 -0.1709555 -0.2337593 -0.1976442 -0.1676078 -0.2235848 -0.1994337 -0.1709555 -0.2235848 -0.2005355 -0.1745881 -0.2235848 -0.2009076 -0.1783657 -0.2235848 -0.2005355 -0.1745881 -0.2337593 -0.2009076 -0.1783657 -0.2337593 -0.2005355 -0.1821435 -0.2337593 -0.1994337 -0.1857759 -0.2337593 -0.2005355 -0.1821435 -0.2235848 -0.1994337 -0.1857759 -0.2235848 -0.1976442 -0.1891236 -0.2235848 -0.1952361 -0.192058 -0.2235848 -0.1976442 -0.1891236 -0.2337593 -0.1952361 -0.192058 -0.2337593 -0.1923018 -0.1944661 -0.2337593 -0.1889541 -0.1962556 -0.2337593 -0.1923018 -0.1944661 -0.2235848 -0.1889541 -0.1962556 -0.2235848 -0.1853216 -0.1973574 -0.2235848 -0.1815438 -0.1977295 -0.2235848 -0.1853216 -0.1973574 -0.2337593 -0.1815438 -0.1977295 -0.2337593 -0.1777662 -0.1973574 -0.2337593 -0.1741337 -0.1962556 -0.2337593 -0.1777662 -0.1973574 -0.2235848 -0.1741337 -0.1962556 -0.2235848 -0.1707859 -0.1944661 -0.2235848 -0.1678516 -0.192058 -0.2235848 -0.1707859 -0.1944661 -0.2337593 -0.1678516 -0.192058 -0.2337593 -0.1654434 -0.1891236 -0.2337593 -0.1636541 -0.1857759 -0.2337593 -0.1654434 -0.1891236 -0.2235848 -0.1636541 -0.1857759 -0.2235848 -0.1625521 -0.1821435 -0.2235848 -0.1621801 -0.1783657 -0.2235848 -0.1625521 -0.1821435 -0.2337593 -0.1621801 -0.1783657 -0.2337593 -0.1625521 -0.1745881 -0.2337593 -0.1636541 -0.1709555 -0.2337593 -0.1625521 -0.1745881 -0.2235848 -0.1636541 -0.1709555 -0.2235848 -0.1654434 -0.1676078 -0.2235848 -0.1678516 -0.1646735 -0.2235848 -0.1654434 -0.1676078 -0.2337593 -0.1678516 -0.1646735 -0.2337593 -0.1707859 -0.1622654 -0.2337593 -0.1741337 -0.160476 -0.2337593 -0.1707859 -0.1622654 -0.2235848 -0.1741337 -0.160476 -0.2235848 -0.1777662 -0.1593741 -0.2235848 -0.1815438 -0.1422469 -0.2488764 -0.1744974 -0.1429409 -0.2488764 -0.1815438 -0.1422469 -0.233887 -0.1885903 -0.1429409 -0.2488764 -0.1953659 -0.1449963 -0.2488764 -0.1885903 -0.1429409 -0.233887 -0.1953659 -0.1449963 -0.233887 -0.2016104 -0.148334 -0.233887 -0.2070837 -0.1528258 -0.233887 -0.2016104 -0.148334 -0.2488764 -0.2070837 -0.1528258 -0.2488764 -0.2115756 -0.1582992 -0.2488764 -0.2149133 -0.1645437 -0.2488764 -0.2115756 -0.1582992 -0.233887 -0.2149133 -0.1645437 -0.233887 -0.2169687 -0.1713194 -0.233887 -0.2176627 -0.1783657 -0.233887 -0.2169687 -0.1713194 -0.2488764 -0.2176627 -0.1783657 -0.2488764 -0.2169687 -0.1854122 -0.2488764 -0.2149133 -0.1921878 -0.2488764 -0.2169687 -0.1854122 -0.233887 -0.2149133 -0.1921878 -0.233887 -0.2115756 -0.1984323 -0.233887 -0.2070837 -0.2039056 -0.233887 -0.2115756 -0.1984323 -0.2488764 -0.2070837 -0.2039056 -0.2488764 -0.2016104 -0.2083975 -0.2488764 -0.1953659 -0.2117353 -0.2488764 -0.2016104 -0.2083975 -0.233887 -0.1953659 -0.2117353 -0.233887 -0.1885903 -0.2137907 -0.233887 -0.1815438 -0.2144846 -0.233887 -0.1885903 -0.2137907 -0.2488764 -0.1815438 -0.2144846 -0.2488764 -0.1744974 -0.2137907 -0.2488764 -0.1677218 -0.2117353 -0.2488764 -0.1744974 -0.2137907 -0.233887 -0.1677218 -0.2117353 -0.233887 -0.1614772 -0.2083975 -0.233887 -0.1560039 -0.2039056 -0.233887 -0.1614772 -0.2083975 -0.2488764 -0.1560039 -0.2039056 -0.2488764 -0.1515121 -0.1984323 -0.2488764 -0.1481744 -0.1921878 -0.2488764 -0.1515121 -0.1984323 -0.233887 -0.1481744 -0.1921878 -0.233887 -0.146119 -0.1854122 -0.233887 -0.145425 -0.1783657 -0.233887 -0.146119 -0.1854122 -0.2488764 -0.145425 -0.1783657 -0.2488764 -0.146119 -0.1713194 -0.2488764 -0.1481744 -0.1645437 -0.2488764 -0.146119 -0.1713194 -0.233887 -0.1481744 -0.1645437 -0.233887 -0.1515121 -0.1582992 -0.233887 -0.1560039 -0.1528258 -0.233887 -0.1515121 -0.1582992 -0.2488764 -0.1560039 -0.1528258 -0.2488764 -0.1614772 -0.148334 -0.2488764 -0.1677218 -0.1449963 -0.2488764 -0.1614772 -0.148334 -0.233887 -0.1677218 -0.1449963 -0.233887 -0.1744974 -0.1429409 -0.233887 -0.1815438 0.2058658 -0.2488764 -0.1744974 0.2051717 -0.2488764 -0.1815438 0.2058658 -0.233887 -0.1885903 0.2051717 -0.2488764 -0.1953659 0.2031163 -0.2488764 -0.1885903 0.2051717 -0.233887 -0.1953659 0.2031163 -0.233887 -0.2016104 0.1997786 -0.233887 -0.2070837 0.1952868 -0.233887 -0.2016104 0.1997786 -0.2488764 -0.2070837 0.1952868 -0.2488764 -0.2115756 0.1898134 -0.2488764 -0.2149133 0.183569 -0.2488764 -0.2115756 0.1898134 -0.233887 -0.2149133 0.183569 -0.233887 -0.2169687 0.1767933 -0.233887 -0.2176627 0.1697469 -0.233887 -0.2169687 0.1767933 -0.2488764 -0.2176627 0.1697469 -0.2488764 -0.2169687 0.1627004 -0.2488764 -0.2149133 0.1559247 -0.2488764 -0.2169687 0.1627004 -0.233887 -0.2149133 0.1559247 -0.233887 -0.2115756 0.1496803 -0.233887 -0.2070837 0.144207 -0.233887 -0.2115756 0.1496803 -0.2488764 -0.2070837 0.144207 -0.2488764 -0.2016104 0.1397151 -0.2488764 -0.1953659 0.1363773 -0.2488764 -0.2016104 0.1397151 -0.233887 -0.1953659 0.1363773 -0.233887 -0.1885903 0.134322 -0.233887 -0.1815438 0.133628 -0.233887 -0.1885903 0.134322 -0.2488764 -0.1815438 0.133628 -0.2488764 -0.1744974 0.134322 -0.2488764 -0.1677218 0.1363773 -0.2488764 -0.1744974 0.134322 -0.233887 -0.1677218 0.1363773 -0.233887 -0.1614772 0.1397151 -0.233887 -0.1560039 0.144207 -0.233887 -0.1614772 0.1397151 -0.2488764 -0.1560039 0.144207 -0.2488764 -0.1515121 0.1496803 -0.2488764 -0.1481744 0.1559247 -0.2488764 -0.1515121 0.1496803 -0.233887 -0.1481744 0.1559247 -0.233887 -0.146119 0.1627004 -0.233887 -0.145425 0.1697469 -0.233887 -0.146119 0.1627004 -0.2488764 -0.145425 0.1697469 -0.2488764 -0.146119 0.1767933 -0.2488764 -0.1481744 0.183569 -0.2488764 -0.146119 0.1767933 -0.233887 -0.1481744 0.183569 -0.233887 -0.1515121 0.1898134 -0.233887 -0.1560039 0.1952868 -0.233887 -0.1515121 0.1898134 -0.2488764 -0.1560039 0.1952868 -0.2488764 -0.1614772 0.1997786 -0.2488764 -0.1677218 0.2031163 -0.2488764 -0.1614772 0.1997786 -0.233887 -0.1677218 0.2031163 -0.233887 -0.1744974 0.2051717 -0.233887 0.1764252 0.1934354 -0.2337593 0.1802029 0.1930633 -0.2337593 0.1764252 0.1934354 -0.2235848 0.1726474 0.1930633 -0.2337593 0.169015 0.1919615 -0.2337593 0.1726474 0.1930633 -0.2235848 0.169015 0.1919615 -0.2235848 0.1656672 0.190172 -0.2235848 0.1627329 0.1877639 -0.2235848 0.1656672 0.190172 -0.2337593 0.1627329 0.1877639 -0.2337593 0.1603248 0.1848296 -0.2337593 0.1585354 0.1814818 -0.2337593 0.1603248 0.1848296 -0.2235848 0.1585354 0.1814818 -0.2235848 0.1574335 0.1778494 -0.2235848 0.1570614 0.1740717 -0.2235848 0.1574335 0.1778494 -0.2337593 0.1570614 0.1740717 -0.2337593 0.1574335 0.1702939 -0.2337593 0.1585354 0.1666615 -0.2337593 0.1574335 0.1702939 -0.2235848 0.1585354 0.1666615 -0.2235848 0.1603248 0.1633137 -0.2235848 0.1627329 0.1603794 -0.2235848 0.1603248 0.1633137 -0.2337593 0.1627329 0.1603794 -0.2337593 0.1656672 0.1579713 -0.2337593 0.169015 0.1561819 -0.2337593 0.1656672 0.1579713 -0.2235848 0.169015 0.1561819 -0.2235848 0.1726474 0.1550799 -0.2235848 0.1764252 0.1547079 -0.2235848 0.1726474 0.1550799 -0.2337593 0.1764252 0.1547079 -0.2337593 0.1802029 0.1550799 -0.2337593 0.1838355 0.1561819 -0.2337593 0.1802029 0.1550799 -0.2235848 0.1838355 0.1561819 -0.2235848 0.1871831 0.1579713 -0.2235848 0.1901174 0.1603794 -0.2235848 0.1871831 0.1579713 -0.2337593 0.1901174 0.1603794 -0.2337593 0.1925256 0.1633137 -0.2337593 0.194315 0.1666615 -0.2337593 0.1925256 0.1633137 -0.2235848 0.194315 0.1666615 -0.2235848 0.1954169 0.1702939 -0.2235848 0.1957889 0.1740717 -0.2235848 0.1954169 0.1702939 -0.2337593 0.1957889 0.1740717 -0.2337593 0.1954169 0.1778494 -0.2337593 0.194315 0.1814818 -0.2337593 0.1954169 0.1778494 -0.2235848 0.194315 0.1814818 -0.2235848 0.1925256 0.1848296 -0.2235848 0.1901174 0.1877639 -0.2235848 0.1925256 0.1848296 -0.2337593 0.1901174 0.1877639 -0.2337593 0.1871831 0.190172 -0.2337593 0.1838355 0.1919615 -0.2337593 0.1871831 0.190172 -0.2235848 0.1838355 0.1919615 -0.2235848 0.1802029 0.1930633 -0.2235848 0.1764252 0.2101905 -0.2488764 0.1834716 0.2094965 -0.2488764 0.1764252 0.2101905 -0.233887 0.1693787 0.2094965 -0.2488764 0.1626031 0.2074411 -0.2488764 0.1693787 0.2094965 -0.233887 0.1626031 0.2074411 -0.233887 0.1563587 0.2041034 -0.233887 0.1508853 0.1996116 -0.233887 0.1563587 0.2041034 -0.2488764 0.1508853 0.1996116 -0.2488764 0.1463935 0.1941382 -0.2488764 0.1430557 0.1878938 -0.2488764 0.1463935 0.1941382 -0.233887 0.1430557 0.1878938 -0.233887 0.1410003 0.1811181 -0.233887 0.1403063 0.1740717 -0.233887 0.1410003 0.1811181 -0.2488764 0.1403063 0.1740717 -0.2488764 0.1410003 0.1670252 -0.2488764 0.1430557 0.1602495 -0.2488764 0.1410003 0.1670252 -0.233887 0.1430557 0.1602495 -0.233887 0.1463935 0.1540051 -0.233887 0.1508853 0.1485317 -0.233887 0.1463935 0.1540051 -0.2488764 0.1508853 0.1485317 -0.2488764 0.1563587 0.1440399 -0.2488764 0.1626031 0.1407021 -0.2488764 0.1563587 0.1440399 -0.233887 0.1626031 0.1407021 -0.233887 0.1693787 0.1386468 -0.233887 0.1764252 0.1379528 -0.233887 0.1693787 0.1386468 -0.2488764 0.1764252 0.1379528 -0.2488764 0.1834716 0.1386468 -0.2488764 0.1902472 0.1407021 -0.2488764 0.1834716 0.1386468 -0.233887 0.1902472 0.1407021 -0.233887 0.1964918 0.1440399 -0.233887 0.2019652 0.1485317 -0.233887 0.1964918 0.1440399 -0.2488764 0.2019652 0.1485317 -0.2488764 0.206457 0.1540051 -0.2488764 0.2097947 0.1602495 -0.2488764 0.206457 0.1540051 -0.233887 0.2097947 0.1602495 -0.233887 0.2118501 0.1670252 -0.233887 0.2125442 0.1740717 -0.233887 0.2118501 0.1670252 -0.2488764 0.2125442 0.1740717 -0.2488764 0.2118501 0.1811181 -0.2488764 0.2097947 0.1878938 -0.2488764 0.2118501 0.1811181 -0.233887 0.2097947 0.1878938 -0.233887 0.206457 0.1941382 -0.233887 0.2019652 0.1996116 -0.233887 0.206457 0.1941382 -0.2488764 0.2019652 0.1996116 -0.2488764 0.1964918 0.2041034 -0.2488764 0.1902472 0.2074411 -0.2488764 0.1964918 0.2041034 -0.233887 0.1902472 0.2074411 -0.233887 0.1834716 0.2094965 -0.233887 -0.233314 -0.2338278 -0.2250038 -0.233314 0.2322065 -0.2250038 -0.233314 -0.2338278 -0.1766134 0.2327204 -0.2338278 -0.2250038 0.2327204 0.2322065 -0.2250038 0.2327204 -0.2338278 -0.1766134 0.2327204 0.2322065 -0.1766134 -0.233314 0.2322065 -0.1766134 -0.2330172 -0.2330172 -0.175586 -0.2330172 0.2330172 -0.175586 -0.2330172 -0.2330172 -0.1721438 0.2330172 -0.2330172 -0.175586 0.2330172 0.2330172 -0.175586 0.2330172 -0.2330172 -0.1721438 0.2330172 0.2330172 -0.1721438 -0.2330172 0.2330172 -0.1721438 0 0.108569 0.2277768 0 0.108569 0.2501785 0.01064157 0.1080462 0.2277768 0.01064157 0.1080462 0.2501785 0.02118074 0.1064829 0.2277768 0.02118074 0.1064829 0.2501785 0.03151589 0.1038941 0.2277768 0.03151589 0.1038941 0.2501785 0.04154753 0.1003047 0.2277768 0.04154753 0.1003047 0.2501785 0.05117905 0.09574931 0.2277768 0.05117905 0.09574931 0.2501785 0.06031769 0.09027183 0.2277768 0.06031769 0.09027183 0.2501785 0.06887543 0.083925 0.2277768 0.06887543 0.083925 0.2501785 0.07676988 0.07676988 0.2277768 0.07676988 0.07676988 0.2501785 0.083925 0.06887543 0.2277768 0.083925 0.06887543 0.2501785 0.09027183 0.06031769 0.2277768 0.09027183 0.06031769 0.2501785 0.09574931 0.05117905 0.2277768 0.09574931 0.05117905 0.2501785 0.1003047 0.04154753 0.2277768 0.1003047 0.04154753 0.2501785 0.1038941 0.03151589 0.2277768 0.1038941 0.03151589 0.2501785 0.1064829 0.02118074 0.2277768 0.1064829 0.02118074 0.2501785 0.1080462 0.01064157 0.2277768 0.1080462 0.01064157 0.2501785 0.108569 0 0.2277768 0.108569 0 0.2501785 0.1080462 -0.01064157 0.2277768 0.1080462 -0.01064157 0.2501785 0.1064829 -0.02118074 0.2277768 0.1064829 -0.02118074 0.2501785 0.1038941 -0.03151589 0.2277768 0.1038941 -0.03151589 0.2501785 0.1003047 -0.04154753 0.2277768 0.1003047 -0.04154753 0.2501785 0.09574931 -0.05117905 0.2277768 0.09574931 -0.05117905 0.2501785 0.09027183 -0.06031769 0.2277768 0.09027183 -0.06031769 0.2501785 0.083925 -0.06887543 0.2277768 0.083925 -0.06887543 0.2501785 0.07676988 -0.07676988 0.2277768 0.07676988 -0.07676988 0.2501785 0.06887543 -0.083925 0.2277768 0.06887543 -0.083925 0.2501785 0.06031769 -0.09027183 0.2277768 0.06031769 -0.09027183 0.2501785 0.05117905 -0.09574931 0.2277768 0.05117905 -0.09574931 0.2501785 0.04154753 -0.1003047 0.2277768 0.04154753 -0.1003047 0.2501785 0.03151589 -0.1038941 0.2277768 0.03151589 -0.1038941 0.2501785 0.02118074 -0.1064829 0.2277768 0.02118074 -0.1064829 0.2501785 0.01064157 -0.1080462 0.2277768 0.01064157 -0.1080462 0.2501785 0 -0.108569 0.2277768 0 -0.108569 0.2501785 -0.01064157 -0.1080462 0.2277768 -0.01064157 -0.1080462 0.2501785 -0.02118074 -0.1064829 0.2277768 -0.02118074 -0.1064829 0.2501785 -0.03151589 -0.1038941 0.2277768 -0.03151589 -0.1038941 0.2501785 -0.04154753 -0.1003047 0.2277768 -0.04154753 -0.1003047 0.2501785 -0.05117905 -0.09574931 0.2277768 -0.05117905 -0.09574931 0.2501785 -0.06031769 -0.09027183 0.2277768 -0.06031769 -0.09027183 0.2501785 -0.06887543 -0.083925 0.2277768 -0.06887543 -0.083925 0.2501785 -0.07676988 -0.07676988 0.2277768 -0.07676988 -0.07676988 0.2501785 -0.083925 -0.06887543 0.2277768 -0.083925 -0.06887543 0.2501785 -0.09027183 -0.06031769 0.2277768 -0.09027183 -0.06031769 0.2501785 -0.09574931 -0.05117905 0.2277768 -0.09574931 -0.05117905 0.2501785 -0.1003047 -0.04154753 0.2277768 -0.1003047 -0.04154753 0.2501785 -0.1038941 -0.03151589 0.2277768 -0.1038941 -0.03151589 0.2501785 -0.1064829 -0.02118074 0.2277768 -0.1064829 -0.02118074 0.2501785 -0.1080462 -0.01064157 0.2277768 -0.1080462 -0.01064157 0.2501785 -0.108569 0 0.2277768 -0.108569 0 0.2501785 -0.1080462 0.01064157 0.2277768 -0.1080462 0.01064157 0.2501785 -0.1064829 0.02118074 0.2277768 -0.1064829 0.02118074 0.2501785 -0.1038941 0.03151589 0.2277768 -0.1038941 0.03151589 0.2501785 -0.1003047 0.04154753 0.2277768 -0.1003047 0.04154753 0.2501785 -0.09574931 0.05117905 0.2277768 -0.09574931 0.05117905 0.2501785 -0.09027183 0.06031769 0.2277768 -0.09027183 0.06031769 0.2501785 -0.083925 0.06887543 0.2277768 -0.083925 0.06887543 0.2501785 -0.07676988 0.07676988 0.2277768 -0.07676988 0.07676988 0.2501785 -0.06887543 0.083925 0.2277768 -0.06887543 0.083925 0.2501785 -0.06031769 0.09027183 0.2277768 -0.06031769 0.09027183 0.2501785 -0.05117905 0.09574931 0.2277768 -0.05117905 0.09574931 0.2501785 -0.04154753 0.1003047 0.2277768 -0.04154753 0.1003047 0.2501785 -0.03151589 0.1038941 0.2277768 -0.03151589 0.1038941 0.2501785 -0.02118074 0.1064829 0.2277768 -0.02118074 0.1064829 0.2501785 -0.01064157 0.1080462 0.2277768 -0.01064157 0.1080462 0.2501785 0 0.2 0.2247711 0 0.2 0.2283224 0.01960343 0.1990369 0.2247711 0.01960343 0.1990369 0.2283224 0.03901803 0.196157 0.2247711 0.03901803 0.196157 0.2283224 0.05805689 0.191388 0.2247711 0.05805689 0.191388 0.2283224 0.07653665 0.1847759 0.2247711 0.07653665 0.1847759 0.2283224 0.09427934 0.1763842 0.2247711 0.09427934 0.1763842 0.2283224 0.111114 0.1662939 0.2247711 0.111114 0.1662939 0.2283224 0.1268786 0.1546021 0.2247711 0.1268786 0.1546021 0.2283224 0.1414213 0.1414213 0.2247711 0.1414213 0.1414213 0.2283224 0.1546021 0.1268786 0.2247711 0.1546021 0.1268786 0.2283224 0.1662939 0.111114 0.2247711 0.1662939 0.111114 0.2283224 0.1763842 0.09427934 0.2247711 0.1763842 0.09427934 0.2283224 0.1847759 0.07653665 0.2247711 0.1847759 0.07653665 0.2283224 0.191388 0.05805689 0.2247711 0.191388 0.05805689 0.2283224 0.196157 0.03901803 0.2247711 0.196157 0.03901803 0.2283224 0.1990369 0.01960343 0.2247711 0.1990369 0.01960343 0.2283224 0.2 0 0.2247711 0.2 0 0.2283224 0.1990369 -0.01960343 0.2247711 0.1990369 -0.01960343 0.2283224 0.196157 -0.03901803 0.2247711 0.196157 -0.03901803 0.2283224 0.191388 -0.05805689 0.2247711 0.191388 -0.05805689 0.2283224 0.1847759 -0.07653665 0.2247711 0.1847759 -0.07653665 0.2283224 0.1763842 -0.09427934 0.2247711 0.1763842 -0.09427934 0.2283224 0.1662939 -0.111114 0.2247711 0.1662939 -0.111114 0.2283224 0.1546021 -0.1268786 0.2247711 0.1546021 -0.1268786 0.2283224 0.1414213 -0.1414213 0.2247711 0.1414213 -0.1414213 0.2283224 0.1268786 -0.1546021 0.2247711 0.1268786 -0.1546021 0.2283224 0.111114 -0.1662939 0.2247711 0.111114 -0.1662939 0.2283224 0.09427934 -0.1763842 0.2247711 0.09427934 -0.1763842 0.2283224 0.07653665 -0.1847759 0.2247711 0.07653665 -0.1847759 0.2283224 0.05805689 -0.191388 0.2247711 0.05805689 -0.191388 0.2283224 0.03901803 -0.196157 0.2247711 0.03901803 -0.196157 0.2283224 0.01960343 -0.1990369 0.2247711 0.01960343 -0.1990369 0.2283224 0 -0.2 0.2247711 0 -0.2 0.2283224 -0.01960343 -0.1990369 0.2247711 -0.01960343 -0.1990369 0.2283224 -0.03901803 -0.196157 0.2247711 -0.03901803 -0.196157 0.2283224 -0.05805689 -0.191388 0.2247711 -0.05805689 -0.191388 0.2283224 -0.07653665 -0.1847759 0.2247711 -0.07653665 -0.1847759 0.2283224 -0.09427934 -0.1763842 0.2247711 -0.09427934 -0.1763842 0.2283224 -0.111114 -0.1662939 0.2247711 -0.111114 -0.1662939 0.2283224 -0.1268786 -0.1546021 0.2247711 -0.1268786 -0.1546021 0.2283224 -0.1414213 -0.1414213 0.2247711 -0.1414213 -0.1414213 0.2283224 -0.1546021 -0.1268786 0.2247711 -0.1546021 -0.1268786 0.2283224 -0.1662939 -0.111114 0.2247711 -0.1662939 -0.111114 0.2283224 -0.1763842 -0.09427934 0.2247711 -0.1763842 -0.09427934 0.2283224 -0.1847759 -0.07653665 0.2247711 -0.1847759 -0.07653665 0.2283224 -0.191388 -0.05805689 0.2247711 -0.191388 -0.05805689 0.2283224 -0.196157 -0.03901803 0.2247711 -0.196157 -0.03901803 0.2283224 -0.1990369 -0.01960343 0.2247711 -0.1990369 -0.01960343 0.2283224 -0.2 0 0.2247711 -0.2 0 0.2283224 -0.1990369 0.01960343 0.2247711 -0.1990369 0.01960343 0.2283224 -0.196157 0.03901803 0.2247711 -0.196157 0.03901803 0.2283224 -0.191388 0.05805689 0.2247711 -0.191388 0.05805689 0.2283224 -0.1847759 0.07653665 0.2247711 -0.1847759 0.07653665 0.2283224 -0.1763842 0.09427934 0.2247711 -0.1763842 0.09427934 0.2283224 -0.1662939 0.111114 0.2247711 -0.1662939 0.111114 0.2283224 -0.1546021 0.1268786 0.2247711 -0.1546021 0.1268786 0.2283224 -0.1414213 0.1414213 0.2247711 -0.1414213 0.1414213 0.2283224 -0.1268786 0.1546021 0.2247711 -0.1268786 0.1546021 0.2283224 -0.111114 0.1662939 0.2247711 -0.111114 0.1662939 0.2283224 -0.09427934 0.1763842 0.2247711 -0.09427934 0.1763842 0.2283224 -0.07653665 0.1847759 0.2247711 -0.07653665 0.1847759 0.2283224 -0.05805689 0.191388 0.2247711 -0.05805689 0.191388 0.2283224 -0.03901803 0.196157 0.2247711 -0.03901803 0.196157 0.2283224 -0.01960343 0.1990369 0.2247711 -0.01960343 0.1990369 0.2283224 - - - - - - - - - - 0 0 -1 0.09802937 0.9951835 0 -0.09802639 0.9951839 0 -0.2902737 0.9569438 0 0 0 1 -0.4713979 0.8819206 0 -0.6344015 0.7730038 0 -0.773002 0.6344037 0 -0.8819187 0.4714016 0 -0.9569441 0.2902726 0 -0.9951853 0.09801107 0 -0.9951854 -0.09801024 0 -0.9569436 -0.2902743 0 -0.8819187 -0.4714016 0 -0.7730081 -0.6343963 0 -0.6343961 -0.7730082 0 -0.4713921 -0.8819237 0 -0.2902944 -0.9569374 0 -0.09800326 -0.9951862 0 0.09800618 -0.9951858 0 0.2902894 -0.9569389 0 0.4713921 -0.8819237 0 0.6343873 -0.7730154 0 0.7730081 -0.6343963 0 0.8819288 -0.4713829 0 0.9569351 -0.2903019 0 0.9951854 -0.09801024 0 0.9951853 0.09801107 0 0.9569357 0.2903002 0 0.8819313 0.4713782 0 0.773005 0.6344001 0 0.6343926 0.773011 0 0.4713979 0.8819206 0 0.2902704 0.9569447 0 0.04906803 0.9987955 0 0.1467304 0.9891766 0 0.2429798 0.9700314 0 0.3368901 0.9415441 0 0.4275553 0.9039893 0 0.5141028 0.8577287 0 0.595699 0.8032079 0 0.6715587 0.7409513 0 0.740951 0.6715592 0 0.803207 0.5957002 0 0.8577283 0.5141035 0 0.9039889 0.427556 0 0.9415441 0.3368901 0 0.9700314 0.2429798 0 0.9891766 0.1467302 0 0.9987955 0.0490688 0 0.9987955 -0.0490669 0 0.9891766 -0.1467302 0 0.9700314 -0.2429798 0 0.9415441 -0.3368901 0 0.9039897 -0.4275545 0 0.857729 -0.5141022 0 0.8032087 -0.5956977 0 0.7409514 -0.6715587 0 0.6715592 -0.7409509 0 0.595699 -0.8032079 0 0.5141032 -0.8577283 0 0.4275547 -0.9039895 0 0.3368901 -0.9415441 0 0.2429798 -0.9700314 0 0.1467304 -0.9891766 0 0.04906803 -0.9987955 0 -0.04906803 -0.9987955 0 -0.1467304 -0.9891766 0 -0.2429798 -0.9700314 0 -0.3368901 -0.9415441 0 -0.4275553 -0.9039893 0 -0.5141028 -0.8577287 0 -0.595699 -0.8032079 0 -0.6715587 -0.7409513 0 -0.740951 -0.6715592 0 -0.803207 -0.5957002 0 -0.8577283 -0.5141035 0 -0.9039889 -0.427556 0 -0.9415441 -0.3368901 0 -0.9700314 -0.2429798 0 -0.9891766 -0.1467302 0 -0.9987955 -0.0490688 0 -0.9987955 0.0490669 0 -0.9891766 0.1467302 0 -0.9700314 0.2429798 0 -0.9415441 0.3368901 0 -0.9039897 0.4275545 0 -0.857729 0.5141022 0 -0.8032087 0.5956977 0 -0.7409514 0.6715587 0 -0.6715592 0.7409509 0 -0.595699 0.8032079 0 -0.5141032 0.8577283 0 -0.4275547 0.9039895 0 -0.3368901 0.9415441 0 -0.2429798 0.9700314 0 -0.1467304 0.9891766 0 -0.04906803 0.9987955 0 0 0 -1 0.09801113 0.9951853 0 -0.09801173 0.9951853 0 -0.2902908 0.9569385 0 -0.4713921 0.8819237 0 -0.6343926 0.773011 0 -0.773011 0.6343926 0 -0.8819286 0.4713832 0 -0.9569373 0.2902952 0 -0.9951846 0.09801852 0 -0.9951854 -0.09800994 0 -0.9569336 -0.2903069 0 -0.8819288 -0.4713829 0 -0.773011 -0.6343926 0 -0.6343926 -0.773011 0 -0.471405 -0.8819169 0 -0.2902771 -0.9569427 0 -0.09801113 -0.9951853 0 0.09801113 -0.9951853 0 0.2902687 -0.9569452 0 0.4714201 -0.8819088 0 0.6343926 -0.773011 0 0.773011 -0.6343926 0 0.8819137 -0.4714109 0 0.9569454 -0.2902683 0 0.9951844 -0.09802186 0 0.9951853 0.09801256 0 0.9569456 0.2902676 0 0.881916 0.4714065 0 0.7730081 0.6343963 0 0.4714046 0.8819171 0 0.2902825 0.956941 0 8.61748e-7 0 -1 0.09801977 0.9951845 0 -0.09802019 0.9951844 0 -0.2902834 0.9569408 0 -0.4713988 0.8819203 0 -0.6343873 0.7730154 0 -0.7730154 0.6343873 0 -0.8819217 0.471396 0 -0.9569391 0.2902892 0 -0.9951843 0.09802311 0 -0.9951847 -0.09801727 0 -0.956939 -0.2902894 0 -0.8819232 -0.4713933 0 -0.7730105 -0.6343933 0 -0.6343965 -0.7730079 0 -0.4714006 -0.8819193 0 -0.2902902 -0.9569387 0 -0.0980032 -0.9951861 0 0.09800362 -0.9951862 0 0.2902914 -0.9569384 0 0.4713933 -0.8819232 0 0.6343965 -0.7730079 0 0.7730084 -0.6343959 0 0.8819232 -0.4713933 0 0.956939 -0.2902894 0 0.9951843 -0.09802162 0 0.9951843 0.09802311 0 0.9569402 0.2902852 0 0.8819217 0.471396 0 0.7730154 0.6343873 0 0.6343873 0.7730154 0 0.4713933 0.8819232 0 0.2902822 0.9569412 0 0.09801405 0.9951851 0 -0.09801113 0.9951853 0 -0.2902875 0.9569395 0 6.20954e-7 0 1 -0.7730056 0.6343992 0 -0.9569448 0.29027 0 -0.9951853 0.09801256 0 -0.956942 -0.2902793 0 -0.6344015 -0.7730038 0 -0.2902737 -0.9569438 0 0.09801405 -0.9951851 0 0.471405 -0.8819169 0 0.9569336 -0.2903069 0 0.9951854 -0.09800994 0 0.9569364 0.2902977 0 0.7730086 0.6343956 0 0.4713921 0.8819237 0 0.2902842 0.9569406 0 3.56946e-7 0 -1 -0.4713951 0.8819222 0 -0.6343916 0.7730119 0 -0.7730111 0.6343925 0 -0.9569414 0.2902811 0 -0.9951847 0.09801876 0 -0.9951843 -0.09802162 0 -0.9569414 -0.2902814 0 -0.7730062 -0.6343985 0 -0.6344008 -0.7730044 0 -0.4713969 -0.8819212 0 0.6344008 -0.7730044 0 0.9569402 -0.2902854 0 0.9951847 0.09801876 0 0.9569426 0.2902771 0 0.6343916 0.7730119 0 3.56946e-7 0 -1 0.09801566 0.9951849 0 -0.09801614 0.9951848 0 -0.2902914 0.9569384 0 -0.4713917 0.881924 0 -0.6343955 0.7730087 0 -0.7730094 0.6343947 0 -0.8819198 0.4713997 0 -0.9569411 0.2902824 0 -0.9951847 0.09801745 0 -0.9951844 -0.0980212 0 -0.8819217 -0.471396 0 -0.7730097 -0.6343942 0 -0.6343955 -0.7730087 0 -0.4714004 -0.8819195 0 -0.2902822 -0.9569412 0 -0.09801566 -0.9951849 0 0.09801614 -0.9951848 0 0.2902834 -0.9569408 0 0.4713967 -0.8819213 0 0.6343955 -0.7730087 0 0.7730119 -0.6343916 0 0.8819217 -0.471396 0 0.9951844 -0.0980212 0 0.9951847 0.09801745 0 0.9569423 0.2902783 0 0.8819198 0.4713997 0 0.7730137 0.6343895 0 0.6343955 0.7730087 0 0.4713899 0.8819251 0 0.2902902 0.9569387 0 0.09802639 0.9951839 0 -0.09802699 0.9951838 0 -0.2902771 0.9569427 0 -0.773005 0.6344001 0 -0.8819313 0.4713782 0 -0.9569357 0.2903002 0 -0.9951847 0.09801703 0 -0.9569351 -0.2903019 0 -0.6343873 -0.7730154 0 -0.2902978 -0.9569364 0 0.09800326 -0.9951862 0 0.4714072 -0.8819158 0 0.9569469 -0.2902632 0 0.9951843 -0.09802216 0 0.9569441 0.2902726 0 0.8819187 0.4714016 0 0.773002 0.6344037 0 0.4714105 0.881914 0 0.2902687 0.9569452 0 -1.72348e-6 0 1 -0.4713954 0.8819221 0 -0.6343913 0.7730122 0 -0.7730137 0.6343895 0 -0.9569386 0.2902904 0 -0.9951843 0.0980218 0 -0.9951848 -0.09801685 0 -0.773014 -0.634389 0 -0.6343913 -0.7730122 0 -0.471404 -0.8819174 0 0.6343913 -0.7730122 0 0.9951843 0.0980218 0 0.9569398 0.2902864 0 0.6343913 0.7730122 0 -1 0 0 0 -1 0 1 0 0 0 1 0 0.04906791 0.9987955 0 0.1467303 0.9891766 0 0.2429802 0.9700313 0 0.3368898 0.9415442 0 0.4275553 0.9039893 0 0.5141018 0.8577292 0 0.5956992 0.8032078 0 0.6715583 0.7409518 0 0.7409514 0.6715587 0 0.8032081 0.5956987 0 0.8577285 0.5141029 0 0.9039897 0.4275545 0 0.941544 0.3368901 0 0.9700311 0.2429808 0 0.9891767 0.1467297 0 0.9987955 0.04906785 0 0.9987955 -0.04906785 0 0.9891765 -0.1467316 0 0.9700316 -0.2429791 0 0.941544 -0.3368901 0 0.9039889 -0.4275561 0 0.8577285 -0.5141029 0 0.8032076 -0.5956993 0 0.7409504 -0.6715598 0 0.6715593 -0.7409508 0 0.5956987 -0.8032081 0 0.5141022 -0.857729 0 0.4275549 -0.9039895 0 0.3368899 -0.9415441 0 0.2429802 -0.9700313 0 0.1467303 -0.9891766 0 0.04906791 -0.9987955 0 -0.04906791 -0.9987955 0 -0.1467303 -0.9891766 0 -0.2429801 -0.9700313 0 -0.3368901 -0.9415441 0 -0.4275549 -0.9039895 0 -0.5141022 -0.857729 0 -0.5956992 -0.8032078 0 -0.6715583 -0.7409518 0 -0.7409514 -0.6715587 0 -0.8032081 -0.5956987 0 -0.8577285 -0.5141029 0 -0.9039897 -0.4275545 0 -0.941544 -0.3368901 0 -0.9700311 -0.2429808 0 -0.9891767 -0.1467297 0 -0.9987955 -0.04906785 0 -0.9987955 0.04906785 0 -0.9891765 0.1467316 0 -0.9700316 0.2429791 0 -0.941544 0.3368901 0 -0.9039889 0.4275561 0 -0.8577285 0.5141029 0 -0.8032076 0.5956993 0 -0.7409504 0.6715598 0 -0.6715593 0.7409508 0 -0.5956987 0.8032081 0 -0.5141022 0.857729 0 -0.4275549 0.9039895 0 -0.3368901 0.9415441 0 -0.2429801 0.9700313 0 -0.1467303 0.9891766 0 -0.04906791 0.9987955 0 -4.46954e-7 0 -1 0.04906815 0.9987955 0 0.1467298 0.9891767 0 0.2429798 0.9700314 0 0.3368909 0.9415438 0 0.4275565 0.9039887 0 0.5141049 0.8577274 0 0.5956983 0.8032083 0 0.6715584 0.7409517 0 0.7409517 0.6715584 0 0.8032057 0.5957018 0 0.8577271 0.5141054 0 0.9039895 0.4275548 0 0.9415432 0.3368927 0 0.970032 0.2429773 0 0.9891768 0.146729 0 0.9987956 0.0490666 0 0.9987955 -0.04906827 0 0.9891765 -0.1467307 0 0.9700313 -0.2429804 0 0.9415426 -0.3368942 0 0.9039895 -0.4275548 0 0.8577278 -0.5141042 0 0.8032066 -0.5957008 0 0.7409508 -0.6715593 0 0.6715584 -0.7409517 0 0.5956983 -0.8032083 0 0.5141049 -0.8577274 0 0.4275559 -0.903989 0 0.3368912 -0.9415436 0 0.2429798 -0.9700314 0 0.1467298 -0.9891767 0 0.04906815 -0.9987955 0 -0.04906815 -0.9987955 0 -0.1467298 -0.9891767 0 -0.2429797 -0.9700314 0 -0.3368912 -0.9415436 0 -0.4275565 -0.9039887 0 -0.5141049 -0.8577274 0 -0.5956983 -0.8032083 0 -0.6715584 -0.7409517 0 -0.7409517 -0.6715584 0 -0.8032057 -0.5957018 0 -0.8577271 -0.5141054 0 -0.9039895 -0.4275548 0 -0.9415432 -0.3368927 0 -0.970032 -0.2429773 0 -0.9891768 -0.146729 0 -0.9987956 -0.0490666 0 -0.9987955 0.04906827 0 -0.9891765 0.1467307 0 -0.9700313 0.2429804 0 -0.9415426 0.3368942 0 -0.9039895 0.4275548 0 -0.8577278 0.5141042 0 -0.8032066 0.5957008 0 -0.7409508 0.6715593 0 -0.6715584 0.7409517 0 -0.5956983 0.8032083 0 -0.5141049 0.8577274 0 -0.4275559 0.903989 0 -0.3368912 0.9415436 0 -0.2429797 0.9700314 0 -0.1467298 0.9891767 0 -0.04906815 0.9987955 0 4.1413e-5 0 -1 -5.59296e-5 0 -1 2.85162e-5 0 -1 -2.07065e-5 0 -1 2.07074e-5 0 -1 -4.14079e-5 0 -1 1.42576e-5 0 -1 -3.74271e-6 0 -1 0.09802973 0.9951835 0 -0.09802681 0.9951838 0 -0.2902724 0.9569442 0 4.14113e-5 0 1 4.14147e-5 0 1 -1.39833e-5 0 1 -1.0352e-5 0 1 2.07048e-5 0 1 -4.14076e-5 0 1 -4.1407e-5 0 1 2.79666e-5 0 1 -0.6344034 0.7730023 0 -0.8819195 0.4714003 0 -0.9951853 0.09801137 0 -0.9951854 -0.09801048 0 -0.8819195 -0.4714003 0 -0.6343979 -0.7730067 0 0.2902911 -0.9569384 0 0.6343891 -0.773014 0 0.8819319 -0.4713768 0 0.9951854 -0.09801048 0 0.9951853 0.09801137 0 0.8819295 0.4713816 0 0.6343945 0.7730096 0 0.2902673 0.9569457 0 0.04906803 0.9987955 0 0.4275547 0.9039895 0 0.5141032 0.8577283 0 0.6715592 0.7409509 0 0.7409514 0.6715587 0 0.8032087 0.5956977 0 0.857729 0.5141021 0 0.9700314 0.2429798 0 0.9987956 0.0490669 0 0.9987955 -0.0490688 0 0.9700314 -0.2429798 0 0.9039889 -0.427556 0 0.8577282 -0.5141035 0 0.803207 -0.5957002 0 0.7409509 -0.6715592 0 0.6715587 -0.7409513 0 0.5141028 -0.8577287 0 0.4275553 -0.9039893 0 0.04906803 -0.9987955 0 -0.04906803 -0.9987955 0 -0.4275547 -0.9039895 0 -0.5141032 -0.8577283 0 -0.6715592 -0.7409509 0 -0.7409514 -0.6715587 0 -0.8032087 -0.5956977 0 -0.857729 -0.5141021 0 -0.9700314 -0.2429798 0 -0.9987956 -0.0490669 0 -0.9987955 0.0490688 0 -0.9700314 0.2429798 0 -0.9039889 0.427556 0 -0.8577282 0.5141035 0 -0.803207 0.5957002 0 -0.7409509 0.6715592 0 -0.6715587 0.7409513 0 -0.5141028 0.8577287 0 -0.4275553 0.9039893 0 -6.16637e-6 0 1 1.23329e-5 0 1 -2.46654e-5 0 1 6.16637e-6 0 1 -1.23329e-5 0 1 2.46654e-5 0 1 3.10556e-6 0 1 1.55278e-6 0 1 -3.10556e-6 0 1 -1.55278e-6 0 1 -1.59856e-6 0 1 1.59856e-6 0 1 2.24841e-7 0 1 -2.24841e-7 0 1 -0.04906803 0.9987955 0 3.0833e-6 0 -1 6.16644e-6 0 -1 -1.23327e-5 0 -1 8.28823e-6 0 -1 8.28818e-6 0 -1 -1.64965e-5 0 -1 1.23327e-5 0 -1 8.28818e-6 0 -1 -1.23326e-5 0 -1 -2.06201e-6 0 -1 -3.0833e-6 0 -1 -6.16644e-6 0 -1 1.23327e-5 0 -1 -8.28823e-6 0 -1 -8.28818e-6 0 -1 1.64965e-5 0 -1 -1.23327e-5 0 -1 -8.28818e-6 0 -1 1.23326e-5 0 -1 2.06201e-6 0 -1 -2.09724e-6 0 -1 2.09724e-6 0 -1 -7.9928e-7 0 -1 -1.9982e-7 0 -1 7.9928e-7 0 -1 1.9982e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 7.1285e-6 0 -1 -1.39829e-5 0 -1 2.07056e-5 0 -1 -4.14049e-5 0 -1 4.14104e-5 0 -1 -7.1288e-6 0 -1 1.39825e-5 0 -1 -2.85168e-5 0 -1 -2.8516e-5 0 -1 -3.51265e-6 0 -1 2.48382e-6 0 -1 3.51264e-6 0 -1 0.09801071 0.9951854 0 -0.09801071 0.9951854 0 -0.2902895 0.956939 0 1.03528e-5 0 1 4.14096e-5 0 1 4.14074e-5 0 1 -1.03528e-5 0 1 -4.14132e-5 0 1 -1.42582e-5 0 1 4.05106e-6 0 1 -7.48548e-6 0 1 -1.0658e-5 0 1 8.10232e-6 0 1 -2.48382e-6 0 1 -0.6343945 0.7730096 0 -0.8819254 0.4713891 0 -0.956937 0.290296 0 -0.9951851 0.09801286 0 -0.995185 -0.0980156 0 -0.9569339 -0.290306 0 -0.8819319 -0.4713768 0 -0.6343945 -0.7730096 0 -0.4714038 -0.8819174 0 -0.2902757 -0.9569432 0 -0.09801131 -0.9951853 0 0.09801071 -0.9951854 0 0.2902673 -0.9569457 0 0.4714164 -0.8819108 0 0.6343945 -0.7730096 0 0.8819195 -0.4714003 0 0.9569422 -0.2902784 0 0.9951855 -0.09800964 0 0.9951841 0.09802478 0 0.9569486 0.2902573 0 0.8819104 0.4714173 0 0.773011 0.6343926 0 0.4714072 0.8819158 0 0.2902811 0.9569414 0 2.38061e-5 0 -1 1.19028e-5 0 -1 -2.38061e-5 0 -1 -1.63913e-5 0 -1 4.30282e-6 0 -1 3.0634e-6 0 -1 -1.42778e-6 0 -1 2.01919e-6 0 -1 -1.42778e-6 0 -1 0.09802019 0.9951844 0 -0.09801977 0.9951845 0 -0.2902822 0.9569412 0 -1.63908e-5 0 1 3.21518e-5 0 1 -2.38047e-5 0 1 -5.95068e-6 0 1 5.95068e-6 0 1 2.38047e-5 0 1 2.38048e-5 0 1 -3.21517e-5 0 1 1.63908e-5 0 1 -8.19544e-6 0 1 8.03755e-6 0 1 6.12685e-6 0 1 -6.12672e-6 0 1 1.00959e-6 0 1 -0.4714006 0.8819193 0 -0.634386 0.7730165 0 -0.7730176 0.6343847 0 -0.95694 0.2902858 0 -0.9569379 -0.2902928 0 -0.8819237 -0.4713924 0 -0.7730084 -0.6343959 0 -0.4713988 -0.8819203 0 -0.2902909 -0.9569385 0 -0.09800362 -0.9951862 0 0.0980032 -0.9951861 0 0.2902897 -0.9569389 0 0.8819237 -0.4713924 0 0.9569392 -0.2902888 0 0.95694 0.2902858 0 0.634386 0.7730165 0 0.2902834 0.9569408 0 2.07065e-5 0 -1 -4.1413e-5 0 -1 -4.141e-5 0 -1 -3.74266e-6 0 -1 -1.24191e-6 0 -1 0.09801369 0.9951851 0 -0.2902861 0.9569399 0 4.14162e-5 0 1 4.14134e-5 0 1 -1.03537e-5 0 1 -4.14092e-5 0 1 -8.10228e-6 0 1 2.99825e-6 0 1 -6.20956e-7 0 1 -0.7730044 0.6344007 0 -0.9951855 -0.09800964 0 -0.9569422 -0.2902784 0 -0.6344034 -0.7730023 0 -0.2902724 -0.9569442 0 -0.09801071 -0.9951854 0 0.09801369 -0.9951851 0 0.290269 -0.9569452 0 0.4714038 -0.8819174 0 0.9569339 -0.290306 0 0.9951851 0.09801286 0 0.7730044 0.6344007 0 -2.38044e-5 0 -1 8.19571e-6 0 -1 -1.19033e-5 0 -1 1.19033e-5 0 -1 2.38044e-5 0 -1 -6.12674e-6 0 -1 -2.32871e-6 0 -1 2.15143e-6 0 -1 2.32871e-6 0 -1 -2.15142e-6 0 -1 3.06337e-6 0 -1 -3.56946e-7 0 -1 1.6391e-5 0 1 -1.63912e-5 0 1 3.2152e-5 0 1 -2.3806e-5 0 1 -2.38039e-5 0 1 -5.95082e-6 0 1 5.95082e-6 0 1 2.38044e-5 0 1 2.3806e-5 0 1 -3.21521e-5 0 1 1.63912e-5 0 1 -8.19551e-6 0 1 8.03768e-6 0 1 -6.12674e-6 0 1 -0.4713969 0.8819212 0 -0.6343903 0.7730129 0 -0.7730134 0.6343899 0 -0.9569425 0.2902777 0 -0.9569404 -0.2902848 0 -0.7730041 -0.6344012 0 -0.4713951 -0.8819222 0 0.9569416 -0.2902808 0 0.9951847 -0.09801727 0 0.9569413 0.2902818 0 0.6343903 0.7730129 0 4.09789e-6 0 -1 2.38047e-5 0 -1 2.38046e-5 0 -1 -2.38044e-5 0 -1 2.38053e-5 0 -1 1.19024e-5 0 -1 -4.09776e-6 0 -1 8.03787e-6 0 -1 -1.19025e-5 0 -1 1.60759e-5 0 -1 -2.38053e-5 0 -1 2.38044e-5 0 -1 -2.38056e-5 0 -1 -2.15141e-6 0 -1 -2.3287e-6 0 -1 2.32869e-6 0 -1 -1.78473e-7 0 -1 0.09801614 0.9951848 0 -0.09801566 0.9951849 0 -0.2902897 0.9569389 0 -2.97548e-6 0 1 5.95096e-6 0 1 -2.38058e-5 0 1 -2.3805e-5 0 1 -2.97566e-6 0 1 2.38058e-5 0 1 8.03781e-6 0 1 6.12683e-6 0 1 -1.72348e-6 0 1 -0.4713935 0.881923 0 -0.6343969 0.7730076 0 -0.7730106 0.6343931 0 -0.8819193 0.4714006 0 -0.9569421 0.2902789 0 -0.9951843 0.09802204 0 -0.7730076 -0.6343969 0 -0.6343969 -0.7730076 0 -0.4713976 -0.8819208 0 -0.2902834 -0.9569408 0 -0.09801614 -0.9951848 0 0.09801566 -0.9951849 0 0.2902822 -0.9569412 0 0.4713959 -0.8819218 0 0.6343969 -0.7730076 0 0.9951848 -0.09801685 0 0.9951843 0.09802204 0 0.9569409 0.290283 0 0.8819193 0.4714006 0 0.7730128 0.6343905 0 0.6343969 0.7730076 0 0.2902909 0.9569385 0 -2.79654e-5 0 -1 -2.7966e-5 0 -1 4.14079e-5 0 -1 2.07091e-5 0 -1 1.42578e-5 0 -1 0.09802681 0.9951838 0 -0.2902757 0.9569432 0 4.1407e-5 0 1 2.07031e-5 0 1 -4.14145e-5 0 1 -4.14122e-5 0 1 2.79673e-5 0 1 -0.8819295 0.4713816 0 -0.9951848 -0.09801644 0 -0.6343891 -0.773014 0 -0.09800386 -0.995186 0 0.4714046 -0.8819171 0 0.9569436 -0.2902743 0 0.9951842 0.09802335 0 0.9569475 0.2902616 0 0.8819144 0.4714097 0 0.471413 0.8819127 0 2.38048e-5 0 -1 -2.38044e-5 0 -1 1.19026e-5 0 -1 8.03794e-6 0 -1 -1.19021e-5 0 -1 2.38044e-5 0 -1 -3.06336e-6 0 -1 -1.42778e-6 0 -1 1.42778e-6 0 -1 -2.97555e-6 0 1 5.95111e-6 0 1 -2.38046e-5 0 1 -2.38056e-5 0 1 1.60756e-5 0 1 -1.60757e-5 0 1 2.38056e-5 0 1 2.38046e-5 0 1 -0.4713972 0.8819211 0 -0.6343925 0.7730111 0 -0.7730149 0.6343879 0 -0.9569397 0.290287 0 -0.9951847 0.09801769 0 -0.7730119 -0.6343916 0 -0.6343925 -0.7730111 0 -0.4714013 -0.8819189 0 0.6343925 -0.7730111 0 0.9569397 0.290287 0 0.6343925 0.7730111 0 0.04906785 0.9987955 0 0.1467306 0.9891765 0 0.3368903 0.9415439 0 0.4275549 0.9039895 0 0.5141037 0.8577281 0 0.5956993 0.8032076 0 0.6715593 0.7409508 0 0.7409512 0.6715589 0 0.8032072 0.5956998 0 0.8577291 0.5141021 0 0.9039889 0.4275561 0 0.9415438 0.3368906 0 0.9700317 0.2429786 0 0.9891765 0.1467313 0 0.9891767 -0.1467294 0 0.9700312 -0.2429804 0 0.9415438 -0.3368906 0 0.8577291 -0.5141021 0 0.8032078 -0.5956992 0 0.7409522 -0.6715578 0 0.6715583 -0.7409518 0 0.5956998 -0.8032072 0 0.5141032 -0.8577284 0 0.4275553 -0.9039893 0 0.3368902 -0.9415439 0 0.1467305 -0.9891765 0 0.04906785 -0.9987955 0 -0.04906785 -0.9987955 0 -0.1467304 -0.9891765 0 -0.2429801 -0.9700313 0 -0.3368905 -0.9415439 0 -0.5141037 -0.8577281 0 -0.5956993 -0.8032076 0 -0.6715593 -0.7409508 0 -0.7409512 -0.6715589 0 -0.8032072 -0.5956998 0 -0.8577291 -0.5141021 0 -0.9039889 -0.4275561 0 -0.9415438 -0.3368906 0 -0.9700317 -0.2429786 0 -0.9891765 -0.1467313 0 -0.9891767 0.1467294 0 -0.9700312 0.2429804 0 -0.9415438 0.3368906 0 -0.8577291 0.5141021 0 -0.8032078 0.5956992 0 -0.7409522 0.6715578 0 -0.6715583 0.7409518 0 -0.5956998 0.8032072 0 -0.5141037 0.8577281 0 -0.3368905 0.9415439 0 -0.2429801 0.9700313 0 2.09253e-5 0 1 -4.18506e-5 0 1 -4.18508e-5 0 1 -4.18511e-5 0 1 -5.59808e-5 0 1 -4.18507e-5 0 1 -2.09253e-5 0 1 4.18506e-5 0 1 4.18508e-5 0 1 4.18511e-5 0 1 5.59808e-5 0 1 4.18507e-5 0 1 -5.26937e-6 0 1 5.2694e-6 0 1 -0.1467305 0.9891765 0 -0.04906785 0.9987955 0 -1.40629e-5 0 -1 1.4063e-5 0 -1 -2.79904e-5 0 -1 -6.27766e-5 0 -1 -1.4063e-5 0 -1 3.51573e-6 0 -1 -3.49875e-6 0 -1 5.23144e-6 0 -1 1.40629e-5 0 -1 -1.4063e-5 0 -1 2.79904e-5 0 -1 6.27766e-5 0 -1 1.4063e-5 0 -1 -3.51575e-6 0 -1 3.49875e-6 0 -1 -5.23155e-6 0 -1 1.77925e-6 0 -1 1.05387e-5 0 -1 -7.11699e-6 0 -1 7.25642e-6 0 -1 -1.05387e-5 0 -1 7.11699e-6 0 -1 -7.25642e-6 0 -1 -6.78091e-7 0 -1 6.7809e-7 0 -1 -6.32089e-7 0 -1 4.46954e-7 0 -1 6.32089e-7 0 -1 0.04906773 0.9987955 0 0.3368912 0.9415436 0 0.4275531 0.9039903 0 0.5140999 0.8577304 0 0.7409508 0.6715593 0 0.803209 0.5956975 0 0.8577296 0.5141013 0 0.9415441 0.3368899 0 0.9700313 0.2429804 0 0.9891762 0.1467326 0 0.9987955 0.04906892 0 0.9987956 -0.04906725 0 0.9891765 -0.146731 0 0.970032 -0.2429773 0 0.9415447 -0.3368884 0 0.8577288 -0.5141025 0 0.8032081 -0.5956986 0 0.7409517 -0.6715584 0 0.5140999 -0.8577304 0 0.4275537 -0.90399 0 0.3368909 -0.9415438 0 0.04906773 -0.9987955 0 -0.04906773 -0.9987955 0 -0.4275531 -0.9039903 0 -0.5140999 -0.8577304 0 -0.7409508 -0.6715593 0 -0.803209 -0.5956975 0 -0.8577296 -0.5141013 0 -0.9415441 -0.3368899 0 -0.9700313 -0.2429804 0 -0.9891762 -0.1467326 0 -0.9987955 -0.04906892 0 -0.9987956 0.04906725 0 -0.9891765 0.146731 0 -0.970032 0.2429773 0 -0.9415447 0.3368884 0 -0.8577288 0.5141025 0 -0.8032081 0.5956986 0 -0.7409517 0.6715584 0 -0.5140999 0.8577304 0 -0.4275537 0.90399 0 7.70806e-7 0 1 -1.23324e-5 0 1 -6.16622e-6 0 1 1.23324e-5 0 1 6.16622e-6 0 1 -3.10555e-6 0 1 6.21113e-6 0 1 3.10555e-6 0 1 -6.21113e-6 0 1 -3.19712e-6 0 1 7.9928e-7 0 1 3.19712e-6 0 1 -7.9928e-7 0 1 -0.04906773 0.9987955 0 -6.16652e-6 0 -1 -2.46654e-5 0 -1 -2.46654e-5 0 -1 3.08318e-6 0 -1 6.16652e-6 0 -1 2.46654e-5 0 -1 2.46654e-5 0 -1 -3.08318e-6 0 -1 - - - - - - - - - - 0.2891493 0.9186341 0.3001785 0.9276854 0.2911272 0.9387146 0.2211529 0.7879142 0.2264539 0.785946 0.2264539 0.7879142 0.2211529 0.7898825 0.2264539 0.7879142 0.2264539 0.7898825 0.2211529 0.7917751 0.2264539 0.7898825 0.2264539 0.7917751 0.339832 0.937572 0.3261786 0.9334301 0.3303204 0.9197767 0.2211529 0.7935193 0.2264539 0.7917751 0.2264539 0.7935193 0.2211529 0.7950481 0.2264539 0.7935193 0.2264539 0.7950481 0.2211529 0.8214344 0.2264539 0.8199056 0.2264539 0.8214344 0.2211529 0.8231787 0.2264539 0.8214344 0.2264539 0.8231787 0.2211529 0.8250712 0.2264539 0.8231787 0.2264539 0.8250712 0.2211529 0.8270395 0.2264539 0.8250712 0.2264539 0.8270395 0.2211529 0.8290078 0.2264539 0.8270395 0.2264539 0.8290078 0.2211529 0.8309003 0.2264539 0.8290078 0.2264539 0.8309003 0.2211529 0.8326445 0.2264539 0.8309003 0.2264539 0.8326445 0.2211529 0.8341734 0.2264539 0.8326445 0.2264539 0.8341734 0.9510146 0.8200913 0.9563157 0.8185383 0.9563157 0.8200913 0.9510146 0.8218535 0.9563157 0.8200913 0.9563157 0.8218535 0.9510146 0.8237569 0.9563157 0.8218535 0.9563157 0.8237569 0.9510146 0.8257287 0.9563157 0.8237569 0.9563157 0.8257287 0.9510146 0.8276927 0.9563157 0.8257287 0.9563157 0.8276927 0.9510146 0.8295737 0.9563157 0.8276927 0.9563157 0.8295737 0.9510146 0.8312993 0.9563157 0.8295737 0.9563157 0.8312993 0.9510146 0.8328033 0.9563157 0.8312993 0.9563157 0.8328033 0.9342217 0.05889558 0.9395228 0.05736678 0.9395228 0.05889558 0.9342217 0.06063985 0.9395228 0.05889558 0.9395228 0.06063985 0.9342217 0.06253242 0.9395228 0.06063985 0.9395228 0.06253242 0.9342217 0.06450068 0.9395228 0.06253242 0.9395228 0.06450068 0.9342217 0.06646889 0.9395228 0.06450068 0.9395228 0.06646889 0.9342217 0.06836152 0.9395228 0.06646889 0.9395228 0.06836152 0.9342217 0.07010573 0.9395228 0.06836152 0.9395228 0.07010573 0.9342217 0.07163459 0.9395228 0.07010573 0.9395228 0.07163459 0.2211529 0.7823092 0.2264539 0.7807803 0.2264539 0.7823092 0.2211529 0.7840534 0.2264539 0.7823092 0.2264539 0.7840534 0.2211529 0.785946 0.2264539 0.7840534 0.2264539 0.785946 0.7748915 0.2454419 0.7851052 0.4522329 0.7748915 0.4522329 0.7851052 0.2454419 0.7952206 0.4522329 0.7851052 0.4522329 0.7952206 0.2454419 0.8051401 0.4522329 0.7952206 0.4522329 0.8051401 0.2454419 0.8147684 0.4522329 0.8051401 0.4522329 0.8147684 0.2454419 0.8240126 0.4522329 0.8147684 0.4522329 0.8240126 0.2454419 0.8327838 0.4522329 0.8240126 0.4522329 0.8327838 0.2454419 0.8409974 0.4522329 0.8327838 0.4522329 0.8409974 0.2454419 0.8485744 0.4522329 0.8409974 0.4522329 0.7461242 0.5477672 0.7537012 0.7545582 0.7461242 0.7545582 0.7537012 0.5477672 0.7619149 0.7545582 0.7537012 0.7545582 0.7619149 0.5477672 0.770686 0.7545582 0.7619149 0.7545582 0.770686 0.5477672 0.7799302 0.7545582 0.770686 0.7545582 0.7799302 0.5477672 0.7895585 0.7545582 0.7799302 0.7545582 0.7895585 0.5477672 0.7994781 0.7545582 0.7895585 0.7545582 0.7994781 0.5477672 0.8095934 0.7545582 0.7994781 0.7545582 0.8095934 0.5477672 0.8198071 0.7545582 0.8095934 0.7545582 0.8198071 0.5477672 0.8300208 0.7545582 0.8198071 0.7545582 0.8300208 0.5477672 0.8401362 0.7545582 0.8300208 0.7545582 0.8401362 0.5477672 0.8500557 0.7545582 0.8401362 0.7545582 0.8500557 0.5477672 0.859684 0.7545582 0.8500557 0.7545582 0.859684 0.5477672 0.8689282 0.7545582 0.859684 0.7545582 0.8689282 0.5477672 0.8776994 0.7545582 0.8689282 0.7545582 0.8776994 0.5477672 0.885913 0.7545582 0.8776994 0.7545582 0.885913 0.5477672 0.89349 0.7545582 0.885913 0.7545582 0.0124287 0.7807803 0.0198698 0.9875713 0.0124287 0.9875713 0.0198698 0.7807803 0.0279625 0.9875713 0.0198698 0.9875713 0.0279625 0.7807803 0.03662902 0.9875713 0.0279625 0.9875713 0.03662902 0.7807803 0.04578584 0.9875713 0.03662902 0.9875713 0.04578584 0.7807803 0.05534482 0.9875713 0.04578584 0.9875713 0.05534482 0.7807803 0.06521379 0.9875713 0.05534482 0.9875713 0.06521379 0.7807803 0.07529783 0.9875713 0.06521379 0.9875713 0.07529783 0.7807803 0.08549976 0.9875713 0.07529783 0.9875713 0.08549976 0.7807803 0.09572136 0.9875713 0.08549976 0.9875713 0.09572136 0.7807803 0.1058641 0.9875713 0.09572136 0.9875713 0.1058641 0.7807803 0.1158305 0.9875713 0.1058641 0.9875713 0.1158305 0.7807803 0.1255244 0.9875713 0.1158305 0.9875713 0.1255244 0.7807803 0.1348524 0.9875713 0.1255244 0.9875713 0.1348524 0.7807803 0.1437249 0.9875713 0.1348524 0.9875713 0.1437249 0.7807803 0.1520562 0.9875713 0.1437249 0.9875713 0.1520562 0.7807803 0.1597662 0.9875713 0.1520562 0.9875713 0.7461242 0.7794157 0.7537012 0.9862067 0.7461242 0.9862067 0.7537012 0.7794157 0.7619149 0.9862067 0.7537012 0.9862067 0.7619149 0.7794157 0.770686 0.9862067 0.7619149 0.9862067 0.770686 0.7794157 0.7799302 0.9862067 0.770686 0.9862067 0.7799302 0.7794157 0.7895585 0.9862067 0.7799302 0.9862067 0.7895585 0.7794157 0.7994781 0.9862067 0.7895585 0.9862067 0.7994781 0.7794157 0.8095934 0.9862067 0.7994781 0.9862067 0.8095934 0.7794157 0.8198071 0.9862067 0.8095934 0.9862067 0.8198071 0.7794157 0.8300208 0.9862067 0.8198071 0.9862067 0.8300208 0.7794157 0.8401362 0.9862067 0.8300208 0.9862067 0.8401362 0.7794157 0.8500557 0.9862067 0.8401362 0.9862067 0.8500557 0.7794157 0.859684 0.9862067 0.8500557 0.9862067 0.859684 0.7794157 0.8689282 0.9862067 0.859684 0.9862067 0.8689282 0.7794157 0.8776994 0.9862067 0.8689282 0.9862067 0.8776994 0.7794157 0.885913 0.9862067 0.8776994 0.9862067 0.885913 0.7794157 0.89349 0.9862067 0.885913 0.9862067 0.7012087 0.2454419 0.7087856 0.4522329 0.7012087 0.4522329 0.7087856 0.2454419 0.7169992 0.4522329 0.7087856 0.4522329 0.7169992 0.2454419 0.7257704 0.4522329 0.7169992 0.4522329 0.7257704 0.2454419 0.7350146 0.4522329 0.7257704 0.4522329 0.7350146 0.2454419 0.7446429 0.4522329 0.7350146 0.4522329 0.7446429 0.2454419 0.7545624 0.4522329 0.7446429 0.4522329 0.1785804 0.5681481 0.219582 0.6365553 0.01343107 0.6671348 0.7545624 0.2454419 0.7646778 0.4522329 0.7545624 0.4522329 0.7646778 0.2454419 0.7748915 0.4522329 0.7646778 0.4522329 0.280098 0.656958 0.3790628 0.5477672 0.4882536 0.646732 0.4719411 0.9186341 0.4793303 0.9208756 0.4829704 0.9276854 0.9342218 0.103626 0.9395228 0.1016577 0.9395228 0.103626 0.9342218 0.1055942 0.9395228 0.103626 0.9395228 0.1055942 0.9342218 0.1074868 0.9395228 0.1055942 0.9395228 0.1074868 0.5082137 0.9316031 0.5149395 0.91902 0.5275226 0.9257457 0.9342218 0.109231 0.9395228 0.1074868 0.9395228 0.109231 0.9342218 0.1107599 0.9395228 0.109231 0.9395228 0.1107599 0.9504621 0.4786192 0.9557631 0.4770904 0.9557631 0.4786192 0.9504621 0.4803634 0.9557631 0.4786192 0.9557631 0.4803634 0.9504621 0.4822561 0.9557631 0.4803634 0.9557631 0.4822561 0.9504621 0.4842243 0.9557631 0.4822561 0.9557631 0.4842243 0.9504621 0.4861925 0.9557631 0.4842243 0.9557631 0.4861925 0.9504621 0.4880851 0.9557631 0.4861925 0.9557631 0.4880851 0.9504621 0.4898293 0.9557631 0.4880851 0.9557631 0.4898293 0.9504621 0.4913582 0.9557631 0.4898293 0.9557631 0.4913582 0.9510147 0.6790419 0.9563158 0.6774888 0.9563158 0.6790419 0.9510147 0.680804 0.9563158 0.6790419 0.9563158 0.680804 0.9510147 0.6827074 0.9563158 0.680804 0.9563158 0.6827074 0.9510147 0.6846791 0.9563158 0.6827074 0.9563158 0.6846791 0.9510147 0.6866432 0.9563158 0.6846791 0.9563158 0.6866432 0.9510147 0.6885243 0.9563158 0.6866432 0.9563158 0.6885243 0.9510147 0.6902498 0.9563158 0.6885243 0.9563158 0.6902498 0.9510147 0.6917538 0.9563158 0.6902498 0.9563158 0.6917538 0.9510147 0.5492961 0.9563158 0.5477672 0.9563158 0.5492961 0.9510147 0.5510403 0.9563158 0.5492961 0.9563158 0.5510403 0.9510147 0.5529329 0.9563158 0.5510403 0.9563158 0.5529329 0.9510147 0.5549011 0.9563158 0.5529329 0.9563158 0.5549011 0.9510147 0.5568693 0.9563158 0.5549011 0.9563158 0.5568693 0.9510147 0.558762 0.9563158 0.5568693 0.9563158 0.558762 0.9510147 0.5605062 0.9563158 0.558762 0.9563158 0.5605062 0.9510147 0.562035 0.9563158 0.5605062 0.9563158 0.562035 0.9342218 0.09802091 0.9395228 0.09649205 0.9395228 0.09802091 0.9342218 0.09976506 0.9395228 0.09802091 0.9395228 0.09976506 0.9342218 0.1016577 0.9395228 0.09976506 0.9395228 0.1016577 0.9248849 0.5012809 0.9157477 0.5124147 0.901414 0.5138265 0.8734319 0.4309719 0.8812416 0.4273006 0.8812416 0.4309719 0.8734319 0.4346432 0.8812416 0.4309719 0.8812416 0.4346432 0.8734319 0.4381734 0.8812416 0.4346432 0.8812416 0.4381734 0.7053897 0.4838799 0.731875 0.4812715 0.7344834 0.5077567 0.8734319 0.4414269 0.8812416 0.4381734 0.8812416 0.4414269 0.8734319 0.4442786 0.8812416 0.4414269 0.8812416 0.4442786 0.9183475 0.5506189 0.9261572 0.5477672 0.9261572 0.5506189 0.9183475 0.5538724 0.9261572 0.5506189 0.9261572 0.5538724 0.9183475 0.5574026 0.9261572 0.5538724 0.9261572 0.5574026 0.9183475 0.5610739 0.9261572 0.5574026 0.9261572 0.5610739 0.9183475 0.5647452 0.9261572 0.5610739 0.9261572 0.5647452 0.9183475 0.5682754 0.9261572 0.5647452 0.9261572 0.5682754 0.9183475 0.5715289 0.9261572 0.5682754 0.9261572 0.5715289 0.9183475 0.5743806 0.9261572 0.5715289 0.9261572 0.5743806 0.6980601 0.908304 0.7058699 0.905407 0.7058699 0.908304 0.6980601 0.9115909 0.7058699 0.908304 0.7058699 0.9115909 0.6980601 0.9151414 0.7058699 0.9115909 0.7058699 0.9151414 0.6980601 0.9188191 0.7058699 0.9151414 0.7058699 0.9188191 0.6980601 0.9224826 0.7058699 0.9188191 0.7058699 0.9224826 0.6980601 0.9259912 0.7058699 0.9224826 0.7058699 0.9259912 0.6980601 0.92921 0.7058699 0.9259912 0.7058699 0.92921 0.6980601 0.9320154 0.7058699 0.92921 0.7058699 0.9320154 0.9183475 0.6020898 0.9261572 0.5992382 0.9261572 0.6020898 0.9183475 0.6053434 0.9261572 0.6020898 0.9261572 0.6053434 0.9183475 0.6088736 0.9261572 0.6053434 0.9261572 0.6088736 0.9183475 0.6125448 0.9261572 0.6088736 0.9261572 0.6125448 0.9183475 0.6162161 0.9261572 0.6125448 0.9261572 0.6162161 0.9183475 0.6197464 0.9261572 0.6162161 0.9261572 0.6197464 0.9183475 0.6229999 0.9261572 0.6197464 0.9261572 0.6229999 0.9183475 0.6258516 0.9261572 0.6229999 0.9261572 0.6258516 0.8734319 0.4205169 0.8812416 0.4176651 0.8812416 0.4205169 0.8734319 0.4237704 0.8812416 0.4205169 0.8812416 0.4237704 0.8734319 0.4273006 0.8812416 0.4237704 0.8812416 0.4273006 0.9342217 0.02345788 0.943273 0.0124287 0.9543022 0.02148008 0.9342217 0.1427512 0.9395228 0.140783 0.9395228 0.1427512 0.9342217 0.1447195 0.9395228 0.1427512 0.9395228 0.1447195 0.9342217 0.1466121 0.9395228 0.1447195 0.9395228 0.1466121 0.9236319 0.9349712 0.9372853 0.9391129 0.9331435 0.9527663 0.9342217 0.1483563 0.9395228 0.1466121 0.9395228 0.1483563 0.9342217 0.1498851 0.9395228 0.1483563 0.9395228 0.1498851 0.9510147 0.600767 0.9563158 0.5992382 0.9563158 0.600767 0.9510147 0.6025112 0.9563158 0.600767 0.9563158 0.6025112 0.9510147 0.6044038 0.9563158 0.6025112 0.9563158 0.6044038 0.9510147 0.606372 0.9563158 0.6044038 0.9563158 0.606372 0.9510147 0.6083403 0.9563158 0.606372 0.9563158 0.6083403 0.9510147 0.6102328 0.9563158 0.6083403 0.9563158 0.6102328 0.9510147 0.6119771 0.9563158 0.6102328 0.9563158 0.6119771 0.9510147 0.6135059 0.9563158 0.6119771 0.9563158 0.6135059 0.9510146 0.7181644 0.9563157 0.7166113 0.9563157 0.7181644 0.9510146 0.7199265 0.9563157 0.7181644 0.9563157 0.7199265 0.9510146 0.72183 0.9563157 0.7199265 0.9563157 0.72183 0.9510146 0.7238017 0.9563157 0.72183 0.9563157 0.7238017 0.9510146 0.7257657 0.9563157 0.7238017 0.9563157 0.7257657 0.9510146 0.7276467 0.9563157 0.7257657 0.9563157 0.7276467 0.9510146 0.7293724 0.9563157 0.7276467 0.9563157 0.7293724 0.9510146 0.7308763 0.9563157 0.7293724 0.9563157 0.7308763 0.9510146 0.6398923 0.9563157 0.6383635 0.9563157 0.6398923 0.9510146 0.6416366 0.9563157 0.6398923 0.9563157 0.6416366 0.9510146 0.6435291 0.9563157 0.6416366 0.9563157 0.6435291 0.9510146 0.6454974 0.9563157 0.6435291 0.9563157 0.6454974 0.9510146 0.6474656 0.9563157 0.6454974 0.9563157 0.6474656 0.9510146 0.6493582 0.9563157 0.6474656 0.9563157 0.6493582 0.9510146 0.6511024 0.9563157 0.6493582 0.9563157 0.6511024 0.9510146 0.6526312 0.9563157 0.6511024 0.9563157 0.6526312 0.9342217 0.1371462 0.9395228 0.1356173 0.9395228 0.1371462 0.9342217 0.1388905 0.9395228 0.1371462 0.9395228 0.1388905 0.9342217 0.140783 0.9395228 0.1388905 0.9395228 0.140783 0.6661127 0.8563589 0.6895836 0.8438133 0.7021292 0.8672842 0.9060992 0.4309719 0.9139088 0.4273005 0.9139088 0.4309719 0.9060992 0.4346432 0.9139088 0.4309719 0.9139088 0.4346432 0.9060992 0.4381734 0.9139088 0.4346432 0.9139088 0.4381734 0.7703115 0.5103652 0.767703 0.4838799 0.7941883 0.4812715 0.9060992 0.4414269 0.9139088 0.4381734 0.9139088 0.4414269 0.9060992 0.4442785 0.9139088 0.4414269 0.9139088 0.4442785 0.9183475 0.6535608 0.9261572 0.6507092 0.9261572 0.6535608 0.9183475 0.6568143 0.9261572 0.6535608 0.9261572 0.6568143 0.9183475 0.6603446 0.9261572 0.6568143 0.9261572 0.6603446 0.9183475 0.6640158 0.9261572 0.6603446 0.9261572 0.6640158 0.9183475 0.6676872 0.9261572 0.6640158 0.9261572 0.6676872 0.9183475 0.6712174 0.9261572 0.6676872 0.9261572 0.6712174 0.9183475 0.6744709 0.9261572 0.6712174 0.9261572 0.6744709 0.9183475 0.6773226 0.9261572 0.6744709 0.9261572 0.6773225 0.9268475 0.2998047 0.9346572 0.2969077 0.9346572 0.2998047 0.9268475 0.3030916 0.9346572 0.2998047 0.9346572 0.3030916 0.9268475 0.3066421 0.9346572 0.3030916 0.9346572 0.3066421 0.9268475 0.3103198 0.9346572 0.3066421 0.9346572 0.3103198 0.9268475 0.3139833 0.9346572 0.3103198 0.9346572 0.3139833 0.9268475 0.3174919 0.9346572 0.3139833 0.9346572 0.3174919 0.9268475 0.3207107 0.9346572 0.3174919 0.9346572 0.3207107 0.9268475 0.323516 0.9346572 0.3207107 0.9346572 0.323516 0.9183474 0.7050318 0.9261572 0.7021801 0.9261572 0.7050318 0.9183474 0.7082853 0.9261572 0.7050318 0.9261572 0.7082853 0.9183474 0.7118155 0.9261572 0.7082853 0.9261572 0.7118155 0.9183474 0.7154868 0.9261572 0.7118155 0.9261572 0.7154868 0.9183474 0.7191581 0.9261572 0.7154868 0.9261572 0.7191581 0.9183474 0.7226883 0.9261572 0.7191581 0.9261572 0.7226883 0.9183474 0.7259418 0.9261572 0.7226883 0.9261572 0.7259418 0.9183474 0.7287935 0.9261572 0.7259418 0.9261572 0.7287935 0.9060992 0.4205168 0.9139088 0.4176651 0.9139088 0.4205168 0.9060992 0.4237703 0.9139088 0.4205168 0.9139088 0.4237703 0.9060992 0.4273005 0.9139088 0.4237703 0.9139088 0.4273005 0.6653929 0.8013528 0.6822763 0.7807803 0.7028487 0.7976636 0.2474307 0.9055204 0.2552404 0.9018491 0.2552404 0.9055204 0.2474307 0.9091917 0.2552404 0.9055204 0.2552404 0.9091917 0.2474307 0.9127219 0.2552404 0.9091917 0.2552404 0.9127219 0.8391005 0.4778101 0.8625714 0.4903556 0.850026 0.5138266 0.2474307 0.9159754 0.2552404 0.9127219 0.2552404 0.9159754 0.2474307 0.9188271 0.2552404 0.9159754 0.2552404 0.9188271 0.9183474 0.7822674 0.9261572 0.7794157 0.9261572 0.7822674 0.9183474 0.7855209 0.9261572 0.7822674 0.9261572 0.7855209 0.9183474 0.7890511 0.9261572 0.7855209 0.9261572 0.7890511 0.9183474 0.7927224 0.9261572 0.7890511 0.9261572 0.7927224 0.9183475 0.7963938 0.9261572 0.7927224 0.9261572 0.7963938 0.9183475 0.799924 0.9261572 0.7963938 0.9261572 0.799924 0.9183475 0.8031774 0.9261572 0.799924 0.9261572 0.8031774 0.9183475 0.8060292 0.9261572 0.8031774 0.9261572 0.8060292 0.9268475 0.3512705 0.9346572 0.3483735 0.9346572 0.3512705 0.9268475 0.3545575 0.9346572 0.3512705 0.9346572 0.3545575 0.9268475 0.3581079 0.9346572 0.3545575 0.9346572 0.3581079 0.9268475 0.3617857 0.9346572 0.3581079 0.9346572 0.3617857 0.9268475 0.3654492 0.9346572 0.3617857 0.9346572 0.3654492 0.9268475 0.3689578 0.9346572 0.3654492 0.9346572 0.3689578 0.9268475 0.3721766 0.9346572 0.3689578 0.9346572 0.3721766 0.9268475 0.3749819 0.9346572 0.3721766 0.9346572 0.3749819 0.9183475 0.8337383 0.9261572 0.8308867 0.9261572 0.8337383 0.9183475 0.8369919 0.9261572 0.8337383 0.9261572 0.8369919 0.9183475 0.8405221 0.9261572 0.8369919 0.9261572 0.8405221 0.9183475 0.8441934 0.9261572 0.8405221 0.9261572 0.8441934 0.9183475 0.8478647 0.9261572 0.8441934 0.9261572 0.8478647 0.9183475 0.851395 0.9261572 0.8478647 0.9261572 0.851395 0.9183475 0.8546484 0.9261572 0.851395 0.9261572 0.8546484 0.9183475 0.8575001 0.9261572 0.8546484 0.9261572 0.8575001 0.2474307 0.8950654 0.2552404 0.8922137 0.2552404 0.8950654 0.2474307 0.8983189 0.2552404 0.8950654 0.2552404 0.8983189 0.2474307 0.9018491 0.2552404 0.8983189 0.2552404 0.9018491 0.3829429 0.9383288 0.3703598 0.931603 0.3770856 0.9190199 0.9342218 0.1818765 0.9395228 0.1799083 0.9395228 0.1818765 0.9342218 0.1838448 0.9395228 0.1818765 0.9395228 0.1838448 0.9342218 0.1857374 0.9395228 0.1838448 0.9395228 0.1857374 0.4190945 0.9334301 0.4232362 0.9197767 0.4368896 0.9239186 0.9342218 0.1874816 0.9395228 0.1857374 0.9395228 0.1874816 0.9342218 0.1890105 0.9395228 0.1874816 0.9395228 0.1890105 0.9387664 0.4191939 0.9440674 0.4176651 0.9440674 0.4191939 0.9387664 0.4209381 0.9440674 0.4191939 0.9440674 0.4209381 0.9387664 0.4228308 0.9440674 0.4209381 0.9440674 0.4228308 0.9387664 0.424799 0.9440674 0.4228308 0.9440674 0.424799 0.9387664 0.4267672 0.9440674 0.424799 0.9440674 0.4267672 0.9387664 0.4286598 0.9440674 0.4267672 0.9440674 0.4286598 0.9387664 0.4304041 0.9440674 0.4286598 0.9440674 0.4304041 0.9387664 0.4319329 0.9440674 0.4304041 0.9440674 0.4319329 0.9510147 0.7809689 0.9563158 0.7794158 0.9563158 0.7809689 0.9510147 0.7827311 0.9563158 0.7809689 0.9563158 0.7827311 0.9510147 0.7846345 0.9563158 0.7827311 0.9563158 0.7846345 0.9510147 0.7866061 0.9563158 0.7846345 0.9563158 0.7866061 0.9510147 0.7885702 0.9563158 0.7866061 0.9563158 0.7885702 0.9510147 0.7904513 0.9563158 0.7885702 0.9563158 0.7904513 0.9510147 0.7921769 0.9563158 0.7904513 0.9563158 0.7921769 0.9510147 0.7936809 0.9563158 0.7921769 0.9563158 0.7936809 0.6288638 0.9386191 0.6341648 0.9370902 0.6341648 0.9386191 0.6288638 0.9403633 0.6341648 0.9386191 0.6341648 0.9403633 0.6288638 0.9422559 0.6341648 0.9403633 0.6341648 0.9422559 0.6288638 0.9442241 0.6341648 0.9422559 0.6341648 0.9442241 0.6288638 0.9461924 0.6341648 0.9442241 0.6341648 0.9461924 0.6288638 0.948085 0.6341648 0.9461924 0.6341648 0.948085 0.6288638 0.9498292 0.6341648 0.948085 0.6341648 0.9498292 0.6288638 0.951358 0.6341648 0.9498292 0.6341648 0.951358 0.9342218 0.1762715 0.9395228 0.1747426 0.9395228 0.1762715 0.9342218 0.1780157 0.9395228 0.1762715 0.9395228 0.1780157 0.9342218 0.1799083 0.9395228 0.1780157 0.9395228 0.1799083 0.2199481 0.8954916 0.2213599 0.9098253 0.1853434 0.8988998 0.6288638 0.898926 0.6366735 0.8952547 0.6366735 0.898926 0.6288638 0.9025973 0.6366735 0.898926 0.6366735 0.9025973 0.6288638 0.9061276 0.6366735 0.9025973 0.6366735 0.9061275 0.5890804 0.916301 0.576378 0.9230905 0.5625951 0.9189094 0.6288638 0.909381 0.6366735 0.9061275 0.6366735 0.909381 0.6288638 0.9122327 0.6366735 0.909381 0.6366735 0.9122327 0.9183475 0.8852093 0.9261572 0.8823576 0.9261572 0.8852093 0.9183475 0.8884628 0.9261572 0.8852093 0.9261572 0.8884628 0.9183475 0.891993 0.9261572 0.8884628 0.9261572 0.891993 0.9183475 0.8956643 0.9261572 0.891993 0.9261572 0.8956643 0.9183475 0.8993356 0.9261572 0.8956643 0.9261572 0.8993356 0.9183475 0.9028658 0.9261572 0.8993356 0.9261572 0.9028658 0.9183475 0.9061194 0.9261572 0.9028658 0.9261572 0.9061194 0.9183475 0.908971 0.9261572 0.9061194 0.9261572 0.908971 0.9268475 0.2483388 0.9346572 0.2454418 0.9346572 0.2483388 0.9268475 0.2516257 0.9346572 0.2483388 0.9346572 0.2516257 0.9268475 0.2551763 0.9346572 0.2516257 0.9346572 0.2551763 0.9268475 0.2588539 0.9346572 0.2551763 0.9346572 0.2588539 0.9268475 0.2625175 0.9346572 0.2588539 0.9346572 0.2625175 0.9268475 0.266026 0.9346572 0.2625175 0.9346572 0.266026 0.9268475 0.2692449 0.9346572 0.266026 0.9346572 0.2692449 0.9268475 0.2720502 0.9346572 0.2692449 0.9346572 0.2720502 0.6653929 0.9082587 0.6732026 0.905407 0.6732026 0.9082587 0.6653929 0.9115122 0.6732026 0.9082587 0.6732026 0.9115122 0.6653929 0.9150424 0.6732026 0.9115122 0.6732026 0.9150424 0.6653929 0.9187138 0.6732026 0.9150424 0.6732026 0.9187138 0.6653929 0.922385 0.6732026 0.9187138 0.6732026 0.922385 0.6653929 0.9259153 0.6732026 0.922385 0.6732026 0.9259153 0.6653929 0.9291687 0.6732026 0.9259153 0.6732026 0.9291687 0.6653929 0.9320204 0.6732026 0.9291687 0.6732026 0.9320204 0.6288638 0.888471 0.6366735 0.8856193 0.6366735 0.888471 0.6288638 0.8917245 0.6366735 0.888471 0.6366735 0.8917245 0.6288638 0.8952547 0.6366735 0.8917245 0.6366735 0.8952547 0.0124287 0.2552404 0.2552404 0.01242876 0.2552404 0.2552404 0.5477672 0.2552404 0.5729795 0.01242876 0.5729795 0.2552404 0.5978369 0.5228631 0.6230491 0.280098 0.6230491 0.5228631 0.5477672 0.5229097 0.5729794 0.280098 0.5729794 0.5229097 0.01242876 0.5229097 0.2552404 0.280098 0.2552404 0.5229097 0.5978369 0.2552404 0.6230491 0.0124287 0.6230492 0.2552404 0.280098 0.2552404 0.5229097 0.01242876 0.5229097 0.2552404 0.6479067 0.2552404 0.6497001 0.01242876 0.6497001 0.2552404 0.6745576 0.5228631 0.6763511 0.280098 0.6763511 0.5228631 0.6479067 0.5229097 0.6497001 0.280098 0.6497001 0.5229097 0.280098 0.5229097 0.5229097 0.280098 0.5229097 0.5229097 0.6745576 0.2552404 0.676351 0.01242876 0.6763511 0.2552404 0.1846237 0.8207787 0.1962953 0.8152342 0.1962953 0.8207787 0.1846237 0.8152342 0.1962953 0.8097431 0.1962953 0.8152342 0.1846237 0.8097431 0.1962953 0.8043584 0.1962953 0.8097431 0.1846237 0.8043584 0.1962953 0.7991317 0.1962953 0.8043584 0.1846237 0.7991317 0.1962953 0.7941135 0.1962953 0.7991317 0.1846237 0.7941135 0.1962953 0.7893521 0.1962953 0.7941135 0.1846237 0.7893521 0.1962953 0.7848934 0.1962953 0.7893521 0.1846237 0.7848934 0.1962953 0.7807803 0.1962953 0.7848934 0.5558055 0.860777 0.5674771 0.856664 0.5674771 0.860777 0.5558055 0.856664 0.5674771 0.8522052 0.5674771 0.856664 0.5558055 0.8522052 0.5674771 0.8474438 0.5674771 0.8522052 0.5558055 0.8474438 0.5674771 0.8424257 0.5674771 0.8474438 0.5558055 0.8424257 0.5674771 0.837199 0.5674771 0.8424257 0.5558055 0.837199 0.5674771 0.8318142 0.5674771 0.837199 0.5558055 0.8318142 0.5674771 0.8263231 0.5674771 0.8318142 0.5558055 0.8263231 0.5674771 0.8207787 0.5674771 0.8263231 0.5558055 0.8207787 0.5674771 0.8152342 0.5674771 0.8207787 0.5558055 0.8152342 0.5674771 0.8097431 0.5674771 0.8152342 0.5558055 0.8097431 0.5674771 0.8043583 0.5674771 0.8097431 0.5558055 0.8043583 0.5674771 0.7991317 0.5674771 0.8043583 0.5558055 0.7991317 0.5674771 0.7941135 0.5674771 0.7991317 0.5558055 0.7941135 0.5674771 0.7893521 0.5674771 0.7941135 0.5558055 0.7893521 0.5674771 0.7848934 0.5674771 0.7893521 0.5558055 0.7848934 0.5674771 0.7807803 0.5674771 0.7848934 0.6288638 0.8607618 0.6405354 0.8567225 0.6405354 0.8607618 0.6288638 0.8567225 0.6405354 0.8523294 0.6405354 0.8567225 0.6288638 0.8523294 0.6405354 0.8476248 0.6405354 0.8523294 0.6288638 0.8476248 0.6405354 0.8426541 0.6405354 0.8476248 0.6288638 0.8426541 0.6405354 0.837465 0.6405354 0.8426541 0.6288638 0.837465 0.6405354 0.8321077 0.6405354 0.837465 0.6288638 0.8321077 0.6405354 0.8266336 0.6405354 0.8321077 0.6288638 0.8266336 0.6405354 0.8210955 0.6405354 0.8266336 0.6288638 0.8210955 0.6405354 0.8155468 0.6405354 0.8210955 0.6288638 0.8155468 0.6405354 0.8100408 0.6405354 0.8155468 0.6288638 0.8100408 0.6405354 0.8046306 0.6405354 0.8100408 0.6288638 0.8046306 0.6405354 0.7993684 0.6405354 0.8046306 0.6288638 0.7993684 0.6405354 0.7943047 0.6405354 0.7993684 0.6288638 0.7943047 0.6405354 0.7894883 0.6405354 0.7943047 0.6288638 0.7894883 0.6405354 0.7849657 0.6405354 0.7894883 0.6288638 0.7849657 0.6405354 0.7807803 0.6405354 0.7849657 0.5923346 0.8607771 0.6040062 0.856664 0.6040062 0.8607771 0.5923346 0.856664 0.6040062 0.8522052 0.6040062 0.856664 0.5923346 0.8522053 0.6040062 0.8474439 0.6040062 0.8522052 0.5923346 0.8474439 0.6040062 0.8424257 0.6040062 0.8474439 0.5923346 0.8424257 0.6040062 0.837199 0.6040062 0.8424257 0.5923346 0.837199 0.6040062 0.8318142 0.6040062 0.837199 0.5923346 0.8318142 0.6040062 0.8263232 0.6040062 0.8318142 0.5923346 0.8263232 0.6040062 0.8207787 0.6040062 0.8263232 0.5923346 0.8207787 0.6040062 0.8152343 0.6040062 0.8207787 0.5923346 0.8152343 0.6040062 0.8097432 0.6040062 0.8152343 0.5923346 0.8097432 0.6040062 0.8043584 0.6040062 0.8097432 0.5923346 0.8043584 0.6040062 0.7991318 0.6040062 0.8043584 0.5923346 0.7991318 0.6040062 0.7941136 0.6040062 0.7991318 0.5923346 0.7941136 0.6040062 0.7893522 0.6040062 0.7941136 0.5923346 0.7893522 0.6040062 0.7848935 0.6040062 0.7893522 0.5923346 0.7848935 0.6040062 0.7807803 0.6040062 0.7848935 0.1846237 0.8607771 0.1962953 0.856664 0.1962953 0.8607771 0.1846237 0.856664 0.1962953 0.8522052 0.1962953 0.856664 0.1846237 0.8522052 0.1962953 0.8474438 0.1962953 0.8522052 0.1846237 0.8474438 0.1962953 0.8424257 0.1962953 0.8474438 0.1846237 0.8424257 0.1962953 0.837199 0.1962953 0.8424257 0.1846237 0.837199 0.1962953 0.8318142 0.1962953 0.837199 0.3930943 0.840054 0.3745837 0.8791913 0.2946833 0.8752661 0.1846237 0.8318142 0.1962953 0.8263232 0.1962953 0.8318142 0.1846237 0.8263232 0.1962953 0.8207787 0.1962953 0.8263232 0.4502646 0.8884137 0.4211902 0.8563351 0.5277095 0.8182218 0.2533901 0.62145 0.2552404 0.6112363 0.2552404 0.62145 0.2533901 0.6112363 0.2552404 0.601121 0.2552404 0.6112363 0.2533901 0.601121 0.2552404 0.5912014 0.2552404 0.601121 0.2533901 0.5912014 0.2552404 0.5815731 0.2552404 0.5912014 0.2533901 0.5815731 0.2552404 0.5723289 0.2552404 0.5815731 0.2533901 0.5723289 0.2552404 0.5635578 0.2552404 0.5723289 0.2533901 0.5635578 0.2552404 0.5553441 0.2552404 0.5635578 0.2533901 0.5553441 0.2552404 0.5477672 0.2552404 0.5553441 0.2533902 0.8673562 0.2552404 0.8597792 0.2552404 0.8673562 0.2533902 0.8597792 0.2552404 0.8515655 0.2552404 0.8597792 0.2533902 0.8515655 0.2552404 0.8427944 0.2552404 0.8515655 0.2533902 0.8427944 0.2552404 0.8335502 0.2552404 0.8427944 0.2533902 0.8335502 0.2552404 0.8239219 0.2552404 0.8335502 0.2533902 0.8239219 0.2552404 0.8140023 0.2552404 0.8239219 0.2533902 0.8140023 0.2552404 0.803887 0.2552404 0.8140023 0.2533902 0.803887 0.2552404 0.7936733 0.2552404 0.803887 0.2533902 0.7936733 0.2552404 0.7834596 0.2552404 0.7936733 0.2533902 0.7834596 0.2552404 0.7733442 0.2552404 0.7834596 0.2533902 0.7733442 0.2552404 0.7634247 0.2552404 0.7733442 0.2533902 0.7634247 0.2552404 0.7537964 0.2552404 0.7634247 0.2533902 0.7537964 0.2552404 0.7445522 0.2552404 0.7537964 0.2533902 0.7445522 0.2552404 0.735781 0.2552404 0.7445522 0.2533902 0.735781 0.2552404 0.7275674 0.2552404 0.735781 0.2533902 0.7275674 0.2552404 0.7199904 0.2552404 0.7275674 0.9001397 0.3927794 0.9019899 0.3853383 0.9019899 0.3927794 0.9001397 0.3853383 0.9019899 0.3772456 0.9019899 0.3853383 0.9001397 0.3772456 0.9019899 0.368579 0.9019899 0.3772456 0.9001397 0.368579 0.9019899 0.3594222 0.9019899 0.368579 0.9001397 0.3594222 0.9019899 0.3498632 0.9019899 0.3594222 0.9001397 0.3498632 0.9019899 0.3399943 0.9019899 0.3498632 0.9001397 0.3399943 0.9019899 0.3299102 0.9019899 0.3399943 0.9001397 0.3299102 0.9019899 0.3197083 0.9019899 0.3299102 0.9001397 0.3197083 0.9019899 0.3094867 0.9019899 0.3197083 0.9001397 0.3094867 0.9019899 0.2993439 0.9019899 0.3094867 0.9001397 0.2993439 0.9019899 0.2893776 0.9019899 0.2993439 0.9001397 0.2893776 0.9019899 0.2796837 0.9019899 0.2893776 0.9001397 0.2796837 0.9019899 0.2703557 0.9019899 0.2796837 0.9001397 0.2703557 0.9019899 0.2614832 0.9019899 0.2703557 0.9001397 0.2614832 0.9019899 0.2531518 0.9019899 0.2614832 0.9001397 0.2531518 0.9019899 0.2454418 0.9019899 0.2531518 0.8734319 0.3928076 0.8752822 0.3852306 0.8752822 0.3928076 0.8734319 0.3852306 0.8752822 0.377017 0.8752822 0.3852306 0.8734319 0.377017 0.8752822 0.3682458 0.8752822 0.377017 0.8734319 0.3682458 0.8752822 0.3590016 0.8752822 0.3682458 0.8734319 0.3590016 0.8752822 0.3493734 0.8752822 0.3590016 0.8734319 0.3493734 0.8752822 0.3394538 0.8752822 0.3493734 0.8734319 0.3394538 0.8752822 0.3293384 0.8752822 0.3394538 0.8734319 0.3293384 0.8752822 0.3191247 0.8752822 0.3293384 0.8734319 0.3191247 0.8752822 0.308911 0.8752822 0.3191247 0.8734319 0.308911 0.8752822 0.2987957 0.8752822 0.308911 0.8734319 0.2987957 0.8752822 0.2888761 0.8752822 0.2987957 0.8734319 0.2888761 0.8752822 0.2792478 0.8752822 0.2888761 0.8734319 0.2792478 0.8752822 0.2700036 0.8752822 0.2792478 0.8734319 0.2700036 0.8752822 0.2612324 0.8752822 0.2700036 0.8734319 0.2612324 0.8752822 0.2530189 0.8752822 0.2612324 0.8734319 0.2530189 0.8752822 0.2454419 0.8752822 0.2530189 0.2533902 0.6951329 0.2552404 0.6875559 0.2552404 0.6951329 0.2533902 0.6875559 0.2552404 0.6793423 0.2552404 0.6875559 0.2533902 0.6793423 0.2552404 0.6705712 0.2552404 0.6793423 0.2533902 0.6705712 0.2552404 0.6613269 0.2552404 0.6705712 0.2533901 0.6613269 0.2552404 0.6516987 0.2552404 0.6613269 0.2533901 0.6516987 0.2552404 0.6417791 0.2552404 0.6516987 0.6792628 0.5681481 0.7202644 0.6365553 0.5141134 0.6671348 0.2533901 0.6417791 0.2552404 0.6316637 0.2552404 0.6417791 0.2533901 0.6316637 0.2552404 0.62145 0.2552404 0.6316637 0.7012086 0.1216195 0.8001734 0.01242876 0.9093642 0.1113936 0.2911272 0.9387146 0.2891494 0.9387146 0.2872096 0.9383288 0.2872096 0.9383288 0.2853824 0.937572 0.283738 0.9364732 0.283738 0.9364732 0.2823395 0.9350747 0.2812407 0.9334303 0.2812407 0.9334303 0.2804838 0.9316031 0.283738 0.9364732 0.2804838 0.9316031 0.2800979 0.9296633 0.283738 0.9364732 0.2800979 0.9296633 0.2800979 0.9276856 0.2804837 0.9257458 0.2804837 0.9257458 0.2812407 0.9239186 0.2800979 0.9296633 0.2812407 0.9239186 0.2823393 0.9222741 0.2800979 0.9296633 0.2823393 0.9222741 0.2837378 0.9208756 0.2853823 0.9197768 0.2853823 0.9197768 0.2872095 0.9190199 0.2891493 0.9186341 0.2891493 0.9186341 0.291127 0.9186341 0.2965385 0.9208756 0.291127 0.9186341 0.2930668 0.9190199 0.2965385 0.9208756 0.2930668 0.9190199 0.294894 0.9197768 0.2965385 0.9208756 0.2965385 0.9208756 0.2979369 0.922274 0.2990357 0.9239185 0.2990357 0.9239185 0.2997927 0.9257457 0.3001785 0.9276854 0.3001785 0.9276854 0.3001785 0.9296632 0.2997927 0.931603 0.2997927 0.931603 0.2990358 0.9334302 0.297937 0.9350746 0.297937 0.9350746 0.2965385 0.9364731 0.2911272 0.9387146 0.2965385 0.9364731 0.2948941 0.9375719 0.2911272 0.9387146 0.2948941 0.9375719 0.2930669 0.9383288 0.2911272 0.9387146 0.2911272 0.9387146 0.2872096 0.9383288 0.2800979 0.9296633 0.2872096 0.9383288 0.283738 0.9364732 0.2800979 0.9296633 0.2823393 0.9222741 0.2853823 0.9197768 0.2800979 0.9296633 0.2853823 0.9197768 0.2891493 0.9186341 0.2800979 0.9296633 0.2965385 0.9208756 0.2990357 0.9239185 0.2891493 0.9186341 0.2990357 0.9239185 0.3001785 0.9276854 0.2891493 0.9186341 0.3001785 0.9276854 0.2997927 0.931603 0.2911272 0.9387146 0.2997927 0.931603 0.297937 0.9350746 0.2911272 0.9387146 0.2911272 0.9387146 0.2800979 0.9296633 0.2891493 0.9186341 0.2211529 0.7879142 0.2211529 0.785946 0.2264539 0.785946 0.2211529 0.7898825 0.2211529 0.7879142 0.2264539 0.7879142 0.2211529 0.7917751 0.2211529 0.7898825 0.2264539 0.7898825 0.339832 0.937572 0.3380048 0.9383288 0.3321475 0.9383288 0.3380048 0.9383288 0.3360651 0.9387146 0.3321475 0.9383288 0.3360651 0.9387146 0.3340873 0.9387146 0.3321475 0.9383288 0.3321475 0.9383288 0.3303203 0.9375719 0.3286759 0.9364731 0.3286759 0.9364731 0.3272774 0.9350746 0.3261786 0.9334301 0.3261786 0.9334301 0.3254218 0.9316029 0.325036 0.9296632 0.325036 0.9296632 0.325036 0.9276854 0.3254218 0.9257457 0.3254218 0.9257457 0.3261787 0.9239184 0.3303204 0.9197767 0.3261787 0.9239184 0.3272775 0.922274 0.3303204 0.9197767 0.3272775 0.922274 0.3286759 0.9208755 0.3303204 0.9197767 0.3303204 0.9197767 0.3321476 0.9190199 0.3340874 0.9186341 0.3340874 0.9186341 0.3360651 0.9186341 0.3380049 0.9190199 0.3380049 0.9190199 0.3398321 0.9197768 0.3439738 0.9239186 0.3398321 0.9197768 0.3414766 0.9208756 0.3439738 0.9239186 0.3414766 0.9208756 0.3428751 0.9222741 0.3439738 0.9239186 0.3439738 0.9239186 0.3447307 0.9257457 0.3451165 0.9276855 0.3451165 0.9276855 0.3451165 0.9296633 0.3447306 0.931603 0.3447306 0.931603 0.3439738 0.9334303 0.342875 0.9350746 0.342875 0.9350746 0.3414765 0.9364731 0.3447306 0.931603 0.3414765 0.9364731 0.339832 0.937572 0.3447306 0.931603 0.3321475 0.9383288 0.3286759 0.9364731 0.339832 0.937572 0.3286759 0.9364731 0.3261786 0.9334301 0.339832 0.937572 0.3261786 0.9334301 0.325036 0.9296632 0.3303204 0.9197767 0.325036 0.9296632 0.3254218 0.9257457 0.3303204 0.9197767 0.3303204 0.9197767 0.3340874 0.9186341 0.3439738 0.9239186 0.3340874 0.9186341 0.3380049 0.9190199 0.3439738 0.9239186 0.3439738 0.9239186 0.3451165 0.9276855 0.3447306 0.931603 0.3439738 0.9239186 0.3447306 0.931603 0.3303204 0.9197767 0.3447306 0.931603 0.339832 0.937572 0.3303204 0.9197767 0.2211529 0.7935193 0.2211529 0.7917751 0.2264539 0.7917751 0.2211529 0.7950481 0.2211529 0.7935193 0.2264539 0.7935193 0.2211529 0.8214344 0.2211529 0.8199056 0.2264539 0.8199056 0.2211529 0.8231787 0.2211529 0.8214344 0.2264539 0.8214344 0.2211529 0.8250712 0.2211529 0.8231787 0.2264539 0.8231787 0.2211529 0.8270395 0.2211529 0.8250712 0.2264539 0.8250712 0.2211529 0.8290078 0.2211529 0.8270395 0.2264539 0.8270395 0.2211529 0.8309003 0.2211529 0.8290078 0.2264539 0.8290078 0.2211529 0.8326445 0.2211529 0.8309003 0.2264539 0.8309003 0.2211529 0.8341734 0.2211529 0.8326445 0.2264539 0.8326445 0.9510146 0.8200913 0.9510146 0.8185383 0.9563157 0.8185383 0.9510146 0.8218535 0.9510146 0.8200913 0.9563157 0.8200913 0.9510146 0.8237569 0.9510146 0.8218535 0.9563157 0.8218535 0.9510146 0.8257287 0.9510146 0.8237569 0.9563157 0.8237569 0.9510146 0.8276927 0.9510146 0.8257287 0.9563157 0.8257287 0.9510146 0.8295737 0.9510146 0.8276927 0.9563157 0.8276927 0.9510146 0.8312993 0.9510146 0.8295737 0.9563157 0.8295737 0.9510146 0.8328033 0.9510146 0.8312993 0.9563157 0.8312993 0.9342217 0.05889558 0.9342217 0.05736678 0.9395228 0.05736678 0.9342217 0.06063985 0.9342217 0.05889558 0.9395228 0.05889558 0.9342217 0.06253242 0.9342217 0.06063985 0.9395228 0.06063985 0.9342217 0.06450068 0.9342217 0.06253242 0.9395228 0.06253242 0.9342217 0.06646889 0.9342217 0.06450068 0.9395228 0.06450068 0.9342217 0.06836152 0.9342217 0.06646889 0.9395228 0.06646889 0.9342217 0.07010573 0.9342217 0.06836152 0.9395228 0.06836152 0.9342217 0.07163459 0.9342217 0.07010573 0.9395228 0.07010573 0.2211529 0.7823092 0.2211529 0.7807803 0.2264539 0.7807803 0.2211529 0.7840534 0.2211529 0.7823092 0.2264539 0.7823092 0.2211529 0.785946 0.2211529 0.7840534 0.2264539 0.7840534 0.7748915 0.2454419 0.7851052 0.2454419 0.7851052 0.4522329 0.7851052 0.2454419 0.7952206 0.2454419 0.7952206 0.4522329 0.7952206 0.2454419 0.8051401 0.2454419 0.8051401 0.4522329 0.8051401 0.2454419 0.8147684 0.2454419 0.8147684 0.4522329 0.8147684 0.2454419 0.8240126 0.2454419 0.8240126 0.4522329 0.8240126 0.2454419 0.8327838 0.2454419 0.8327838 0.4522329 0.8327838 0.2454419 0.8409974 0.2454419 0.8409974 0.4522329 0.8409974 0.2454419 0.8485744 0.2454419 0.8485744 0.4522329 0.7461242 0.5477672 0.7537012 0.5477672 0.7537012 0.7545582 0.7537012 0.5477672 0.7619149 0.5477672 0.7619149 0.7545582 0.7619149 0.5477672 0.770686 0.5477672 0.770686 0.7545582 0.770686 0.5477672 0.7799302 0.5477672 0.7799302 0.7545582 0.7799302 0.5477672 0.7895585 0.5477672 0.7895585 0.7545582 0.7895585 0.5477672 0.7994781 0.5477672 0.7994781 0.7545582 0.7994781 0.5477672 0.8095934 0.5477672 0.8095934 0.7545582 0.8095934 0.5477672 0.8198071 0.5477672 0.8198071 0.7545582 0.8198071 0.5477672 0.8300208 0.5477672 0.8300208 0.7545582 0.8300208 0.5477672 0.8401362 0.5477672 0.8401362 0.7545582 0.8401362 0.5477672 0.8500557 0.5477672 0.8500557 0.7545582 0.8500557 0.5477672 0.859684 0.5477672 0.859684 0.7545582 0.859684 0.5477672 0.8689282 0.5477672 0.8689282 0.7545582 0.8689282 0.5477672 0.8776994 0.5477672 0.8776994 0.7545582 0.8776994 0.5477672 0.885913 0.5477672 0.885913 0.7545582 0.885913 0.5477672 0.89349 0.5477672 0.89349 0.7545582 0.0124287 0.7807803 0.0198698 0.7807803 0.0198698 0.9875713 0.0198698 0.7807803 0.0279625 0.7807803 0.0279625 0.9875713 0.0279625 0.7807803 0.03662902 0.7807803 0.03662902 0.9875713 0.03662902 0.7807803 0.04578584 0.7807803 0.04578584 0.9875713 0.04578584 0.7807803 0.05534482 0.7807803 0.05534482 0.9875713 0.05534482 0.7807803 0.06521379 0.7807803 0.06521379 0.9875713 0.06521379 0.7807803 0.07529783 0.7807803 0.07529783 0.9875713 0.07529783 0.7807803 0.08549976 0.7807803 0.08549976 0.9875713 0.08549976 0.7807803 0.09572136 0.7807803 0.09572136 0.9875713 0.09572136 0.7807803 0.1058641 0.7807803 0.1058641 0.9875713 0.1058641 0.7807803 0.1158305 0.7807803 0.1158305 0.9875713 0.1158305 0.7807803 0.1255244 0.7807803 0.1255244 0.9875713 0.1255244 0.7807803 0.1348524 0.7807803 0.1348524 0.9875713 0.1348524 0.7807803 0.1437249 0.7807803 0.1437249 0.9875713 0.1437249 0.7807803 0.1520562 0.7807803 0.1520562 0.9875713 0.1520562 0.7807803 0.1597662 0.7807803 0.1597662 0.9875713 0.7461242 0.7794157 0.7537012 0.7794157 0.7537012 0.9862067 0.7537012 0.7794157 0.7619149 0.7794157 0.7619149 0.9862067 0.7619149 0.7794157 0.770686 0.7794157 0.770686 0.9862067 0.770686 0.7794157 0.7799302 0.7794157 0.7799302 0.9862067 0.7799302 0.7794157 0.7895585 0.7794157 0.7895585 0.9862067 0.7895585 0.7794157 0.7994781 0.7794157 0.7994781 0.9862067 0.7994781 0.7794157 0.8095934 0.7794157 0.8095934 0.9862067 0.8095934 0.7794157 0.8198071 0.7794157 0.8198071 0.9862067 0.8198071 0.7794157 0.8300208 0.7794157 0.8300208 0.9862067 0.8300208 0.7794157 0.8401362 0.7794157 0.8401362 0.9862067 0.8401362 0.7794157 0.8500557 0.7794157 0.8500557 0.9862067 0.8500557 0.7794157 0.859684 0.7794157 0.859684 0.9862067 0.859684 0.7794157 0.8689282 0.7794157 0.8689282 0.9862067 0.8689282 0.7794157 0.8776994 0.7794157 0.8776994 0.9862067 0.8776994 0.7794157 0.885913 0.7794157 0.885913 0.9862067 0.885913 0.7794157 0.89349 0.7794157 0.89349 0.9862067 0.7012087 0.2454419 0.7087856 0.2454419 0.7087856 0.4522329 0.7087856 0.2454419 0.7169992 0.2454419 0.7169992 0.4522329 0.7169992 0.2454419 0.7257704 0.2454419 0.7257704 0.4522329 0.7257704 0.2454419 0.7350146 0.2454419 0.7350146 0.4522329 0.7350146 0.2454419 0.7446429 0.2454419 0.7446429 0.4522329 0.7446429 0.2454419 0.7545624 0.2454419 0.7545624 0.4522329 0.219582 0.6365553 0.2205843 0.646732 0.2205843 0.6569581 0.2205843 0.6569581 0.219582 0.6671349 0.219582 0.6365553 0.219582 0.6671349 0.217587 0.6771644 0.219582 0.6365553 0.217587 0.6771644 0.2146185 0.6869501 0.2107052 0.6963977 0.2107052 0.6963977 0.2058847 0.7054163 0.2002034 0.7139189 0.2002034 0.7139189 0.1937161 0.7218237 0.1864852 0.7290546 0.1864852 0.7290546 0.1785804 0.7355419 0.1700777 0.7412232 0.1700777 0.7412232 0.1610592 0.7460438 0.1516115 0.749957 0.1516115 0.749957 0.1418258 0.7529255 0.1317963 0.7549205 0.1317963 0.7549205 0.1216195 0.7559228 0.1113935 0.7559228 0.1113935 0.7559228 0.1012167 0.7549205 0.1317963 0.7549205 0.1012167 0.7549205 0.09118711 0.7529255 0.1317963 0.7549205 0.09118711 0.7529255 0.08140146 0.749957 0.07195383 0.7460437 0.07195383 0.7460437 0.06293529 0.7412232 0.05443263 0.7355419 0.05443263 0.7355419 0.0465278 0.7290546 0.03929692 0.7218236 0.03929692 0.7218236 0.03280961 0.7139188 0.02712833 0.7054162 0.02712833 0.7054162 0.02230781 0.6963976 0.01839447 0.68695 0.01839447 0.68695 0.01542603 0.6771643 0.01343107 0.6671348 0.01343107 0.6671348 0.0124287 0.656958 0.01542603 0.6265257 0.0124287 0.656958 0.0124287 0.6467319 0.01542603 0.6265257 0.0124287 0.6467319 0.01343107 0.6365551 0.01542603 0.6265257 0.01542603 0.6265257 0.01839452 0.6167399 0.02230787 0.6072923 0.02230787 0.6072923 0.02712839 0.5982738 0.03280967 0.5897711 0.03280967 0.5897711 0.03929698 0.5818663 0.04652786 0.5746354 0.04652786 0.5746354 0.05443269 0.5681481 0.06293535 0.5624668 0.06293535 0.5624668 0.07195389 0.5576463 0.08140152 0.553733 0.08140152 0.553733 0.09118723 0.5507645 0.1012168 0.5487695 0.1012168 0.5487695 0.1113936 0.5477672 0.1216196 0.5477672 0.1216196 0.5477672 0.1317964 0.5487695 0.1012168 0.5487695 0.1317964 0.5487695 0.1418259 0.5507646 0.1012168 0.5487695 0.1418259 0.5507646 0.1516116 0.553733 0.1610592 0.5576463 0.1610592 0.5576463 0.1700778 0.5624669 0.1785804 0.5681481 0.1785804 0.5681481 0.1864852 0.5746355 0.1937161 0.5818664 0.1937161 0.5818664 0.2002034 0.5897712 0.2058847 0.5982738 0.2058847 0.5982738 0.2107052 0.6072924 0.2146186 0.61674 0.2146186 0.61674 0.217587 0.6265257 0.219582 0.6365553 0.217587 0.6771644 0.2107052 0.6963977 0.2002034 0.7139189 0.2002034 0.7139189 0.1864852 0.7290546 0.1700777 0.7412232 0.1700777 0.7412232 0.1516115 0.749957 0.1317963 0.7549205 0.09118711 0.7529255 0.07195383 0.7460437 0.05443263 0.7355419 0.05443263 0.7355419 0.03929692 0.7218236 0.02712833 0.7054162 0.02712833 0.7054162 0.01839447 0.68695 0.01343107 0.6671348 0.01542603 0.6265257 0.02230787 0.6072923 0.03280967 0.5897711 0.03280967 0.5897711 0.04652786 0.5746354 0.06293535 0.5624668 0.06293535 0.5624668 0.08140152 0.553733 0.1012168 0.5487695 0.1418259 0.5507646 0.1610592 0.5576463 0.1785804 0.5681481 0.1785804 0.5681481 0.1937161 0.5818664 0.2058847 0.5982738 0.2058847 0.5982738 0.2146186 0.61674 0.219582 0.6365553 0.219582 0.6365553 0.217587 0.6771644 0.2002034 0.7139189 0.2002034 0.7139189 0.1700777 0.7412232 0.1317963 0.7549205 0.1317963 0.7549205 0.09118711 0.7529255 0.05443263 0.7355419 0.05443263 0.7355419 0.02712833 0.7054162 0.01343107 0.6671348 0.01343107 0.6671348 0.01542603 0.6265257 0.03280967 0.5897711 0.03280967 0.5897711 0.06293535 0.5624668 0.1012168 0.5487695 0.1012168 0.5487695 0.1418259 0.5507646 0.1785804 0.5681481 0.1785804 0.5681481 0.2058847 0.5982738 0.219582 0.6365553 0.219582 0.6365553 0.2002034 0.7139189 0.1317963 0.7549205 0.1317963 0.7549205 0.05443263 0.7355419 0.219582 0.6365553 0.05443263 0.7355419 0.01343107 0.6671348 0.219582 0.6365553 0.01343107 0.6671348 0.03280967 0.5897711 0.1012168 0.5487695 0.1012168 0.5487695 0.1785804 0.5681481 0.01343107 0.6671348 0.7545624 0.2454419 0.7646778 0.2454419 0.7646778 0.4522329 0.7646778 0.2454419 0.7748915 0.2454419 0.7748915 0.4522329 0.4882536 0.646732 0.4882536 0.6569581 0.4872512 0.6671348 0.4872512 0.6671348 0.4852563 0.6771644 0.4822878 0.6869501 0.4822878 0.6869501 0.4783744 0.6963977 0.4735539 0.7054163 0.4735539 0.7054163 0.4678726 0.7139189 0.4822878 0.6869501 0.4678726 0.7139189 0.4613853 0.7218237 0.4822878 0.6869501 0.4613853 0.7218237 0.4541544 0.7290546 0.4462496 0.7355419 0.4462496 0.7355419 0.437747 0.7412232 0.4613853 0.7218237 0.437747 0.7412232 0.4287284 0.7460437 0.4613853 0.7218237 0.4287284 0.7460437 0.4192808 0.749957 0.3892887 0.7559228 0.4192808 0.749957 0.4094951 0.7529255 0.3892887 0.7559228 0.4094951 0.7529255 0.3994655 0.7549205 0.3892887 0.7559228 0.3892887 0.7559228 0.3790627 0.7559228 0.3688859 0.7549205 0.3688859 0.7549205 0.3588564 0.7529255 0.3490707 0.749957 0.3490707 0.749957 0.3396231 0.7460437 0.3306045 0.7412232 0.3306045 0.7412232 0.3221019 0.7355419 0.3490707 0.749957 0.3221019 0.7355419 0.3141971 0.7290545 0.3490707 0.749957 0.3141971 0.7290545 0.3069662 0.7218236 0.3004789 0.7139188 0.3004789 0.7139188 0.2947976 0.7054162 0.3141971 0.7290545 0.2947976 0.7054162 0.2899771 0.6963976 0.3141971 0.7290545 0.2899771 0.6963976 0.2860637 0.68695 0.280098 0.656958 0.2860637 0.68695 0.2830953 0.6771643 0.280098 0.656958 0.2830953 0.6771643 0.2811003 0.6671348 0.280098 0.656958 0.280098 0.656958 0.280098 0.6467319 0.2811003 0.6365551 0.2811003 0.6365551 0.2830953 0.6265257 0.2860638 0.6167399 0.2860638 0.6167399 0.2899771 0.6072923 0.2947976 0.5982738 0.2947976 0.5982738 0.3004789 0.5897711 0.2860638 0.6167399 0.3004789 0.5897711 0.3069663 0.5818663 0.2860638 0.6167399 0.3069663 0.5818663 0.3141971 0.5746354 0.322102 0.5681481 0.322102 0.5681481 0.3306046 0.5624668 0.3069663 0.5818663 0.3306046 0.5624668 0.3396232 0.5576463 0.3069663 0.5818663 0.3396232 0.5576463 0.3490708 0.553733 0.3790628 0.5477672 0.3490708 0.553733 0.3588565 0.5507645 0.3790628 0.5477672 0.3588565 0.5507645 0.368886 0.5487695 0.3790628 0.5477672 0.3790628 0.5477672 0.3892889 0.5477672 0.3994656 0.5487695 0.3994656 0.5487695 0.4094952 0.5507646 0.4192809 0.553733 0.4192809 0.553733 0.4287285 0.5576463 0.437747 0.5624669 0.437747 0.5624669 0.4462497 0.5681481 0.4192809 0.553733 0.4462497 0.5681481 0.4541545 0.5746355 0.4192809 0.553733 0.4541545 0.5746355 0.4613854 0.5818664 0.4678727 0.5897712 0.4678727 0.5897712 0.473554 0.5982738 0.4541545 0.5746355 0.473554 0.5982738 0.4783745 0.6072924 0.4541545 0.5746355 0.4783745 0.6072924 0.4822878 0.61674 0.4882536 0.646732 0.4822878 0.61674 0.4852563 0.6265257 0.4882536 0.646732 0.4852563 0.6265257 0.4872513 0.6365553 0.4882536 0.646732 0.4882536 0.646732 0.4872512 0.6671348 0.4613853 0.7218237 0.4872512 0.6671348 0.4822878 0.6869501 0.4613853 0.7218237 0.3892887 0.7559228 0.3688859 0.7549205 0.3141971 0.7290545 0.3688859 0.7549205 0.3490707 0.749957 0.3141971 0.7290545 0.280098 0.656958 0.2811003 0.6365551 0.3069663 0.5818663 0.2811003 0.6365551 0.2860638 0.6167399 0.3069663 0.5818663 0.3790628 0.5477672 0.3994656 0.5487695 0.4541545 0.5746355 0.3994656 0.5487695 0.4192809 0.553733 0.4541545 0.5746355 0.4613853 0.7218237 0.4287284 0.7460437 0.3892887 0.7559228 0.3141971 0.7290545 0.2899771 0.6963976 0.280098 0.656958 0.3069663 0.5818663 0.3396232 0.5576463 0.3790628 0.5477672 0.4541545 0.5746355 0.4783745 0.6072924 0.4882536 0.646732 0.4882536 0.646732 0.4613853 0.7218237 0.3892887 0.7559228 0.3892887 0.7559228 0.3141971 0.7290545 0.280098 0.656958 0.280098 0.656958 0.3069663 0.5818663 0.3790628 0.5477672 0.3790628 0.5477672 0.4541545 0.5746355 0.4882536 0.646732 0.4882536 0.646732 0.3892887 0.7559228 0.280098 0.656958 0.4829704 0.9276854 0.4829704 0.9296632 0.4807289 0.9350746 0.4829704 0.9296632 0.4825845 0.931603 0.4807289 0.9350746 0.4825845 0.931603 0.4818277 0.9334303 0.4807289 0.9350746 0.4807289 0.9350746 0.4793304 0.9364731 0.473919 0.9387146 0.4793304 0.9364731 0.477686 0.937572 0.473919 0.9387146 0.477686 0.937572 0.4758588 0.9383288 0.473919 0.9387146 0.473919 0.9387146 0.4719413 0.9387146 0.4665299 0.9364732 0.4719413 0.9387146 0.4700015 0.9383288 0.4665299 0.9364732 0.4700015 0.9383288 0.4681743 0.937572 0.4665299 0.9364732 0.4665299 0.9364732 0.4651314 0.9350748 0.4640325 0.9334303 0.4640325 0.9334303 0.4632756 0.9316031 0.4628898 0.9296634 0.4628898 0.9296634 0.4628898 0.9276856 0.4651312 0.9222741 0.4628898 0.9276856 0.4632757 0.9257458 0.4651312 0.9222741 0.4632757 0.9257458 0.4640325 0.9239186 0.4651312 0.9222741 0.4651312 0.9222741 0.4665297 0.9208756 0.4681742 0.9197769 0.4681742 0.9197769 0.4700014 0.91902 0.4651312 0.9222741 0.4700014 0.91902 0.4719411 0.9186341 0.4651312 0.9222741 0.4719411 0.9186341 0.4739189 0.9186341 0.4758586 0.9190199 0.4758586 0.9190199 0.4776859 0.9197768 0.4719411 0.9186341 0.4776859 0.9197768 0.4793303 0.9208756 0.4719411 0.9186341 0.4793303 0.9208756 0.4807288 0.9222741 0.4818276 0.9239185 0.4818276 0.9239185 0.4825845 0.9257457 0.4793303 0.9208756 0.4825845 0.9257457 0.4829704 0.9276854 0.4793303 0.9208756 0.4665299 0.9364732 0.4640325 0.9334303 0.473919 0.9387146 0.4640325 0.9334303 0.4628898 0.9296634 0.473919 0.9387146 0.4829704 0.9276854 0.4807289 0.9350746 0.4628898 0.9296634 0.4807289 0.9350746 0.473919 0.9387146 0.4628898 0.9296634 0.4628898 0.9296634 0.4651312 0.9222741 0.4829704 0.9276854 0.4651312 0.9222741 0.4719411 0.9186341 0.4829704 0.9276854 0.9342218 0.103626 0.9342218 0.1016577 0.9395228 0.1016577 0.9342218 0.1055942 0.9342218 0.103626 0.9395228 0.103626 0.9342218 0.1074868 0.9342218 0.1055942 0.9395228 0.1055942 0.5275226 0.9257457 0.5279084 0.9276854 0.5279084 0.9296633 0.5279084 0.9296633 0.5275226 0.931603 0.5267658 0.9334302 0.5267658 0.9334302 0.525667 0.9350746 0.5242685 0.9364731 0.5242685 0.9364731 0.522624 0.937572 0.5207968 0.9383288 0.5207968 0.9383288 0.5188571 0.9387147 0.5168793 0.9387147 0.5168793 0.9387147 0.5149396 0.9383289 0.5131124 0.937572 0.5131124 0.937572 0.5114679 0.9364733 0.5100694 0.9350748 0.5100694 0.9350748 0.5089706 0.9334303 0.5131124 0.937572 0.5089706 0.9334303 0.5082137 0.9316031 0.5131124 0.937572 0.5082137 0.9316031 0.5078279 0.9296634 0.5078279 0.9276856 0.5078279 0.9276856 0.5082137 0.9257458 0.5089706 0.9239186 0.5089706 0.9239186 0.5100693 0.9222742 0.5149395 0.91902 0.5100693 0.9222742 0.5114678 0.9208757 0.5149395 0.91902 0.5114678 0.9208757 0.5131123 0.9197769 0.5149395 0.91902 0.5149395 0.91902 0.5168792 0.9186341 0.518857 0.9186341 0.518857 0.9186341 0.5207967 0.9190199 0.522624 0.9197768 0.522624 0.9197768 0.5242684 0.9208756 0.5275226 0.9257457 0.5242684 0.9208756 0.5256669 0.9222741 0.5275226 0.9257457 0.5256669 0.9222741 0.5267657 0.9239185 0.5275226 0.9257457 0.5275226 0.9257457 0.5279084 0.9296633 0.5207968 0.9383288 0.5279084 0.9296633 0.5267658 0.9334302 0.5207968 0.9383288 0.5267658 0.9334302 0.5242685 0.9364731 0.5207968 0.9383288 0.5207968 0.9383288 0.5168793 0.9387147 0.5131124 0.937572 0.5082137 0.9316031 0.5078279 0.9276856 0.5149395 0.91902 0.5078279 0.9276856 0.5089706 0.9239186 0.5149395 0.91902 0.5149395 0.91902 0.518857 0.9186341 0.5275226 0.9257457 0.518857 0.9186341 0.522624 0.9197768 0.5275226 0.9257457 0.5207968 0.9383288 0.5131124 0.937572 0.5275226 0.9257457 0.5131124 0.937572 0.5082137 0.9316031 0.5275226 0.9257457 0.9342218 0.109231 0.9342218 0.1074868 0.9395228 0.1074868 0.9342218 0.1107599 0.9342218 0.109231 0.9395228 0.109231 0.9504621 0.4786192 0.9504621 0.4770904 0.9557631 0.4770904 0.9504621 0.4803634 0.9504621 0.4786192 0.9557631 0.4786192 0.9504621 0.4822561 0.9504621 0.4803634 0.9557631 0.4803634 0.9504621 0.4842243 0.9504621 0.4822561 0.9557631 0.4822561 0.9504621 0.4861925 0.9504621 0.4842243 0.9557631 0.4842243 0.9504621 0.4880851 0.9504621 0.4861925 0.9557631 0.4861925 0.9504621 0.4898293 0.9504621 0.4880851 0.9557631 0.4880851 0.9504621 0.4913582 0.9504621 0.4898293 0.9557631 0.4898293 0.9510147 0.6790419 0.9510147 0.6774888 0.9563158 0.6774888 0.9510147 0.680804 0.9510147 0.6790419 0.9563158 0.6790419 0.9510147 0.6827074 0.9510147 0.680804 0.9563158 0.680804 0.9510147 0.6846791 0.9510147 0.6827074 0.9563158 0.6827074 0.9510147 0.6866432 0.9510147 0.6846791 0.9563158 0.6846791 0.9510147 0.6885243 0.9510147 0.6866432 0.9563158 0.6866432 0.9510147 0.6902498 0.9510147 0.6885243 0.9563158 0.6885243 0.9510147 0.6917538 0.9510147 0.6902498 0.9563158 0.6902498 0.9510147 0.5492961 0.9510147 0.5477672 0.9563158 0.5477672 0.9510147 0.5510403 0.9510147 0.5492961 0.9563158 0.5492961 0.9510147 0.5529329 0.9510147 0.5510403 0.9563158 0.5510403 0.9510147 0.5549011 0.9510147 0.5529329 0.9563158 0.5529329 0.9510147 0.5568693 0.9510147 0.5549011 0.9563158 0.5549011 0.9510147 0.558762 0.9510147 0.5568693 0.9563158 0.5568693 0.9510147 0.5605062 0.9510147 0.558762 0.9563158 0.558762 0.9510147 0.562035 0.9510147 0.5605062 0.9563158 0.5605062 0.9342218 0.09802091 0.9342218 0.09649205 0.9395228 0.09649205 0.9342218 0.09976506 0.9342218 0.09802091 0.9395228 0.09802091 0.9342218 0.1016577 0.9342218 0.09976506 0.9395228 0.09976506 0.901414 0.5138265 0.8980058 0.5124148 0.8949384 0.5103653 0.8949384 0.5103653 0.8923298 0.5077567 0.8902803 0.5046893 0.8902803 0.5046893 0.8888685 0.5012811 0.8881487 0.4976629 0.8881487 0.4976629 0.8881487 0.4939738 0.8902803 0.5046893 0.8881487 0.4939738 0.8888684 0.4903556 0.8902803 0.5046893 0.8888684 0.4903556 0.8902801 0.4869473 0.8923296 0.48388 0.8923296 0.48388 0.8949382 0.4812714 0.8888684 0.4903556 0.8949382 0.4812714 0.8980056 0.4792218 0.8888684 0.4903556 0.8980056 0.4792218 0.9014138 0.4778101 0.905032 0.4770903 0.905032 0.4770903 0.9087212 0.4770903 0.8980056 0.4792218 0.9087212 0.4770903 0.9123393 0.47781 0.8980056 0.4792218 0.9123393 0.47781 0.9157476 0.4792218 0.9234731 0.4869472 0.9157476 0.4792218 0.918815 0.4812713 0.9234731 0.4869472 0.918815 0.4812713 0.9214236 0.4838798 0.9234731 0.4869472 0.9234731 0.4869472 0.9248849 0.4903555 0.9256046 0.4939736 0.9256046 0.4939736 0.9256046 0.4976627 0.9234731 0.4869472 0.9256046 0.4976627 0.9248849 0.5012809 0.9234731 0.4869472 0.9248849 0.5012809 0.9234732 0.5046892 0.9214237 0.5077565 0.9214237 0.5077565 0.9188151 0.5103651 0.9248849 0.5012809 0.9188151 0.5103651 0.9157477 0.5124147 0.9248849 0.5012809 0.9157477 0.5124147 0.9123395 0.5138265 0.9087213 0.5145462 0.9087213 0.5145462 0.9050322 0.5145462 0.901414 0.5138265 0.901414 0.5138265 0.8949384 0.5103653 0.8888684 0.4903556 0.8949384 0.5103653 0.8902803 0.5046893 0.8888684 0.4903556 0.9157477 0.5124147 0.9087213 0.5145462 0.901414 0.5138265 0.8888684 0.4903556 0.8980056 0.4792218 0.901414 0.5138265 0.8980056 0.4792218 0.9123393 0.47781 0.901414 0.5138265 0.9123393 0.47781 0.9234731 0.4869472 0.901414 0.5138265 0.9234731 0.4869472 0.9248849 0.5012809 0.901414 0.5138265 0.8734319 0.4309719 0.8734319 0.4273006 0.8812416 0.4273006 0.8734319 0.4346432 0.8734319 0.4309719 0.8812416 0.4309719 0.8734319 0.4381734 0.8734319 0.4346432 0.8812416 0.4346432 0.7344834 0.5077567 0.7318748 0.5103653 0.721781 0.5145462 0.7318748 0.5103653 0.7288075 0.5124148 0.721781 0.5145462 0.7288075 0.5124148 0.7253992 0.5138266 0.721781 0.5145462 0.721781 0.5145462 0.718092 0.5145462 0.7079982 0.5103651 0.718092 0.5145462 0.7144737 0.5138265 0.7079982 0.5103651 0.7144737 0.5138265 0.7110655 0.5124147 0.7079982 0.5103651 0.7079982 0.5103651 0.7053896 0.5077565 0.7012087 0.4976627 0.7053896 0.5077565 0.7033401 0.5046892 0.7012087 0.4976627 0.7033401 0.5046892 0.7019283 0.501281 0.7012087 0.4976627 0.7012087 0.4976627 0.7012087 0.4939736 0.7019284 0.4903555 0.7019284 0.4903555 0.7033401 0.4869472 0.7053897 0.4838799 0.7053897 0.4838799 0.7079982 0.4812713 0.7110656 0.4792218 0.7110656 0.4792218 0.7144739 0.47781 0.7180921 0.4770904 0.7180921 0.4770904 0.7217812 0.4770904 0.7253994 0.4778101 0.7253994 0.4778101 0.7288076 0.4792218 0.731875 0.4812715 0.731875 0.4812715 0.7344835 0.48388 0.7365331 0.4869474 0.7365331 0.4869474 0.7379448 0.4903556 0.731875 0.4812715 0.7379448 0.4903556 0.7386645 0.4939738 0.731875 0.4812715 0.7386645 0.4939738 0.7386645 0.4976629 0.7344834 0.5077567 0.7386645 0.4976629 0.7379448 0.5012811 0.7344834 0.5077567 0.7379448 0.5012811 0.736533 0.5046893 0.7344834 0.5077567 0.7012087 0.4976627 0.7019284 0.4903555 0.7053897 0.4838799 0.7053897 0.4838799 0.7110656 0.4792218 0.731875 0.4812715 0.7110656 0.4792218 0.7180921 0.4770904 0.731875 0.4812715 0.7180921 0.4770904 0.7253994 0.4778101 0.731875 0.4812715 0.7344834 0.5077567 0.721781 0.5145462 0.7079982 0.5103651 0.7079982 0.5103651 0.7012087 0.4976627 0.7344834 0.5077567 0.7012087 0.4976627 0.7053897 0.4838799 0.7344834 0.5077567 0.731875 0.4812715 0.7386645 0.4939738 0.7344834 0.5077567 0.8734319 0.4414269 0.8734319 0.4381734 0.8812416 0.4381734 0.8734319 0.4442786 0.8734319 0.4414269 0.8812416 0.4414269 0.9183475 0.5506189 0.9183475 0.5477672 0.9261572 0.5477672 0.9183475 0.5538724 0.9183475 0.5506189 0.9261572 0.5506189 0.9183475 0.5574026 0.9183475 0.5538724 0.9261572 0.5538724 0.9183475 0.5610739 0.9183475 0.5574026 0.9261572 0.5574026 0.9183475 0.5647452 0.9183475 0.5610739 0.9261572 0.5610739 0.9183475 0.5682754 0.9183475 0.5647452 0.9261572 0.5647452 0.9183475 0.5715289 0.9183475 0.5682754 0.9261572 0.5682754 0.9183475 0.5743806 0.9183475 0.5715289 0.9261572 0.5715289 0.6980601 0.908304 0.6980601 0.905407 0.7058699 0.905407 0.6980601 0.9115909 0.6980601 0.908304 0.7058699 0.908304 0.6980601 0.9151414 0.6980601 0.9115909 0.7058699 0.9115909 0.6980601 0.9188191 0.6980601 0.9151414 0.7058699 0.9151414 0.6980601 0.9224826 0.6980601 0.9188191 0.7058699 0.9188191 0.6980601 0.9259912 0.6980601 0.9224826 0.7058699 0.9224826 0.6980601 0.92921 0.6980601 0.9259912 0.7058699 0.9259912 0.6980601 0.9320154 0.6980601 0.92921 0.7058699 0.92921 0.9183475 0.6020898 0.9183475 0.5992382 0.9261572 0.5992382 0.9183475 0.6053434 0.9183475 0.6020898 0.9261572 0.6020898 0.9183475 0.6088736 0.9183475 0.6053434 0.9261572 0.6053434 0.9183475 0.6125448 0.9183475 0.6088736 0.9261572 0.6088736 0.9183475 0.6162161 0.9183475 0.6125448 0.9261572 0.6125448 0.9183475 0.6197464 0.9183475 0.6162161 0.9261572 0.6162161 0.9183475 0.6229999 0.9183475 0.6197464 0.9261572 0.6197464 0.9183475 0.6258516 0.9183475 0.6229999 0.9261572 0.6229999 0.8734319 0.4205169 0.8734319 0.4176651 0.8812416 0.4176651 0.8734319 0.4237704 0.8734319 0.4205169 0.8812416 0.4205169 0.8734319 0.4273006 0.8734319 0.4237704 0.8812416 0.4237704 0.9543022 0.02148008 0.9543022 0.02345782 0.9539164 0.02539759 0.9539164 0.02539759 0.9531595 0.02722477 0.9520608 0.02886927 0.9520608 0.02886927 0.9506623 0.03026777 0.9490178 0.03136658 0.9490178 0.03136658 0.9471907 0.03212338 0.9520608 0.02886927 0.9471907 0.03212338 0.9452509 0.03250926 0.9520608 0.02886927 0.9452509 0.03250926 0.9432731 0.03250926 0.9413334 0.03212344 0.9413334 0.03212344 0.9395062 0.03136652 0.9452509 0.03250926 0.9395062 0.03136652 0.9378617 0.03026783 0.9452509 0.03250926 0.9378617 0.03026783 0.9364632 0.02886933 0.9342217 0.02345788 0.9364632 0.02886933 0.9353644 0.02722483 0.9342217 0.02345788 0.9353644 0.02722483 0.9346075 0.02539765 0.9342217 0.02345788 0.9342217 0.02345788 0.9342217 0.02148014 0.9364632 0.01606869 0.9342217 0.02148014 0.9346075 0.01954036 0.9364632 0.01606869 0.9346075 0.01954036 0.9353644 0.01771312 0.9364632 0.01606869 0.9364632 0.01606869 0.9378616 0.01467025 0.9395061 0.01357144 0.9395061 0.01357144 0.9413333 0.01281452 0.943273 0.0124287 0.943273 0.0124287 0.9452508 0.01242876 0.9471905 0.01281458 0.9471905 0.01281458 0.9490178 0.01357138 0.9506623 0.01467019 0.9506623 0.01467019 0.9520607 0.01606869 0.9543022 0.02148008 0.9520607 0.01606869 0.9531595 0.01771306 0.9543022 0.02148008 0.9531595 0.01771306 0.9539164 0.0195403 0.9543022 0.02148008 0.9543022 0.02148008 0.9539164 0.02539759 0.9452509 0.03250926 0.9539164 0.02539759 0.9520608 0.02886927 0.9452509 0.03250926 0.9364632 0.01606869 0.9395061 0.01357144 0.9342217 0.02345788 0.9395061 0.01357144 0.943273 0.0124287 0.9342217 0.02345788 0.943273 0.0124287 0.9471905 0.01281458 0.9543022 0.02148008 0.9471905 0.01281458 0.9506623 0.01467019 0.9543022 0.02148008 0.9452509 0.03250926 0.9378617 0.03026783 0.9342217 0.02345788 0.9543022 0.02148008 0.9452509 0.03250926 0.9342217 0.02345788 0.9342217 0.1427512 0.9342217 0.140783 0.9395228 0.140783 0.9342217 0.1447195 0.9342217 0.1427512 0.9395228 0.1427512 0.9342217 0.1466121 0.9342217 0.1447195 0.9395228 0.1447195 0.9194902 0.9486246 0.9187333 0.9467973 0.9183475 0.9448576 0.9183475 0.9448576 0.9183475 0.9428798 0.9187333 0.9409401 0.9187333 0.9409401 0.9194902 0.9391129 0.920589 0.9374684 0.920589 0.9374684 0.9219874 0.9360699 0.9236319 0.9349712 0.9236319 0.9349712 0.9254592 0.9342143 0.9273989 0.9338285 0.9273989 0.9338285 0.9293767 0.9338285 0.9313164 0.9342143 0.9313164 0.9342143 0.9331436 0.9349712 0.9372853 0.9391129 0.9331436 0.9349712 0.9347881 0.93607 0.9372853 0.9391129 0.9347881 0.93607 0.9361865 0.9374685 0.9372853 0.9391129 0.9372853 0.9391129 0.9380422 0.9409401 0.938428 0.9428799 0.938428 0.9428799 0.938428 0.9448576 0.9380422 0.9467974 0.9380422 0.9467974 0.9372853 0.9486246 0.9331435 0.9527663 0.9372853 0.9486246 0.9361865 0.9502691 0.9331435 0.9527663 0.9361865 0.9502691 0.934788 0.9516676 0.9331435 0.9527663 0.9331435 0.9527663 0.9313164 0.9535232 0.9293766 0.953909 0.9293766 0.953909 0.9273989 0.953909 0.925459 0.9535231 0.925459 0.9535231 0.9236319 0.9527663 0.9219874 0.9516675 0.9219874 0.9516675 0.9205889 0.950269 0.925459 0.9535231 0.9205889 0.950269 0.9194902 0.9486246 0.925459 0.9535231 0.9194902 0.9486246 0.9183475 0.9448576 0.9187333 0.9409401 0.9187333 0.9409401 0.920589 0.9374684 0.9194902 0.9486246 0.920589 0.9374684 0.9236319 0.9349712 0.9194902 0.9486246 0.9236319 0.9349712 0.9273989 0.9338285 0.9372853 0.9391129 0.9273989 0.9338285 0.9313164 0.9342143 0.9372853 0.9391129 0.9372853 0.9391129 0.938428 0.9428799 0.9331435 0.9527663 0.938428 0.9428799 0.9380422 0.9467974 0.9331435 0.9527663 0.9331435 0.9527663 0.9293766 0.953909 0.925459 0.9535231 0.9331435 0.9527663 0.925459 0.9535231 0.9194902 0.9486246 0.9194902 0.9486246 0.9236319 0.9349712 0.9331435 0.9527663 0.9342217 0.1483563 0.9342217 0.1466121 0.9395228 0.1466121 0.9342217 0.1498851 0.9342217 0.1483563 0.9395228 0.1483563 0.9510147 0.600767 0.9510147 0.5992382 0.9563158 0.5992382 0.9510147 0.6025112 0.9510147 0.600767 0.9563158 0.600767 0.9510147 0.6044038 0.9510147 0.6025112 0.9563158 0.6025112 0.9510147 0.606372 0.9510147 0.6044038 0.9563158 0.6044038 0.9510147 0.6083403 0.9510147 0.606372 0.9563158 0.606372 0.9510147 0.6102328 0.9510147 0.6083403 0.9563158 0.6083403 0.9510147 0.6119771 0.9510147 0.6102328 0.9563158 0.6102328 0.9510147 0.6135059 0.9510147 0.6119771 0.9563158 0.6119771 0.9510146 0.7181644 0.9510146 0.7166113 0.9563157 0.7166113 0.9510146 0.7199265 0.9510146 0.7181644 0.9563157 0.7181644 0.9510146 0.72183 0.9510146 0.7199265 0.9563157 0.7199265 0.9510146 0.7238017 0.9510146 0.72183 0.9563157 0.72183 0.9510146 0.7257657 0.9510146 0.7238017 0.9563157 0.7238017 0.9510146 0.7276467 0.9510146 0.7257657 0.9563157 0.7257657 0.9510146 0.7293724 0.9510146 0.7276467 0.9563157 0.7276467 0.9510146 0.7308763 0.9510146 0.7293724 0.9563157 0.7293724 0.9510146 0.6398923 0.9510146 0.6383635 0.9563157 0.6383635 0.9510146 0.6416366 0.9510146 0.6398923 0.9563157 0.6398923 0.9510146 0.6435291 0.9510146 0.6416366 0.9563157 0.6416366 0.9510146 0.6454974 0.9510146 0.6435291 0.9563157 0.6435291 0.9510146 0.6474656 0.9510146 0.6454974 0.9563157 0.6454974 0.9510146 0.6493582 0.9510146 0.6474656 0.9563157 0.6474656 0.9510146 0.6511024 0.9510146 0.6493582 0.9563157 0.6493582 0.9510146 0.6526312 0.9510146 0.6511024 0.9563157 0.6511024 0.9342217 0.1371462 0.9342217 0.1356173 0.9395228 0.1356173 0.9342217 0.1388905 0.9342217 0.1371462 0.9395228 0.1371462 0.9342217 0.140783 0.9342217 0.1388905 0.9395228 0.1388905 0.6786583 0.8798298 0.6752501 0.8784181 0.6721827 0.8763685 0.6721827 0.8763685 0.6695741 0.87376 0.6675245 0.8706926 0.6675245 0.8706926 0.6661127 0.8672844 0.6653931 0.8636662 0.6653931 0.8636662 0.6653931 0.8599771 0.6661127 0.8563589 0.6661127 0.8563589 0.6675245 0.8529507 0.669574 0.8498833 0.669574 0.8498833 0.6721825 0.8472747 0.6752499 0.8452252 0.6752499 0.8452252 0.6786581 0.8438134 0.6895836 0.8438133 0.6786581 0.8438134 0.6822763 0.8430936 0.6895836 0.8438133 0.6822763 0.8430936 0.6859654 0.8430936 0.6895836 0.8438133 0.6895836 0.8438133 0.6929919 0.8452251 0.7007174 0.8529505 0.6929919 0.8452251 0.6960593 0.8472746 0.7007174 0.8529505 0.6960593 0.8472746 0.6986678 0.8498831 0.7007174 0.8529505 0.7007174 0.8529505 0.7021291 0.8563588 0.7021292 0.8672842 0.7021291 0.8563588 0.7028489 0.859977 0.7021292 0.8672842 0.7028489 0.859977 0.7028489 0.8636661 0.7021292 0.8672842 0.7021292 0.8672842 0.7007175 0.8706925 0.698668 0.8737598 0.698668 0.8737598 0.6960594 0.8763685 0.692992 0.878418 0.692992 0.878418 0.6895837 0.8798298 0.6859656 0.8805495 0.6859656 0.8805495 0.6822765 0.8805495 0.6786583 0.8798298 0.6786583 0.8798298 0.6721827 0.8763685 0.6661127 0.8563589 0.6721827 0.8763685 0.6675245 0.8706926 0.6661127 0.8563589 0.6675245 0.8706926 0.6653931 0.8636662 0.6661127 0.8563589 0.6661127 0.8563589 0.669574 0.8498833 0.6895836 0.8438133 0.669574 0.8498833 0.6752499 0.8452252 0.6895836 0.8438133 0.7021292 0.8672842 0.698668 0.8737598 0.6786583 0.8798298 0.698668 0.8737598 0.692992 0.878418 0.6786583 0.8798298 0.692992 0.878418 0.6859656 0.8805495 0.6786583 0.8798298 0.6895836 0.8438133 0.7007174 0.8529505 0.7021292 0.8672842 0.6786583 0.8798298 0.6661127 0.8563589 0.7021292 0.8672842 0.9060992 0.4309719 0.9060992 0.4273005 0.9139088 0.4273005 0.9060992 0.4346432 0.9060992 0.4309719 0.9139088 0.4309719 0.9060992 0.4381734 0.9060992 0.4346432 0.9139088 0.4346432 0.7967967 0.5077567 0.7941882 0.5103653 0.7840943 0.5145462 0.7941882 0.5103653 0.7911208 0.5124148 0.7840943 0.5145462 0.7911208 0.5124148 0.7877125 0.5138266 0.7840943 0.5145462 0.7840943 0.5145462 0.7804053 0.5145462 0.7767871 0.5138265 0.7767871 0.5138265 0.7733789 0.5124148 0.7840943 0.5145462 0.7733789 0.5124148 0.7703115 0.5103652 0.7840943 0.5145462 0.7703115 0.5103652 0.7677029 0.5077566 0.763522 0.4976628 0.7677029 0.5077566 0.7656534 0.5046893 0.763522 0.4976628 0.7656534 0.5046893 0.7642417 0.501281 0.763522 0.4976628 0.763522 0.4976628 0.763522 0.4939737 0.7642418 0.4903555 0.7642418 0.4903555 0.7656535 0.4869472 0.767703 0.4838799 0.767703 0.4838799 0.7703116 0.4812713 0.773379 0.4792218 0.773379 0.4792218 0.7767872 0.47781 0.7804054 0.4770904 0.7804054 0.4770904 0.7840945 0.4770904 0.7877128 0.4778102 0.7877128 0.4778102 0.791121 0.4792219 0.7941883 0.4812715 0.7941883 0.4812715 0.7967969 0.4838801 0.7988464 0.4869474 0.7988464 0.4869474 0.8002581 0.4903556 0.7941883 0.4812715 0.8002581 0.4903556 0.8009778 0.4939739 0.7941883 0.4812715 0.8009778 0.4939739 0.8009778 0.4976629 0.7967967 0.5077567 0.8009778 0.4976629 0.8002581 0.5012812 0.7967967 0.5077567 0.8002581 0.5012812 0.7988464 0.5046894 0.7967967 0.5077567 0.763522 0.4976628 0.7642418 0.4903555 0.7703115 0.5103652 0.7642418 0.4903555 0.767703 0.4838799 0.7703115 0.5103652 0.767703 0.4838799 0.773379 0.4792218 0.7941883 0.4812715 0.773379 0.4792218 0.7804054 0.4770904 0.7941883 0.4812715 0.7804054 0.4770904 0.7877128 0.4778102 0.7941883 0.4812715 0.7967967 0.5077567 0.7840943 0.5145462 0.7703115 0.5103652 0.7941883 0.4812715 0.8009778 0.4939739 0.7967967 0.5077567 0.7967967 0.5077567 0.7703115 0.5103652 0.7941883 0.4812715 0.9060992 0.4414269 0.9060992 0.4381734 0.9139088 0.4381734 0.9060992 0.4442785 0.9060992 0.4414269 0.9139088 0.4414269 0.9183475 0.6535608 0.9183475 0.6507092 0.9261572 0.6507092 0.9183475 0.6568143 0.9183475 0.6535608 0.9261572 0.6535608 0.9183475 0.6603446 0.9183475 0.6568143 0.9261572 0.6568143 0.9183475 0.6640158 0.9183475 0.6603446 0.9261572 0.6603446 0.9183475 0.6676872 0.9183475 0.6640158 0.9261572 0.6640158 0.9183475 0.6712174 0.9183475 0.6676872 0.9261572 0.6676872 0.9183475 0.6744709 0.9183475 0.6712174 0.9261572 0.6712174 0.9183475 0.6773226 0.9183475 0.6744709 0.9261572 0.6744709 0.9268475 0.2998047 0.9268475 0.2969077 0.9346572 0.2969077 0.9268475 0.3030916 0.9268475 0.2998047 0.9346572 0.2998047 0.9268475 0.3066421 0.9268475 0.3030916 0.9346572 0.3030916 0.9268475 0.3103198 0.9268475 0.3066421 0.9346572 0.3066421 0.9268475 0.3139833 0.9268475 0.3103198 0.9346572 0.3103198 0.9268475 0.3174919 0.9268475 0.3139833 0.9346572 0.3139833 0.9268475 0.3207107 0.9268475 0.3174919 0.9346572 0.3174919 0.9268475 0.323516 0.9268475 0.3207107 0.9346572 0.3207107 0.9183474 0.7050318 0.9183474 0.7021801 0.9261572 0.7021801 0.9183474 0.7082853 0.9183474 0.7050318 0.9261572 0.7050318 0.9183474 0.7118155 0.9183474 0.7082853 0.9261572 0.7082853 0.9183474 0.7154868 0.9183474 0.7118155 0.9261572 0.7118155 0.9183474 0.7191581 0.9183474 0.7154868 0.9261572 0.7154868 0.9183474 0.7226883 0.9183474 0.7191581 0.9261572 0.7191581 0.9183474 0.7259418 0.9183474 0.7226883 0.9261572 0.7226883 0.9183474 0.7287935 0.9183474 0.7259418 0.9261572 0.7259418 0.9060992 0.4205168 0.9060992 0.4176651 0.9139088 0.4176651 0.9060992 0.4237703 0.9060992 0.4205168 0.9139088 0.4205168 0.9060992 0.4273005 0.9060992 0.4237703 0.9139088 0.4237703 0.6859654 0.8182361 0.6822763 0.8182361 0.6786581 0.8175165 0.6786581 0.8175165 0.6752499 0.8161047 0.6859654 0.8182361 0.6752499 0.8161047 0.6721825 0.8140552 0.6859654 0.8182361 0.6721825 0.8140552 0.6695739 0.8114466 0.6675244 0.8083792 0.6675244 0.8083792 0.6661126 0.804971 0.6653929 0.8013528 0.6653929 0.8013528 0.6653929 0.7976637 0.6661126 0.7940455 0.6661126 0.7940455 0.6675243 0.7906373 0.6695739 0.7875699 0.6695739 0.7875699 0.6721825 0.7849613 0.6822763 0.7807803 0.6721825 0.7849613 0.6752498 0.7829118 0.6822763 0.7807803 0.6752498 0.7829118 0.6786581 0.7815 0.6822763 0.7807803 0.6822763 0.7807803 0.6859654 0.7807803 0.6960592 0.7849613 0.6859654 0.7807803 0.6895835 0.7815 0.6960592 0.7849613 0.6895835 0.7815 0.6929918 0.7829117 0.6960592 0.7849613 0.6960592 0.7849613 0.6986677 0.7875698 0.7028487 0.7976636 0.6986677 0.7875698 0.7007173 0.7906372 0.7028487 0.7976636 0.7007173 0.7906372 0.702129 0.7940455 0.7028487 0.7976636 0.7028487 0.7976636 0.7028487 0.8013527 0.702129 0.8049709 0.702129 0.8049709 0.7007173 0.8083792 0.6986678 0.8114466 0.6986678 0.8114466 0.6960592 0.8140551 0.6929919 0.8161047 0.6929919 0.8161047 0.6895836 0.8175164 0.6986678 0.8114466 0.6895836 0.8175164 0.6859654 0.8182361 0.6986678 0.8114466 0.6721825 0.8140552 0.6675244 0.8083792 0.6859654 0.8182361 0.6675244 0.8083792 0.6653929 0.8013528 0.6859654 0.8182361 0.6653929 0.8013528 0.6661126 0.7940455 0.6822763 0.7807803 0.6661126 0.7940455 0.6695739 0.7875699 0.6822763 0.7807803 0.7028487 0.7976636 0.702129 0.8049709 0.6859654 0.8182361 0.702129 0.8049709 0.6986678 0.8114466 0.6859654 0.8182361 0.6822763 0.7807803 0.6960592 0.7849613 0.7028487 0.7976636 0.6859654 0.8182361 0.6653929 0.8013528 0.7028487 0.7976636 0.2474307 0.9055204 0.2474307 0.9018491 0.2552404 0.9018491 0.2474307 0.9091917 0.2474307 0.9055204 0.2552404 0.9055204 0.2474307 0.9127219 0.2474307 0.9091917 0.2552404 0.9091917 0.850026 0.5138266 0.8464078 0.5145463 0.8427187 0.5145463 0.8427187 0.5145463 0.8391005 0.5138266 0.8356923 0.5124148 0.8356923 0.5124148 0.8326249 0.5103653 0.8300163 0.5077567 0.8300163 0.5077567 0.8279668 0.5046893 0.826555 0.5012811 0.826555 0.5012811 0.8258354 0.4976629 0.8279668 0.4869474 0.8258354 0.4976629 0.8258353 0.4939738 0.8279668 0.4869474 0.8258353 0.4939738 0.826555 0.4903556 0.8279668 0.4869474 0.8279668 0.4869474 0.8300163 0.48388 0.8326249 0.4812715 0.8326249 0.4812715 0.8356922 0.4792219 0.8391005 0.4778101 0.8391005 0.4778101 0.8427187 0.4770904 0.8464077 0.4770904 0.8464077 0.4770904 0.850026 0.4778101 0.8534342 0.4792218 0.8534342 0.4792218 0.8565016 0.4812714 0.8591102 0.48388 0.8591102 0.48388 0.8611597 0.4869473 0.8534342 0.4792218 0.8611597 0.4869473 0.8625714 0.4903556 0.8534342 0.4792218 0.8625714 0.4903556 0.8632912 0.4939737 0.8632912 0.4976629 0.8632912 0.4976629 0.8625714 0.501281 0.8625714 0.4903556 0.8625714 0.501281 0.8611597 0.5046893 0.8625714 0.4903556 0.8611597 0.5046893 0.8591102 0.5077567 0.850026 0.5138266 0.8591102 0.5077567 0.8565016 0.5103653 0.850026 0.5138266 0.8565016 0.5103653 0.8534343 0.5124148 0.850026 0.5138266 0.850026 0.5138266 0.8427187 0.5145463 0.8356923 0.5124148 0.8356923 0.5124148 0.8300163 0.5077567 0.850026 0.5138266 0.8300163 0.5077567 0.826555 0.5012811 0.850026 0.5138266 0.8279668 0.4869474 0.8326249 0.4812715 0.8391005 0.4778101 0.8391005 0.4778101 0.8464077 0.4770904 0.8625714 0.4903556 0.8464077 0.4770904 0.8534342 0.4792218 0.8625714 0.4903556 0.826555 0.5012811 0.8279668 0.4869474 0.850026 0.5138266 0.8279668 0.4869474 0.8391005 0.4778101 0.850026 0.5138266 0.8625714 0.4903556 0.8611597 0.5046893 0.850026 0.5138266 0.2474307 0.9159754 0.2474307 0.9127219 0.2552404 0.9127219 0.2474307 0.9188271 0.2474307 0.9159754 0.2552404 0.9159754 0.9183474 0.7822674 0.9183474 0.7794157 0.9261572 0.7794157 0.9183474 0.7855209 0.9183474 0.7822674 0.9261572 0.7822674 0.9183474 0.7890511 0.9183474 0.7855209 0.9261572 0.7855209 0.9183474 0.7927224 0.9183474 0.7890511 0.9261572 0.7890511 0.9183475 0.7963938 0.9183474 0.7927224 0.9261572 0.7927224 0.9183475 0.799924 0.9183475 0.7963938 0.9261572 0.7963938 0.9183475 0.8031774 0.9183475 0.799924 0.9261572 0.799924 0.9183475 0.8060292 0.9183475 0.8031774 0.9261572 0.8031774 0.9268475 0.3512705 0.9268475 0.3483735 0.9346572 0.3483735 0.9268475 0.3545575 0.9268475 0.3512705 0.9346572 0.3512705 0.9268475 0.3581079 0.9268475 0.3545575 0.9346572 0.3545575 0.9268475 0.3617857 0.9268475 0.3581079 0.9346572 0.3581079 0.9268475 0.3654492 0.9268475 0.3617857 0.9346572 0.3617857 0.9268475 0.3689578 0.9268475 0.3654492 0.9346572 0.3654492 0.9268475 0.3721766 0.9268475 0.3689578 0.9346572 0.3689578 0.9268475 0.3749819 0.9268475 0.3721766 0.9346572 0.3721766 0.9183475 0.8337383 0.9183475 0.8308867 0.9261572 0.8308867 0.9183475 0.8369919 0.9183475 0.8337383 0.9261572 0.8337383 0.9183475 0.8405221 0.9183475 0.8369919 0.9261572 0.8369919 0.9183475 0.8441934 0.9183475 0.8405221 0.9261572 0.8405221 0.9183475 0.8478647 0.9183475 0.8441934 0.9261572 0.8441934 0.9183475 0.851395 0.9183475 0.8478647 0.9261572 0.8478647 0.9183475 0.8546484 0.9183475 0.851395 0.9261572 0.851395 0.9183475 0.8575001 0.9183475 0.8546484 0.9261572 0.8546484 0.2474307 0.8950654 0.2474307 0.8922137 0.2552404 0.8922137 0.2474307 0.8983189 0.2474307 0.8950654 0.2552404 0.8950654 0.2474307 0.9018491 0.2474307 0.8983189 0.2552404 0.8983189 0.3829429 0.9383288 0.3810032 0.9387146 0.3790253 0.9387146 0.3790253 0.9387146 0.3770856 0.9383288 0.3752584 0.9375719 0.3752584 0.9375719 0.373614 0.9364731 0.3703598 0.931603 0.373614 0.9364731 0.3722155 0.9350746 0.3703598 0.931603 0.3722155 0.9350746 0.3711166 0.9334302 0.3703598 0.931603 0.3703598 0.931603 0.369974 0.9296632 0.3711167 0.9239185 0.369974 0.9296632 0.369974 0.9276854 0.3711167 0.9239185 0.369974 0.9276854 0.3703598 0.9257457 0.3711167 0.9239185 0.3711167 0.9239185 0.3722155 0.922274 0.373614 0.9208756 0.373614 0.9208756 0.3752585 0.9197768 0.3770856 0.9190199 0.3770856 0.9190199 0.3790255 0.9186341 0.3847702 0.9197768 0.3790255 0.9186341 0.3810033 0.9186341 0.3847702 0.9197768 0.3810033 0.9186341 0.382943 0.9190199 0.3847702 0.9197768 0.3847702 0.9197768 0.3864146 0.9208756 0.3878131 0.9222741 0.3878131 0.9222741 0.3889119 0.9239186 0.3847702 0.9197768 0.3889119 0.9239186 0.3896687 0.9257458 0.3847702 0.9197768 0.3896687 0.9257458 0.3900545 0.9276856 0.3900545 0.9296633 0.3900545 0.9296633 0.3896687 0.9316031 0.3896687 0.9257458 0.3896687 0.9316031 0.3889119 0.9334303 0.3896687 0.9257458 0.3889119 0.9334303 0.387813 0.9350747 0.3829429 0.9383288 0.387813 0.9350747 0.3864145 0.9364732 0.3829429 0.9383288 0.3864145 0.9364732 0.3847701 0.937572 0.3829429 0.9383288 0.3829429 0.9383288 0.3790253 0.9387146 0.3703598 0.931603 0.3790253 0.9387146 0.3752584 0.9375719 0.3703598 0.931603 0.3711167 0.9239185 0.373614 0.9208756 0.3703598 0.931603 0.373614 0.9208756 0.3770856 0.9190199 0.3703598 0.931603 0.3770856 0.9190199 0.3847702 0.9197768 0.3829429 0.9383288 0.3847702 0.9197768 0.3896687 0.9257458 0.3829429 0.9383288 0.3896687 0.9257458 0.3889119 0.9334303 0.3829429 0.9383288 0.9342218 0.1818765 0.9342218 0.1799083 0.9395228 0.1799083 0.9342218 0.1838448 0.9342218 0.1818765 0.9395228 0.1818765 0.9342218 0.1857374 0.9342218 0.1838448 0.9395228 0.1838448 0.4327479 0.937572 0.4309206 0.9383288 0.4250633 0.9383288 0.4309206 0.9383288 0.4289808 0.9387146 0.4250633 0.9383288 0.4289808 0.9387146 0.427003 0.9387146 0.4250633 0.9383288 0.4250633 0.9383288 0.4232361 0.9375719 0.4190945 0.9334301 0.4232361 0.9375719 0.4215916 0.9364731 0.4190945 0.9334301 0.4215916 0.9364731 0.4201932 0.9350746 0.4190945 0.9334301 0.4190945 0.9334301 0.4183375 0.931603 0.4179517 0.9296632 0.4179517 0.9296632 0.4179517 0.9276854 0.4183376 0.9257457 0.4183376 0.9257457 0.4190945 0.9239185 0.4201933 0.922274 0.4201933 0.922274 0.4215918 0.9208756 0.4183376 0.9257457 0.4215918 0.9208756 0.4232362 0.9197767 0.4183376 0.9257457 0.4232362 0.9197767 0.4250634 0.9190199 0.4270032 0.9186341 0.4270032 0.9186341 0.428981 0.9186341 0.4309207 0.9190199 0.4309207 0.9190199 0.4327479 0.9197768 0.4368896 0.9239186 0.4327479 0.9197768 0.4343923 0.9208756 0.4368896 0.9239186 0.4343923 0.9208756 0.4357908 0.9222741 0.4368896 0.9239186 0.4368896 0.9239186 0.4376465 0.9257457 0.4380323 0.9276855 0.4380323 0.9276855 0.4380323 0.9296633 0.4376465 0.931603 0.4376465 0.931603 0.4368895 0.9334303 0.4357908 0.9350747 0.4357908 0.9350747 0.4343923 0.9364732 0.4376465 0.931603 0.4343923 0.9364732 0.4327479 0.937572 0.4376465 0.931603 0.4190945 0.9334301 0.4179517 0.9296632 0.4183376 0.9257457 0.4232362 0.9197767 0.4270032 0.9186341 0.4368896 0.9239186 0.4270032 0.9186341 0.4309207 0.9190199 0.4368896 0.9239186 0.4368896 0.9239186 0.4380323 0.9276855 0.4327479 0.937572 0.4380323 0.9276855 0.4376465 0.931603 0.4327479 0.937572 0.4327479 0.937572 0.4250633 0.9383288 0.4190945 0.9334301 0.4190945 0.9334301 0.4183376 0.9257457 0.4232362 0.9197767 0.4327479 0.937572 0.4190945 0.9334301 0.4368896 0.9239186 0.9342218 0.1874816 0.9342218 0.1857374 0.9395228 0.1857374 0.9342218 0.1890105 0.9342218 0.1874816 0.9395228 0.1874816 0.9387664 0.4191939 0.9387664 0.4176651 0.9440674 0.4176651 0.9387664 0.4209381 0.9387664 0.4191939 0.9440674 0.4191939 0.9387664 0.4228308 0.9387664 0.4209381 0.9440674 0.4209381 0.9387664 0.424799 0.9387664 0.4228308 0.9440674 0.4228308 0.9387664 0.4267672 0.9387664 0.424799 0.9440674 0.424799 0.9387664 0.4286598 0.9387664 0.4267672 0.9440674 0.4267672 0.9387664 0.4304041 0.9387664 0.4286598 0.9440674 0.4286598 0.9387664 0.4319329 0.9387664 0.4304041 0.9440674 0.4304041 0.9510147 0.7809689 0.9510147 0.7794158 0.9563158 0.7794158 0.9510147 0.7827311 0.9510147 0.7809689 0.9563158 0.7809689 0.9510147 0.7846345 0.9510147 0.7827311 0.9563158 0.7827311 0.9510147 0.7866061 0.9510147 0.7846345 0.9563158 0.7846345 0.9510147 0.7885702 0.9510147 0.7866061 0.9563158 0.7866061 0.9510147 0.7904513 0.9510147 0.7885702 0.9563158 0.7885702 0.9510147 0.7921769 0.9510147 0.7904513 0.9563158 0.7904513 0.9510147 0.7936809 0.9510147 0.7921769 0.9563158 0.7921769 0.6288638 0.9386191 0.6288638 0.9370902 0.6341648 0.9370902 0.6288638 0.9403633 0.6288638 0.9386191 0.6341648 0.9386191 0.6288638 0.9422559 0.6288638 0.9403633 0.6341648 0.9403633 0.6288638 0.9442241 0.6288638 0.9422559 0.6341648 0.9422559 0.6288638 0.9461924 0.6288638 0.9442241 0.6341648 0.9442241 0.6288638 0.948085 0.6288638 0.9461924 0.6341648 0.9461924 0.6288638 0.9498292 0.6288638 0.948085 0.6341648 0.948085 0.6288638 0.951358 0.6288638 0.9498292 0.6341648 0.9498292 0.9342218 0.1762715 0.9342218 0.1747426 0.9395228 0.1747426 0.9342218 0.1780157 0.9342218 0.1762715 0.9395228 0.1762715 0.9342218 0.1799083 0.9342218 0.1780157 0.9395228 0.1780157 0.2213599 0.9098253 0.2199481 0.9132335 0.2178986 0.9163009 0.2178986 0.9163009 0.21529 0.9189094 0.2213599 0.9098253 0.21529 0.9189094 0.2122226 0.920959 0.2213599 0.9098253 0.2122226 0.920959 0.2088143 0.9223708 0.2051962 0.9230905 0.2051962 0.9230905 0.2015071 0.9230905 0.1978889 0.9223708 0.1978889 0.9223708 0.1944806 0.9209591 0.1914132 0.9189095 0.1914132 0.9189095 0.1888047 0.9163009 0.1978889 0.9223708 0.1888047 0.9163009 0.1867551 0.9132336 0.1978889 0.9223708 0.1867551 0.9132336 0.1853434 0.9098253 0.1846237 0.9062071 0.1846237 0.9062071 0.1846237 0.902518 0.1853434 0.8988998 0.1853434 0.8988998 0.1867551 0.8954916 0.1944806 0.8877661 0.1867551 0.8954916 0.1888047 0.8924242 0.1944806 0.8877661 0.1888047 0.8924242 0.1914132 0.8898156 0.1944806 0.8877661 0.1944806 0.8877661 0.1978889 0.8863543 0.201507 0.8856347 0.201507 0.8856347 0.2051962 0.8856347 0.1944806 0.8877661 0.2051962 0.8856347 0.2088143 0.8863543 0.1944806 0.8877661 0.2088143 0.8863543 0.2122226 0.8877661 0.21529 0.8898156 0.21529 0.8898156 0.2178986 0.8924242 0.2088143 0.8863543 0.2178986 0.8924242 0.2199481 0.8954916 0.2088143 0.8863543 0.2199481 0.8954916 0.2213598 0.8988998 0.2220795 0.902518 0.2220795 0.902518 0.2220795 0.9062071 0.2199481 0.8954916 0.2220795 0.9062071 0.2213599 0.9098253 0.2199481 0.8954916 0.2122226 0.920959 0.2051962 0.9230905 0.2213599 0.9098253 0.2051962 0.9230905 0.1978889 0.9223708 0.2213599 0.9098253 0.1867551 0.9132336 0.1846237 0.9062071 0.1853434 0.8988998 0.1978889 0.9223708 0.1867551 0.9132336 0.2213599 0.9098253 0.1867551 0.9132336 0.1853434 0.8988998 0.2213599 0.9098253 0.1853434 0.8988998 0.1944806 0.8877661 0.2088143 0.8863543 0.2088143 0.8863543 0.2199481 0.8954916 0.1853434 0.8988998 0.6288638 0.898926 0.6288638 0.8952547 0.6366735 0.8952547 0.6288638 0.9025973 0.6288638 0.898926 0.6366735 0.898926 0.6288638 0.9061276 0.6288638 0.9025973 0.6366735 0.9025973 0.5625951 0.9189094 0.5599865 0.9163009 0.557937 0.9132335 0.557937 0.9132335 0.5565252 0.9098253 0.5558056 0.9062071 0.5558056 0.9062071 0.5558056 0.902518 0.5565253 0.8988998 0.5565253 0.8988998 0.557937 0.8954916 0.5558056 0.9062071 0.557937 0.8954916 0.5599866 0.8924242 0.5558056 0.9062071 0.5599866 0.8924242 0.5625951 0.8898156 0.5726889 0.8856347 0.5625951 0.8898156 0.5656625 0.8877661 0.5726889 0.8856347 0.5656625 0.8877661 0.5690708 0.8863543 0.5726889 0.8856347 0.5726889 0.8856347 0.5763781 0.8856347 0.5799962 0.8863543 0.5799962 0.8863543 0.5834045 0.8877661 0.5726889 0.8856347 0.5834045 0.8877661 0.5864719 0.8898156 0.5726889 0.8856347 0.5864719 0.8898156 0.5890804 0.8924242 0.59113 0.8954916 0.59113 0.8954916 0.5925417 0.8988999 0.5932614 0.902518 0.5932614 0.902518 0.5932614 0.9062071 0.5890804 0.916301 0.5932614 0.9062071 0.5925417 0.9098253 0.5890804 0.916301 0.5925417 0.9098253 0.59113 0.9132336 0.5890804 0.916301 0.5890804 0.916301 0.5864719 0.9189095 0.5834045 0.9209591 0.5834045 0.9209591 0.5799962 0.9223708 0.5890804 0.916301 0.5799962 0.9223708 0.576378 0.9230905 0.5890804 0.916301 0.576378 0.9230905 0.5726889 0.9230905 0.5625951 0.9189094 0.5726889 0.9230905 0.5690708 0.9223708 0.5625951 0.9189094 0.5690708 0.9223708 0.5656625 0.920959 0.5625951 0.9189094 0.5625951 0.9189094 0.557937 0.9132335 0.5558056 0.9062071 0.5864719 0.8898156 0.59113 0.8954916 0.5932614 0.902518 0.5625951 0.9189094 0.5558056 0.9062071 0.5599866 0.8924242 0.5599866 0.8924242 0.5726889 0.8856347 0.5625951 0.9189094 0.5726889 0.8856347 0.5864719 0.8898156 0.5625951 0.9189094 0.5864719 0.8898156 0.5932614 0.902518 0.5625951 0.9189094 0.5932614 0.902518 0.5890804 0.916301 0.5625951 0.9189094 0.6288638 0.909381 0.6288638 0.9061276 0.6366735 0.9061275 0.6288638 0.9122327 0.6288638 0.909381 0.6366735 0.909381 0.9183475 0.8852093 0.9183475 0.8823576 0.9261572 0.8823576 0.9183475 0.8884628 0.9183475 0.8852093 0.9261572 0.8852093 0.9183475 0.891993 0.9183475 0.8884628 0.9261572 0.8884628 0.9183475 0.8956643 0.9183475 0.891993 0.9261572 0.891993 0.9183475 0.8993356 0.9183475 0.8956643 0.9261572 0.8956643 0.9183475 0.9028658 0.9183475 0.8993356 0.9261572 0.8993356 0.9183475 0.9061194 0.9183475 0.9028658 0.9261572 0.9028658 0.9183475 0.908971 0.9183475 0.9061194 0.9261572 0.9061194 0.9268475 0.2483388 0.9268475 0.2454418 0.9346572 0.2454418 0.9268475 0.2516257 0.9268475 0.2483388 0.9346572 0.2483388 0.9268475 0.2551763 0.9268475 0.2516257 0.9346572 0.2516257 0.9268475 0.2588539 0.9268475 0.2551763 0.9346572 0.2551763 0.9268475 0.2625175 0.9268475 0.2588539 0.9346572 0.2588539 0.9268475 0.266026 0.9268475 0.2625175 0.9346572 0.2625175 0.9268475 0.2692449 0.9268475 0.266026 0.9346572 0.266026 0.9268475 0.2720502 0.9268475 0.2692449 0.9346572 0.2692449 0.6653929 0.9082587 0.6653929 0.905407 0.6732026 0.905407 0.6653929 0.9115122 0.6653929 0.9082587 0.6732026 0.9082587 0.6653929 0.9150424 0.6653929 0.9115122 0.6732026 0.9115122 0.6653929 0.9187138 0.6653929 0.9150424 0.6732026 0.9150424 0.6653929 0.922385 0.6653929 0.9187138 0.6732026 0.9187138 0.6653929 0.9259153 0.6653929 0.922385 0.6732026 0.922385 0.6653929 0.9291687 0.6653929 0.9259153 0.6732026 0.9259153 0.6653929 0.9320204 0.6653929 0.9291687 0.6732026 0.9291687 0.6288638 0.888471 0.6288638 0.8856193 0.6366735 0.8856193 0.6288638 0.8917245 0.6288638 0.888471 0.6366735 0.888471 0.6288638 0.8952547 0.6288638 0.8917245 0.6366735 0.8917245 0.0124287 0.2552404 0.0124287 0.01242876 0.2552404 0.01242876 0.5477672 0.2552404 0.5477672 0.01242876 0.5729795 0.01242876 0.5978369 0.5228631 0.5978369 0.280098 0.6230491 0.280098 0.5477672 0.5229097 0.5477672 0.280098 0.5729794 0.280098 0.01242876 0.5229097 0.01242876 0.280098 0.2552404 0.280098 0.5978369 0.2552404 0.5978369 0.0124287 0.6230491 0.0124287 0.280098 0.2552404 0.280098 0.01242876 0.5229097 0.01242876 0.6479067 0.2552404 0.6479067 0.01242876 0.6497001 0.01242876 0.6745576 0.5228631 0.6745576 0.280098 0.6763511 0.280098 0.6479067 0.5229097 0.6479067 0.280098 0.6497001 0.280098 0.280098 0.5229097 0.280098 0.280098 0.5229097 0.280098 0.6745576 0.2552404 0.6745576 0.01242876 0.676351 0.01242876 0.1846237 0.8207787 0.1846237 0.8152342 0.1962953 0.8152342 0.1846237 0.8152342 0.1846237 0.8097431 0.1962953 0.8097431 0.1846237 0.8097431 0.1846237 0.8043584 0.1962953 0.8043584 0.1846237 0.8043584 0.1846237 0.7991317 0.1962953 0.7991317 0.1846237 0.7991317 0.1846237 0.7941135 0.1962953 0.7941135 0.1846237 0.7941135 0.1846237 0.7893521 0.1962953 0.7893521 0.1846237 0.7893521 0.1846237 0.7848934 0.1962953 0.7848934 0.1846237 0.7848934 0.1846237 0.7807803 0.1962953 0.7807803 0.5558055 0.860777 0.5558055 0.856664 0.5674771 0.856664 0.5558055 0.856664 0.5558055 0.8522052 0.5674771 0.8522052 0.5558055 0.8522052 0.5558055 0.8474438 0.5674771 0.8474438 0.5558055 0.8474438 0.5558055 0.8424257 0.5674771 0.8424257 0.5558055 0.8424257 0.5558055 0.837199 0.5674771 0.837199 0.5558055 0.837199 0.5558055 0.8318142 0.5674771 0.8318142 0.5558055 0.8318142 0.5558055 0.8263231 0.5674771 0.8263231 0.5558055 0.8263231 0.5558055 0.8207787 0.5674771 0.8207787 0.5558055 0.8207787 0.5558055 0.8152342 0.5674771 0.8152342 0.5558055 0.8152342 0.5558055 0.8097431 0.5674771 0.8097431 0.5558055 0.8097431 0.5558055 0.8043583 0.5674771 0.8043583 0.5558055 0.8043583 0.5558055 0.7991317 0.5674771 0.7991317 0.5558055 0.7991317 0.5558055 0.7941135 0.5674771 0.7941135 0.5558055 0.7941135 0.5558055 0.7893521 0.5674771 0.7893521 0.5558055 0.7893521 0.5558055 0.7848934 0.5674771 0.7848934 0.5558055 0.7848934 0.5558055 0.7807803 0.5674771 0.7807803 0.6288638 0.8607618 0.6288638 0.8567225 0.6405354 0.8567225 0.6288638 0.8567225 0.6288638 0.8523294 0.6405354 0.8523294 0.6288638 0.8523294 0.6288638 0.8476248 0.6405354 0.8476248 0.6288638 0.8476248 0.6288638 0.8426541 0.6405354 0.8426541 0.6288638 0.8426541 0.6288638 0.837465 0.6405354 0.837465 0.6288638 0.837465 0.6288638 0.8321077 0.6405354 0.8321077 0.6288638 0.8321077 0.6288638 0.8266336 0.6405354 0.8266336 0.6288638 0.8266336 0.6288638 0.8210955 0.6405354 0.8210955 0.6288638 0.8210955 0.6288638 0.8155468 0.6405354 0.8155468 0.6288638 0.8155468 0.6288638 0.8100408 0.6405354 0.8100408 0.6288638 0.8100408 0.6288638 0.8046306 0.6405354 0.8046306 0.6288638 0.8046306 0.6288638 0.7993684 0.6405354 0.7993684 0.6288638 0.7993684 0.6288638 0.7943047 0.6405354 0.7943047 0.6288638 0.7943047 0.6288638 0.7894883 0.6405354 0.7894883 0.6288638 0.7894883 0.6288638 0.7849657 0.6405354 0.7849657 0.6288638 0.7849657 0.6288638 0.7807803 0.6405354 0.7807803 0.5923346 0.8607771 0.5923346 0.856664 0.6040062 0.856664 0.5923346 0.856664 0.5923346 0.8522053 0.6040062 0.8522052 0.5923346 0.8522053 0.5923346 0.8474439 0.6040062 0.8474439 0.5923346 0.8474439 0.5923346 0.8424257 0.6040062 0.8424257 0.5923346 0.8424257 0.5923346 0.837199 0.6040062 0.837199 0.5923346 0.837199 0.5923346 0.8318142 0.6040062 0.8318142 0.5923346 0.8318142 0.5923346 0.8263232 0.6040062 0.8263232 0.5923346 0.8263232 0.5923346 0.8207787 0.6040062 0.8207787 0.5923346 0.8207787 0.5923346 0.8152343 0.6040062 0.8152343 0.5923346 0.8152343 0.5923346 0.8097432 0.6040062 0.8097432 0.5923346 0.8097432 0.5923346 0.8043584 0.6040062 0.8043584 0.5923346 0.8043584 0.5923346 0.7991318 0.6040062 0.7991318 0.5923346 0.7991318 0.5923346 0.7941136 0.6040062 0.7941136 0.5923346 0.7941136 0.5923346 0.7893522 0.6040062 0.7893522 0.5923346 0.7893522 0.5923346 0.7848935 0.6040062 0.7848935 0.5923346 0.7848935 0.5923346 0.7807803 0.6040062 0.7807803 0.1846237 0.8607771 0.1846237 0.856664 0.1962953 0.856664 0.1846237 0.856664 0.1846237 0.8522052 0.1962953 0.8522052 0.1846237 0.8522052 0.1846237 0.8474438 0.1962953 0.8474438 0.1846237 0.8474438 0.1846237 0.8424257 0.1962953 0.8424257 0.1846237 0.8424257 0.1846237 0.837199 0.1962953 0.837199 0.1846237 0.837199 0.1846237 0.8318142 0.1962953 0.8318142 0.2946833 0.8752661 0.2911617 0.870975 0.2833365 0.8563351 0.2911617 0.870975 0.2880776 0.8663594 0.2833365 0.8563351 0.2880776 0.8663594 0.2854608 0.8614637 0.2833365 0.8563351 0.2833365 0.8563351 0.2817251 0.851023 0.2806421 0.8455785 0.2806421 0.8455785 0.280098 0.840054 0.280098 0.8345029 0.280098 0.8345029 0.2806421 0.8289785 0.2817251 0.823534 0.2817251 0.823534 0.2833365 0.8182219 0.2854608 0.8130933 0.2854608 0.8130933 0.2880776 0.8081976 0.2911617 0.803582 0.2911617 0.803582 0.2946833 0.7992909 0.2986085 0.7953656 0.2986085 0.7953656 0.3028996 0.791844 0.3075152 0.78876 0.3075152 0.78876 0.3124109 0.7861432 0.2986085 0.7953656 0.3124109 0.7861432 0.3175395 0.7840189 0.2986085 0.7953656 0.3175395 0.7840189 0.3228516 0.7824075 0.3282961 0.7813245 0.3282961 0.7813245 0.3338205 0.7807804 0.3393717 0.7807804 0.3393717 0.7807804 0.3448961 0.7813245 0.3503406 0.7824074 0.3503406 0.7824074 0.3556527 0.7840189 0.3607813 0.7861432 0.3607813 0.7861432 0.365677 0.78876 0.3702926 0.791844 0.3702926 0.791844 0.3745837 0.7953656 0.3785089 0.7992909 0.3785089 0.7992909 0.3820306 0.803582 0.3898558 0.8182219 0.3820306 0.803582 0.3851146 0.8081976 0.3898558 0.8182219 0.3851146 0.8081976 0.3877314 0.8130933 0.3898558 0.8182219 0.3898558 0.8182219 0.3914672 0.823534 0.3925501 0.8289785 0.3925501 0.8289785 0.3930943 0.8345029 0.3930943 0.840054 0.3930943 0.840054 0.3925501 0.8455785 0.3914672 0.851023 0.3914672 0.851023 0.3898558 0.8563351 0.3877314 0.8614637 0.3877314 0.8614637 0.3851146 0.8663594 0.3820306 0.870975 0.3820306 0.870975 0.3785089 0.8752661 0.3745837 0.8791913 0.3745837 0.8791913 0.3702926 0.882713 0.365677 0.885797 0.365677 0.885797 0.3607813 0.8884138 0.3745837 0.8791913 0.3607813 0.8884138 0.3556527 0.8905381 0.3745837 0.8791913 0.3556527 0.8905381 0.3503406 0.8921495 0.3448961 0.8932325 0.3448961 0.8932325 0.3393717 0.8937766 0.3338205 0.8937766 0.3338205 0.8937766 0.3282961 0.8932325 0.3228516 0.8921495 0.3228516 0.8921495 0.3175395 0.8905381 0.3124109 0.8884138 0.3124109 0.8884138 0.3075152 0.885797 0.3028996 0.882713 0.3028996 0.882713 0.2986086 0.8791913 0.2946833 0.8752661 0.2833365 0.8563351 0.2806421 0.8455785 0.2946833 0.8752661 0.2806421 0.8455785 0.280098 0.8345029 0.2946833 0.8752661 0.280098 0.8345029 0.2817251 0.823534 0.2854608 0.8130933 0.2854608 0.8130933 0.2911617 0.803582 0.280098 0.8345029 0.2911617 0.803582 0.2986085 0.7953656 0.280098 0.8345029 0.3175395 0.7840189 0.3282961 0.7813245 0.2986085 0.7953656 0.3282961 0.7813245 0.3393717 0.7807804 0.2986085 0.7953656 0.3393717 0.7807804 0.3503406 0.7824074 0.3607813 0.7861432 0.3607813 0.7861432 0.3702926 0.791844 0.3785089 0.7992909 0.3898558 0.8182219 0.3925501 0.8289785 0.3785089 0.7992909 0.3925501 0.8289785 0.3930943 0.840054 0.3785089 0.7992909 0.3930943 0.840054 0.3914672 0.851023 0.3877314 0.8614637 0.3877314 0.8614637 0.3820306 0.870975 0.3930943 0.840054 0.3820306 0.870975 0.3745837 0.8791913 0.3930943 0.840054 0.3556527 0.8905381 0.3448961 0.8932325 0.3745837 0.8791913 0.3448961 0.8932325 0.3338205 0.8937766 0.3745837 0.8791913 0.3338205 0.8937766 0.3228516 0.8921495 0.3124109 0.8884138 0.3124109 0.8884138 0.3028996 0.882713 0.2946833 0.8752661 0.3393717 0.7807804 0.3607813 0.7861432 0.2986085 0.7953656 0.3607813 0.7861432 0.3785089 0.7992909 0.2986085 0.7953656 0.3338205 0.8937766 0.3124109 0.8884138 0.3745837 0.8791913 0.3124109 0.8884138 0.2946833 0.8752661 0.3745837 0.8791913 0.2946833 0.8752661 0.280098 0.8345029 0.3785089 0.7992909 0.280098 0.8345029 0.2986085 0.7953656 0.3785089 0.7992909 0.3785089 0.7992909 0.3930943 0.840054 0.2946833 0.8752661 0.1846237 0.8318142 0.1846237 0.8263232 0.1962953 0.8263232 0.1846237 0.8263232 0.1846237 0.8207787 0.1962953 0.8207787 0.4211902 0.8563351 0.4195788 0.8510229 0.4184958 0.8455784 0.4184958 0.8455784 0.4179517 0.840054 0.4179517 0.8345029 0.4179517 0.8345029 0.4184958 0.8289784 0.4195788 0.823534 0.4195788 0.823534 0.4211902 0.8182219 0.4233145 0.8130933 0.4233145 0.8130933 0.4259313 0.8081976 0.4290154 0.803582 0.4290154 0.803582 0.432537 0.7992908 0.4233145 0.8130933 0.432537 0.7992908 0.4364622 0.7953656 0.4233145 0.8130933 0.4364622 0.7953656 0.4407534 0.791844 0.4553933 0.7840188 0.4407534 0.791844 0.445369 0.78876 0.4553933 0.7840188 0.445369 0.78876 0.4502646 0.7861431 0.4553933 0.7840188 0.4553933 0.7840188 0.4607053 0.7824074 0.4661499 0.7813244 0.4661499 0.7813244 0.4716743 0.7807803 0.4772254 0.7807803 0.4772254 0.7807803 0.4827498 0.7813244 0.4881944 0.7824074 0.4881944 0.7824074 0.4935064 0.7840188 0.4986351 0.7861431 0.4986351 0.7861431 0.5035308 0.78876 0.5081464 0.791844 0.5081464 0.791844 0.5124375 0.7953656 0.4986351 0.7861431 0.5124375 0.7953656 0.5163627 0.7992908 0.4986351 0.7861431 0.5163627 0.7992908 0.5198843 0.803582 0.5277095 0.8182218 0.5198843 0.803582 0.5229684 0.8081976 0.5277095 0.8182218 0.5229684 0.8081976 0.5255852 0.8130933 0.5277095 0.8182218 0.5277095 0.8182218 0.5293209 0.823534 0.5304039 0.8289784 0.5304039 0.8289784 0.530948 0.8345029 0.530948 0.840054 0.530948 0.840054 0.5304039 0.8455784 0.5255852 0.8614636 0.5304039 0.8455784 0.5293209 0.8510229 0.5255852 0.8614636 0.5293209 0.8510229 0.5277095 0.8563351 0.5255852 0.8614636 0.5255852 0.8614636 0.5229684 0.8663593 0.5198843 0.8709749 0.5198843 0.8709749 0.5163627 0.875266 0.5255852 0.8614636 0.5163627 0.875266 0.5124375 0.8791913 0.5255852 0.8614636 0.5124375 0.8791913 0.5081464 0.8827129 0.4935064 0.8905381 0.5081464 0.8827129 0.5035308 0.885797 0.4935064 0.8905381 0.5035308 0.885797 0.4986351 0.8884137 0.4935064 0.8905381 0.4935064 0.8905381 0.4881944 0.8921495 0.4827498 0.8932325 0.4827498 0.8932325 0.4772254 0.8937766 0.4716743 0.8937766 0.4716743 0.8937766 0.4661499 0.8932325 0.4607053 0.8921495 0.4607053 0.8921495 0.4553933 0.8905381 0.4502646 0.8884137 0.4502646 0.8884137 0.445369 0.885797 0.4407534 0.8827129 0.4407534 0.8827129 0.4364623 0.8791913 0.4502646 0.8884137 0.4364623 0.8791913 0.432537 0.875266 0.4502646 0.8884137 0.432537 0.875266 0.4290154 0.870975 0.4211902 0.8563351 0.4290154 0.870975 0.4259313 0.8663593 0.4211902 0.8563351 0.4259313 0.8663593 0.4233145 0.8614637 0.4211902 0.8563351 0.4211902 0.8563351 0.4184958 0.8455784 0.4179517 0.8345029 0.4179517 0.8345029 0.4195788 0.823534 0.4211902 0.8563351 0.4195788 0.823534 0.4233145 0.8130933 0.4211902 0.8563351 0.4553933 0.7840188 0.4661499 0.7813244 0.4772254 0.7807803 0.4772254 0.7807803 0.4881944 0.7824074 0.4553933 0.7840188 0.4881944 0.7824074 0.4986351 0.7861431 0.4553933 0.7840188 0.5277095 0.8182218 0.5304039 0.8289784 0.5255852 0.8614636 0.5304039 0.8289784 0.530948 0.840054 0.5255852 0.8614636 0.4935064 0.8905381 0.4827498 0.8932325 0.4716743 0.8937766 0.4716743 0.8937766 0.4607053 0.8921495 0.4935064 0.8905381 0.4607053 0.8921495 0.4502646 0.8884137 0.4935064 0.8905381 0.4233145 0.8130933 0.4364622 0.7953656 0.4553933 0.7840188 0.4986351 0.7861431 0.5163627 0.7992908 0.5277095 0.8182218 0.5255852 0.8614636 0.5124375 0.8791913 0.4935064 0.8905381 0.4502646 0.8884137 0.432537 0.875266 0.4211902 0.8563351 0.4211902 0.8563351 0.4233145 0.8130933 0.4553933 0.7840188 0.4553933 0.7840188 0.4986351 0.7861431 0.4211902 0.8563351 0.4986351 0.7861431 0.5277095 0.8182218 0.4211902 0.8563351 0.5277095 0.8182218 0.5255852 0.8614636 0.4935064 0.8905381 0.4935064 0.8905381 0.4502646 0.8884137 0.5277095 0.8182218 0.2533901 0.62145 0.2533901 0.6112363 0.2552404 0.6112363 0.2533901 0.6112363 0.2533901 0.601121 0.2552404 0.601121 0.2533901 0.601121 0.2533901 0.5912014 0.2552404 0.5912014 0.2533901 0.5912014 0.2533901 0.5815731 0.2552404 0.5815731 0.2533901 0.5815731 0.2533901 0.5723289 0.2552404 0.5723289 0.2533901 0.5723289 0.2533901 0.5635578 0.2552404 0.5635578 0.2533901 0.5635578 0.2533901 0.5553441 0.2552404 0.5553441 0.2533901 0.5553441 0.2533901 0.5477672 0.2552404 0.5477672 0.2533902 0.8673562 0.2533902 0.8597792 0.2552404 0.8597792 0.2533902 0.8597792 0.2533902 0.8515655 0.2552404 0.8515655 0.2533902 0.8515655 0.2533902 0.8427944 0.2552404 0.8427944 0.2533902 0.8427944 0.2533902 0.8335502 0.2552404 0.8335502 0.2533902 0.8335502 0.2533902 0.8239219 0.2552404 0.8239219 0.2533902 0.8239219 0.2533902 0.8140023 0.2552404 0.8140023 0.2533902 0.8140023 0.2533902 0.803887 0.2552404 0.803887 0.2533902 0.803887 0.2533902 0.7936733 0.2552404 0.7936733 0.2533902 0.7936733 0.2533902 0.7834596 0.2552404 0.7834596 0.2533902 0.7834596 0.2533902 0.7733442 0.2552404 0.7733442 0.2533902 0.7733442 0.2533902 0.7634247 0.2552404 0.7634247 0.2533902 0.7634247 0.2533902 0.7537964 0.2552404 0.7537964 0.2533902 0.7537964 0.2533902 0.7445522 0.2552404 0.7445522 0.2533902 0.7445522 0.2533902 0.735781 0.2552404 0.735781 0.2533902 0.735781 0.2533902 0.7275674 0.2552404 0.7275674 0.2533902 0.7275674 0.2533902 0.7199904 0.2552404 0.7199904 0.9001397 0.3927794 0.9001397 0.3853383 0.9019899 0.3853383 0.9001397 0.3853383 0.9001397 0.3772456 0.9019899 0.3772456 0.9001397 0.3772456 0.9001397 0.368579 0.9019899 0.368579 0.9001397 0.368579 0.9001397 0.3594222 0.9019899 0.3594222 0.9001397 0.3594222 0.9001397 0.3498632 0.9019899 0.3498632 0.9001397 0.3498632 0.9001397 0.3399943 0.9019899 0.3399943 0.9001397 0.3399943 0.9001397 0.3299102 0.9019899 0.3299102 0.9001397 0.3299102 0.9001397 0.3197083 0.9019899 0.3197083 0.9001397 0.3197083 0.9001397 0.3094867 0.9019899 0.3094867 0.9001397 0.3094867 0.9001397 0.2993439 0.9019899 0.2993439 0.9001397 0.2993439 0.9001397 0.2893776 0.9019899 0.2893776 0.9001397 0.2893776 0.9001397 0.2796837 0.9019899 0.2796837 0.9001397 0.2796837 0.9001397 0.2703557 0.9019899 0.2703557 0.9001397 0.2703557 0.9001397 0.2614832 0.9019899 0.2614832 0.9001397 0.2614832 0.9001397 0.2531518 0.9019899 0.2531518 0.9001397 0.2531518 0.9001397 0.2454418 0.9019899 0.2454418 0.8734319 0.3928076 0.8734319 0.3852306 0.8752822 0.3852306 0.8734319 0.3852306 0.8734319 0.377017 0.8752822 0.377017 0.8734319 0.377017 0.8734319 0.3682458 0.8752822 0.3682458 0.8734319 0.3682458 0.8734319 0.3590016 0.8752822 0.3590016 0.8734319 0.3590016 0.8734319 0.3493734 0.8752822 0.3493734 0.8734319 0.3493734 0.8734319 0.3394538 0.8752822 0.3394538 0.8734319 0.3394538 0.8734319 0.3293384 0.8752822 0.3293384 0.8734319 0.3293384 0.8734319 0.3191247 0.8752822 0.3191247 0.8734319 0.3191247 0.8734319 0.308911 0.8752822 0.308911 0.8734319 0.308911 0.8734319 0.2987957 0.8752822 0.2987957 0.8734319 0.2987957 0.8734319 0.2888761 0.8752822 0.2888761 0.8734319 0.2888761 0.8734319 0.2792478 0.8752822 0.2792478 0.8734319 0.2792478 0.8734319 0.2700036 0.8752822 0.2700036 0.8734319 0.2700036 0.8734319 0.2612324 0.8752822 0.2612324 0.8734319 0.2612324 0.8734319 0.2530189 0.8752822 0.2530189 0.8734319 0.2530189 0.8734319 0.2454419 0.8752822 0.2454419 0.2533902 0.6951329 0.2533902 0.6875559 0.2552404 0.6875559 0.2533902 0.6875559 0.2533902 0.6793423 0.2552404 0.6793423 0.2533902 0.6793423 0.2533902 0.6705712 0.2552404 0.6705712 0.2533902 0.6705712 0.2533901 0.6613269 0.2552404 0.6613269 0.2533901 0.6613269 0.2533901 0.6516987 0.2552404 0.6516987 0.2533901 0.6516987 0.2533901 0.6417791 0.2552404 0.6417791 0.7202644 0.6365553 0.7212667 0.646732 0.7212667 0.6569581 0.7212667 0.6569581 0.7202643 0.6671348 0.7202644 0.6365553 0.7202643 0.6671348 0.7182694 0.6771644 0.7202644 0.6365553 0.7182694 0.6771644 0.7153009 0.6869501 0.7113875 0.6963977 0.7113875 0.6963977 0.706567 0.7054163 0.7008857 0.7139189 0.7008857 0.7139189 0.6943984 0.7218237 0.6871675 0.7290546 0.6871675 0.7290546 0.6792627 0.7355419 0.67076 0.7412232 0.67076 0.7412232 0.6617415 0.7460437 0.6522939 0.749957 0.6522939 0.749957 0.6425082 0.7529255 0.6324786 0.7549205 0.6324786 0.7549205 0.6223018 0.7559228 0.6120758 0.7559228 0.6120758 0.7559228 0.601899 0.7549205 0.6324786 0.7549205 0.601899 0.7549205 0.5918695 0.7529255 0.6324786 0.7549205 0.5918695 0.7529255 0.5820838 0.749957 0.5726362 0.7460437 0.5726362 0.7460437 0.5636176 0.7412232 0.555115 0.7355419 0.555115 0.7355419 0.5472102 0.7290545 0.5399793 0.7218236 0.5399793 0.7218236 0.533492 0.7139188 0.5278107 0.7054162 0.5278107 0.7054162 0.5229902 0.6963976 0.5190768 0.68695 0.5190768 0.68695 0.5161084 0.6771643 0.5141134 0.6671348 0.5141134 0.6671348 0.5131111 0.656958 0.5161084 0.6265256 0.5131111 0.656958 0.5131111 0.6467319 0.5161084 0.6265256 0.5131111 0.6467319 0.5141134 0.6365551 0.5161084 0.6265256 0.5161084 0.6265256 0.5190769 0.6167399 0.5229902 0.6072923 0.5229902 0.6072923 0.5278107 0.5982738 0.533492 0.5897711 0.533492 0.5897711 0.5399793 0.5818663 0.5472102 0.5746354 0.5472102 0.5746354 0.5551151 0.5681481 0.5636177 0.5624668 0.5636177 0.5624668 0.5726363 0.5576463 0.5820839 0.5537329 0.5820839 0.5537329 0.5918696 0.5507645 0.6018991 0.5487695 0.6018991 0.5487695 0.6120759 0.5477672 0.6223019 0.5477672 0.6223019 0.5477672 0.6324787 0.5487695 0.6018991 0.5487695 0.6324787 0.5487695 0.6425083 0.5507645 0.6018991 0.5487695 0.6425083 0.5507645 0.652294 0.553733 0.6617416 0.5576463 0.6617416 0.5576463 0.6707601 0.5624669 0.6792628 0.5681481 0.6792628 0.5681481 0.6871676 0.5746355 0.6943985 0.5818663 0.6943985 0.5818663 0.7008858 0.5897712 0.7065671 0.5982738 0.7065671 0.5982738 0.7113876 0.6072924 0.7153009 0.61674 0.7153009 0.61674 0.7182694 0.6265257 0.7202644 0.6365553 0.7182694 0.6771644 0.7113875 0.6963977 0.7008857 0.7139189 0.7008857 0.7139189 0.6871675 0.7290546 0.67076 0.7412232 0.67076 0.7412232 0.6522939 0.749957 0.6324786 0.7549205 0.5918695 0.7529255 0.5726362 0.7460437 0.555115 0.7355419 0.555115 0.7355419 0.5399793 0.7218236 0.5278107 0.7054162 0.5278107 0.7054162 0.5190768 0.68695 0.5141134 0.6671348 0.5161084 0.6265256 0.5229902 0.6072923 0.533492 0.5897711 0.533492 0.5897711 0.5472102 0.5746354 0.5636177 0.5624668 0.5636177 0.5624668 0.5820839 0.5537329 0.6018991 0.5487695 0.6425083 0.5507645 0.6617416 0.5576463 0.6792628 0.5681481 0.6792628 0.5681481 0.6943985 0.5818663 0.7065671 0.5982738 0.7065671 0.5982738 0.7153009 0.61674 0.7202644 0.6365553 0.7202644 0.6365553 0.7182694 0.6771644 0.7008857 0.7139189 0.7008857 0.7139189 0.67076 0.7412232 0.6324786 0.7549205 0.6324786 0.7549205 0.5918695 0.7529255 0.555115 0.7355419 0.555115 0.7355419 0.5278107 0.7054162 0.5141134 0.6671348 0.5141134 0.6671348 0.5161084 0.6265256 0.533492 0.5897711 0.533492 0.5897711 0.5636177 0.5624668 0.6018991 0.5487695 0.6018991 0.5487695 0.6425083 0.5507645 0.6792628 0.5681481 0.6792628 0.5681481 0.7065671 0.5982738 0.7202644 0.6365553 0.7202644 0.6365553 0.7008857 0.7139189 0.6324786 0.7549205 0.6324786 0.7549205 0.555115 0.7355419 0.7202644 0.6365553 0.555115 0.7355419 0.5141134 0.6671348 0.7202644 0.6365553 0.5141134 0.6671348 0.533492 0.5897711 0.6018991 0.5487695 0.6018991 0.5487695 0.6792628 0.5681481 0.5141134 0.6671348 0.2533901 0.6417791 0.2533901 0.6316637 0.2552404 0.6316637 0.2533901 0.6316637 0.2533901 0.62145 0.2552404 0.62145 0.9093642 0.1113936 0.9093642 0.1216196 0.9083619 0.1317964 0.9083619 0.1317964 0.9063668 0.1418259 0.9033984 0.1516116 0.9033984 0.1516116 0.8994851 0.1610593 0.8946645 0.1700778 0.8946645 0.1700778 0.8889833 0.1785804 0.9033984 0.1516116 0.8889833 0.1785804 0.8824959 0.1864852 0.9033984 0.1516116 0.8824959 0.1864852 0.875265 0.1937161 0.8673602 0.2002035 0.8673602 0.2002035 0.8588576 0.2058847 0.8824959 0.1864852 0.8588576 0.2058847 0.849839 0.2107052 0.8824959 0.1864852 0.849839 0.2107052 0.8403914 0.2146186 0.8103994 0.2205843 0.8403914 0.2146186 0.8306057 0.217587 0.8103994 0.2205843 0.8306057 0.217587 0.8205761 0.219582 0.8103994 0.2205843 0.8103994 0.2205843 0.8001734 0.2205843 0.7899965 0.219582 0.7899965 0.219582 0.779967 0.217587 0.7701813 0.2146186 0.7701813 0.2146186 0.7607337 0.2107052 0.7517151 0.2058847 0.7517151 0.2058847 0.7432125 0.2002034 0.7701813 0.2146186 0.7432125 0.2002034 0.7353077 0.1937161 0.7701813 0.2146186 0.7353077 0.1937161 0.7280768 0.1864852 0.7215895 0.1785804 0.7215895 0.1785804 0.7159082 0.1700777 0.7353077 0.1937161 0.7159082 0.1700777 0.7110877 0.1610592 0.7353077 0.1937161 0.7110877 0.1610592 0.7071744 0.1516115 0.7012086 0.1216195 0.7071744 0.1516115 0.7042059 0.1418258 0.7012086 0.1216195 0.7042059 0.1418258 0.7022109 0.1317963 0.7012086 0.1216195 0.7012086 0.1216195 0.7012086 0.1113935 0.7022109 0.1012167 0.7022109 0.1012167 0.7042059 0.09118717 0.7071744 0.08140146 0.7071744 0.08140146 0.7110877 0.07195383 0.7159082 0.06293529 0.7159082 0.06293529 0.7215895 0.05443263 0.7071744 0.08140146 0.7215895 0.05443263 0.7280768 0.0465278 0.7071744 0.08140146 0.7280768 0.0465278 0.7353078 0.03929692 0.7432126 0.03280961 0.7432126 0.03280961 0.7517152 0.02712833 0.7280768 0.0465278 0.7517152 0.02712833 0.7607338 0.02230781 0.7280768 0.0465278 0.7607338 0.02230781 0.7701814 0.01839452 0.8001734 0.01242876 0.7701814 0.01839452 0.7799671 0.01542603 0.8001734 0.01242876 0.7799671 0.01542603 0.7899966 0.01343107 0.8001734 0.01242876 0.8001734 0.01242876 0.8103994 0.01242876 0.8205763 0.01343107 0.8205763 0.01343107 0.8306058 0.01542609 0.8403915 0.01839452 0.8403915 0.01839452 0.8498391 0.02230787 0.8588576 0.02712839 0.8588576 0.02712839 0.8673603 0.03280967 0.8403915 0.01839452 0.8673603 0.03280967 0.8752651 0.03929698 0.8403915 0.01839452 0.8752651 0.03929698 0.882496 0.04652792 0.8889833 0.05443274 0.8889833 0.05443274 0.8946646 0.06293535 0.8752651 0.03929698 0.8946646 0.06293535 0.8994851 0.07195395 0.8752651 0.03929698 0.8994851 0.07195395 0.9033984 0.08140152 0.9093642 0.1113936 0.9033984 0.08140152 0.9063669 0.09118723 0.9093642 0.1113936 0.9063669 0.09118723 0.9083619 0.1012168 0.9093642 0.1113936 0.9093642 0.1113936 0.9083619 0.1317964 0.8824959 0.1864852 0.9083619 0.1317964 0.9033984 0.1516116 0.8824959 0.1864852 0.8103994 0.2205843 0.7899965 0.219582 0.7353077 0.1937161 0.7899965 0.219582 0.7701813 0.2146186 0.7353077 0.1937161 0.7012086 0.1216195 0.7022109 0.1012167 0.7280768 0.0465278 0.7022109 0.1012167 0.7071744 0.08140146 0.7280768 0.0465278 0.8001734 0.01242876 0.8205763 0.01343107 0.8752651 0.03929698 0.8205763 0.01343107 0.8403915 0.01839452 0.8752651 0.03929698 0.8824959 0.1864852 0.849839 0.2107052 0.8103994 0.2205843 0.7353077 0.1937161 0.7110877 0.1610592 0.7012086 0.1216195 0.7280768 0.0465278 0.7607338 0.02230781 0.8001734 0.01242876 0.8752651 0.03929698 0.8994851 0.07195395 0.9093642 0.1113936 0.9093642 0.1113936 0.8824959 0.1864852 0.8103994 0.2205843 0.8103994 0.2205843 0.7353077 0.1937161 0.7012086 0.1216195 0.7012086 0.1216195 0.7280768 0.0465278 0.8001734 0.01242876 0.8001734 0.01242876 0.8752651 0.03929698 0.9093642 0.1113936 0.9093642 0.1113936 0.8103994 0.2205843 0.7012086 0.1216195 - - - - - - - - - - - - - - -

65 34 102 66 34 103 64 34 104 67 35 105 68 35 106 66 35 107 69 36 108 70 36 109 68 36 110 71 37 111 72 37 112 70 37 113 73 38 114 74 38 115 72 38 116 75 39 117 76 39 118 74 39 119 77 40 120 78 40 121 76 40 122 79 41 123 80 41 124 78 41 125 81 42 126 82 42 127 80 42 128 83 43 129 84 43 130 82 43 131 85 44 132 86 44 133 84 44 134 87 45 135 88 45 136 86 45 137 89 46 138 90 46 139 88 46 140 91 47 141 92 47 142 90 47 143 93 48 144 94 48 145 92 48 146 95 49 147 96 49 148 94 49 149 97 50 150 98 50 151 96 50 152 99 51 153 100 51 154 98 51 155 101 52 156 102 52 157 100 52 158 103 53 159 104 53 160 102 53 161 105 54 162 106 54 163 104 54 164 107 55 165 108 55 166 106 55 167 109 56 168 110 56 169 108 56 170 111 57 171 112 57 172 110 57 173 113 58 174 114 58 175 112 58 176 115 59 177 116 59 178 114 59 179 117 60 180 118 60 181 116 60 182 119 61 183 120 61 184 118 61 185 121 62 186 122 62 187 120 62 188 123 63 189 124 63 190 122 63 191 125 64 192 126 64 193 124 64 194 127 65 195 128 65 196 126 65 197 129 66 198 130 66 199 128 66 200 131 67 201 132 67 202 130 67 203 133 68 204 134 68 205 132 68 206 135 69 207 136 69 208 134 69 209 137 70 210 138 70 211 136 70 212 139 71 213 140 71 214 138 71 215 141 72 216 142 72 217 140 72 218 143 73 219 144 73 220 142 73 221 145 74 222 146 74 223 144 74 224 147 75 225 148 75 226 146 75 227 149 76 228 150 76 229 148 76 230 151 77 231 152 77 232 150 77 233 153 78 234 154 78 235 152 78 236 155 79 237 156 79 238 154 79 239 157 80 240 158 80 241 156 80 242 159 81 243 160 81 244 158 81 245 161 82 246 162 82 247 160 82 248 163 83 249 164 83 250 162 83 251 165 84 252 166 84 253 164 84 254 167 85 255 168 85 256 166 85 257 169 86 258 170 86 259 168 86 260 171 87 261 172 87 262 170 87 263 173 88 264 174 88 265 172 88 266 175 89 267 176 89 268 174 89 269 177 90 270 178 90 271 176 90 272 179 91 273 180 91 274 178 91 275 181 92 276 182 92 277 180 92 278 183 93 279 184 93 280 182 93 281 185 94 282 186 94 283 184 94 284 187 95 285 188 95 286 186 95 287 85 4 288 69 4 289 133 4 290 189 96 291 190 96 292 188 96 293 191 97 294 64 97 295 190 97 296 126 98 297 158 98 298 190 98 299 644 0 1014 640 0 1015 641 0 1016 642 261 1017 641 261 1018 640 261 1019 645 262 1020 640 262 1021 643 262 1022 646 263 1023 643 263 1024 644 263 1025 647 4 1026 645 4 1027 646 4 1028 647 264 1029 644 264 1030 641 264 1031 657 265 1050 658 265 1051 656 265 1052 659 266 1053 660 266 1054 658 266 1055 661 267 1056 662 267 1057 660 267 1058 663 268 1059 664 268 1060 662 268 1061 665 269 1062 666 269 1063 664 269 1064 667 270 1065 668 270 1066 666 270 1067 669 271 1068 670 271 1069 668 271 1070 671 272 1071 672 272 1072 670 272 1073 673 273 1074 674 273 1075 672 273 1076 675 274 1077 676 274 1078 674 274 1079 677 275 1080 678 275 1081 676 275 1082 679 276 1083 680 276 1084 678 276 1085 681 277 1086 682 277 1087 680 277 1088 683 278 1089 684 278 1090 682 278 1091 685 279 1092 686 279 1093 684 279 1094 687 280 1095 688 280 1096 686 280 1097 689 281 1098 690 281 1099 688 281 1100 691 282 1101 692 282 1102 690 282 1103 693 283 1104 694 283 1105 692 283 1106 695 284 1107 696 284 1108 694 284 1109 697 285 1110 698 285 1111 696 285 1112 699 286 1113 700 286 1114 698 286 1115 701 287 1116 702 287 1117 700 287 1118 703 288 1119 704 288 1120 702 288 1121 705 289 1122 706 289 1123 704 289 1124 707 290 1125 708 290 1126 706 290 1127 709 291 1128 710 291 1129 708 291 1130 711 292 1131 712 292 1132 710 292 1133 713 293 1134 714 293 1135 712 293 1136 715 294 1137 716 294 1138 714 294 1139 717 295 1140 718 295 1141 716 295 1142 719 296 1143 720 296 1144 718 296 1145 721 297 1146 722 297 1147 720 297 1148 723 298 1149 724 298 1150 722 298 1151 725 299 1152 726 299 1153 724 299 1154 727 300 1155 728 300 1156 726 300 1157 729 301 1158 730 301 1159 728 301 1160 731 302 1161 732 302 1162 730 302 1163 733 303 1164 734 303 1165 732 303 1166 735 304 1167 736 304 1168 734 304 1169 737 305 1170 738 305 1171 736 305 1172 739 306 1173 740 306 1174 738 306 1175 741 307 1176 742 307 1177 740 307 1178 743 308 1179 744 308 1180 742 308 1181 745 309 1182 746 309 1183 744 309 1184 747 310 1185 748 310 1186 746 310 1187 749 311 1188 750 311 1189 748 311 1190 751 312 1191 752 312 1192 750 312 1193 753 313 1194 754 313 1195 752 313 1196 755 314 1197 756 314 1198 754 314 1199 757 315 1200 758 315 1201 756 315 1202 759 316 1203 760 316 1204 758 316 1205 761 317 1206 762 317 1207 760 317 1208 763 318 1209 764 318 1210 762 318 1211 765 319 1212 766 319 1213 764 319 1214 767 320 1215 768 320 1216 766 320 1217 769 321 1218 770 321 1219 768 321 1220 771 322 1221 772 322 1222 770 322 1223 773 323 1224 774 323 1225 772 323 1226 775 324 1227 776 324 1228 774 324 1229 777 325 1230 778 325 1231 776 325 1232 779 326 1233 780 326 1234 778 326 1235 709 4 1236 693 4 1237 661 4 1238 781 327 1239 782 327 1240 780 327 1241 783 328 1242 656 328 1243 782 328 1244 766 329 1245 782 329 1246 718 329 1247 65 427 1716 67 427 1717 66 427 1718 67 35 1719 69 35 1720 68 35 1721 69 36 1722 71 36 1723 70 36 1724 71 37 1725 73 37 1726 72 37 1727 73 428 1728 75 428 1729 74 428 1730 75 429 1731 77 429 1732 76 429 1733 77 40 1734 79 40 1735 78 40 1736 79 430 1737 81 430 1738 80 430 1739 81 431 1740 83 431 1741 82 431 1742 83 432 1743 85 432 1744 84 432 1745 85 433 1746 87 433 1747 86 433 1748 87 276 1749 89 276 1750 88 276 1751 89 277 1752 91 277 1753 90 277 1754 91 434 1755 93 434 1756 92 434 1757 93 48 1758 95 48 1759 94 48 1760 95 435 1761 97 435 1762 96 435 1763 97 436 1764 99 436 1765 98 436 1766 99 51 1767 101 51 1768 100 51 1769 101 437 1770 103 437 1771 102 437 1772 103 284 1773 105 284 1774 104 284 1775 105 438 1776 107 438 1777 106 438 1778 107 439 1779 109 439 1780 108 439 1781 109 440 1782 111 440 1783 110 440 1784 111 441 1785 113 441 1786 112 441 1787 113 442 1788 115 442 1789 114 442 1790 115 59 1791 117 59 1792 116 59 1793 117 443 1794 119 443 1795 118 443 1796 119 444 1797 121 444 1798 120 444 1799 121 62 1800 123 62 1801 122 62 1802 123 63 1803 125 63 1804 124 63 1805 125 64 1806 127 64 1807 126 64 1808 127 445 1809 129 445 1810 128 445 1811 129 446 1812 131 446 1813 130 446 1814 131 67 1815 133 67 1816 132 67 1817 133 68 1818 135 68 1819 134 68 1820 135 69 1821 137 69 1822 136 69 1823 137 447 1824 139 447 1825 138 447 1826 139 448 1827 141 448 1828 140 448 1829 141 72 1830 143 72 1831 142 72 1832 143 449 1833 145 449 1834 144 449 1835 145 450 1836 147 450 1837 146 450 1838 147 451 1839 149 451 1840 148 451 1841 149 452 1842 151 452 1843 150 452 1844 151 308 1845 153 308 1846 152 308 1847 153 309 1848 155 309 1849 154 309 1850 155 453 1851 157 453 1852 156 453 1853 157 80 1854 159 80 1855 158 80 1856 159 454 1857 161 454 1858 160 454 1859 161 455 1860 163 455 1861 162 455 1862 163 83 1863 165 83 1864 164 83 1865 165 456 1866 167 456 1867 166 456 1868 167 316 1869 169 316 1870 168 316 1871 169 457 1872 171 457 1873 170 457 1874 171 458 1875 173 458 1876 172 458 1877 173 459 1878 175 459 1879 174 459 1880 175 460 1881 177 460 1882 176 460 1883 177 461 1884 179 461 1885 178 461 1886 179 91 1887 181 91 1888 180 91 1889 181 462 1890 183 462 1891 182 462 1892 183 463 1893 185 463 1894 184 463 1895 185 94 1896 187 94 1897 186 94 1898 187 95 1899 189 95 1900 188 95 1901 69 4 1902 67 4 1903 65 4 1904 65 4 1905 191 4 1906 69 4 1907 191 4 1908 189 4 1909 69 4 1910 189 464 1911 187 464 1912 185 464 1913 185 4 1914 183 4 1915 181 4 1916 181 465 1917 179 465 1918 177 465 1919 177 4 1920 175 4 1921 173 4 1922 173 4 1923 171 4 1924 169 4 1925 169 4 1926 167 4 1927 165 4 1928 165 466 1929 163 466 1930 161 466 1931 161 4 1932 159 4 1933 165 4 1934 159 4 1935 157 4 1936 165 4 1937 157 4 1938 155 4 1939 153 4 1940 153 4 1941 151 4 1942 149 4 1943 149 4 1944 147 4 1945 145 4 1946 145 465 1947 143 465 1948 141 465 1949 141 4 1950 139 4 1951 137 4 1952 137 464 1953 135 464 1954 133 464 1955 133 4 1956 131 4 1957 125 4 1958 131 4 1959 129 4 1960 125 4 1961 129 4 1962 127 4 1963 125 4 1964 125 467 1965 123 467 1966 121 467 1967 121 4 1968 119 4 1969 117 4 1970 117 468 1971 115 468 1972 113 468 1973 113 4 1974 111 4 1975 109 4 1976 109 4 1977 107 4 1978 105 4 1979 105 4 1980 103 4 1981 101 4 1982 101 469 1983 99 469 1984 97 469 1985 97 4 1986 95 4 1987 101 4 1988 95 4 1989 93 4 1990 101 4 1991 93 4 1992 91 4 1993 89 4 1994 89 4 1995 87 4 1996 85 4 1997 85 4 1998 83 4 1999 81 4 2000 81 468 2001 79 468 2002 77 468 2003 77 4 2004 75 4 2005 73 4 2006 73 467 2007 71 467 2008 69 467 2009 189 4 2010 185 4 2011 181 4 2012 181 4 2013 177 4 2014 173 4 2015 173 4 2016 169 4 2017 165 4 2018 157 470 2019 153 470 2020 149 470 2021 149 4 2022 145 4 2023 141 4 2024 141 471 2025 137 471 2026 133 471 2027 125 4 2028 121 4 2029 117 4 2030 117 4 2031 113 4 2032 109 4 2033 109 4 2034 105 4 2035 101 4 2036 93 472 2037 89 472 2038 85 472 2039 85 4 2040 81 4 2041 77 4 2042 77 473 2043 73 473 2044 69 473 2045 69 4 2046 189 4 2047 181 4 2048 181 4 2049 173 4 2050 165 4 2051 165 474 2052 157 474 2053 149 474 2054 149 4 2055 141 4 2056 133 4 2057 133 4 2058 125 4 2059 117 4 2060 117 4 2061 109 4 2062 101 4 2063 101 475 2064 93 475 2065 85 475 2066 85 4 2067 77 4 2068 69 4 2069 69 476 2070 181 476 2071 165 476 2072 165 4 2073 149 4 2074 69 4 2075 149 4 2076 133 4 2077 69 4 2078 133 477 2079 117 477 2080 101 477 2081 101 4 2082 85 4 2083 133 4 2084 189 96 2085 191 96 2086 190 96 2087 191 478 2088 65 478 2089 64 478 2090 190 0 2091 64 0 2092 66 0 2093 66 479 2094 68 479 2095 70 479 2096 70 480 2097 72 480 2098 74 480 2099 74 0 2100 76 0 2101 70 0 2102 76 0 2103 78 0 2104 70 0 2105 78 481 2106 80 481 2107 82 481 2108 82 0 2109 84 0 2110 78 0 2111 84 482 2112 86 482 2113 78 482 2114 86 483 2115 88 483 2116 94 483 2117 88 484 2118 90 484 2119 94 484 2120 90 0 2121 92 0 2122 94 0 2123 94 0 2124 96 0 2125 98 0 2126 98 0 2127 100 0 2128 102 0 2129 102 485 2130 104 485 2131 106 485 2132 106 0 2133 108 0 2134 102 0 2135 108 486 2136 110 486 2137 102 486 2138 110 487 2139 112 487 2140 114 487 2141 114 0 2142 116 0 2143 110 0 2144 116 0 2145 118 0 2146 110 0 2147 118 0 2148 120 0 2149 126 0 2150 120 488 2151 122 488 2152 126 488 2153 122 479 2154 124 479 2155 126 479 2156 126 0 2157 128 0 2158 130 0 2159 130 489 2160 132 489 2161 134 489 2162 134 490 2163 136 490 2164 138 490 2165 138 0 2166 140 0 2167 134 0 2168 140 0 2169 142 0 2170 134 0 2171 142 491 2172 144 491 2173 146 491 2174 146 0 2175 148 0 2176 142 0 2177 148 492 2178 150 492 2179 142 492 2180 150 493 2181 152 493 2182 158 493 2183 152 494 2184 154 494 2185 158 494 2186 154 0 2187 156 0 2188 158 0 2189 158 0 2190 160 0 2191 162 0 2192 162 0 2193 164 0 2194 166 0 2195 166 495 2196 168 495 2197 170 495 2198 170 0 2199 172 0 2200 166 0 2201 172 496 2202 174 496 2203 166 496 2204 174 497 2205 176 497 2206 178 497 2207 178 0 2208 180 0 2209 174 0 2210 180 0 2211 182 0 2212 174 0 2213 182 0 2214 184 0 2215 190 0 2216 184 498 2217 186 498 2218 190 498 2219 186 489 2220 188 489 2221 190 489 2222 190 0 2223 66 0 2224 78 0 2225 66 0 2226 70 0 2227 78 0 2228 94 0 2229 98 0 2230 110 0 2231 98 499 2232 102 499 2233 110 499 2234 126 0 2235 130 0 2236 142 0 2237 130 0 2238 134 0 2239 142 0 2240 158 0 2241 162 0 2242 174 0 2243 162 500 2244 166 500 2245 174 500 2246 78 501 2247 86 501 2248 94 501 2249 110 502 2250 118 502 2251 126 502 2252 142 503 2253 150 503 2254 158 503 2255 174 504 2256 182 504 2257 190 504 2258 190 0 2259 78 0 2260 94 0 2261 94 505 2262 110 505 2263 126 505 2264 126 0 2265 142 0 2266 158 0 2267 158 506 2268 174 506 2269 190 506 2270 190 507 2271 94 507 2272 126 507 2273 644 0 4164 643 0 4165 640 0 4166 642 261 4167 647 261 4168 641 261 4169 645 262 4170 642 262 4171 640 262 4172 646 263 4173 645 263 4174 643 263 4175 647 4 4176 642 4 4177 645 4 4178 647 264 4179 646 264 4180 644 264 4181 657 765 4200 659 765 4201 658 765 4202 659 766 4203 661 766 4204 660 766 4205 661 267 4206 663 267 4207 662 267 4208 663 767 4209 665 767 4210 664 767 4211 665 768 4212 667 768 4213 666 768 4214 667 769 4215 669 769 4216 668 769 4217 669 770 4218 671 770 4219 670 770 4220 671 771 4221 673 771 4222 672 771 4223 673 772 4224 675 772 4225 674 772 4226 675 773 4227 677 773 4228 676 773 4229 677 774 4230 679 774 4231 678 774 4232 679 775 4233 681 775 4234 680 775 4235 681 776 4236 683 776 4237 682 776 4238 683 777 4239 685 777 4240 684 777 4241 685 778 4242 687 778 4243 686 778 4244 687 280 4245 689 280 4246 688 280 4247 689 281 4248 691 281 4249 690 281 4250 691 779 4251 693 779 4252 692 779 4253 693 780 4254 695 780 4255 694 780 4256 695 781 4257 697 781 4258 696 781 4259 697 54 4260 699 54 4261 698 54 4262 699 782 4263 701 782 4264 700 782 4265 701 783 4266 703 783 4267 702 783 4268 703 784 4269 705 784 4270 704 784 4271 705 785 4272 707 785 4273 706 785 4274 707 786 4275 709 786 4276 708 786 4277 709 787 4278 711 787 4279 710 787 4280 711 788 4281 713 788 4282 712 788 4283 713 789 4284 715 789 4285 714 789 4286 715 294 4287 717 294 4288 716 294 4289 717 790 4290 719 790 4291 718 790 4292 719 791 4293 721 791 4294 720 791 4295 721 792 4296 723 792 4297 722 792 4298 723 793 4299 725 793 4300 724 793 4301 725 794 4302 727 794 4303 726 794 4304 727 795 4305 729 795 4306 728 795 4307 729 301 4308 731 301 4309 730 301 4310 731 796 4311 733 796 4312 732 796 4313 733 797 4314 735 797 4315 734 797 4316 735 798 4317 737 798 4318 736 798 4319 737 799 4320 739 799 4321 738 799 4322 739 800 4323 741 800 4324 740 800 4325 741 801 4326 743 801 4327 742 801 4328 743 802 4329 745 802 4330 744 802 4331 745 803 4332 747 803 4333 746 803 4334 747 804 4335 749 804 4336 748 804 4337 749 805 4338 751 805 4339 750 805 4340 751 312 4341 753 312 4342 752 312 4343 753 313 4344 755 313 4345 754 313 4346 755 806 4347 757 806 4348 756 806 4349 757 807 4350 759 807 4351 758 807 4352 759 808 4353 761 808 4354 760 808 4355 761 86 4356 763 86 4357 762 86 4358 763 809 4359 765 809 4360 764 809 4361 765 810 4362 767 810 4363 766 810 4364 767 811 4365 769 811 4366 768 811 4367 769 812 4368 771 812 4369 770 812 4370 771 813 4371 773 813 4372 772 813 4373 773 814 4374 775 814 4375 774 814 4376 775 324 4377 777 324 4378 776 324 4379 777 815 4380 779 815 4381 778 815 4382 779 816 4383 781 816 4384 780 816 4385 661 4 4386 659 4 4387 781 4 4388 659 4 4389 657 4 4390 781 4 4391 657 4 4392 783 4 4393 781 4 4394 781 4 4395 779 4 4396 777 4 4397 777 4 4398 775 4 4399 773 4 4400 773 817 4401 771 817 4402 769 817 4403 769 4 4404 767 4 4405 765 4 4406 765 818 4407 763 818 4408 761 818 4409 761 819 4410 759 819 4411 757 819 4412 757 820 4413 755 820 4414 753 820 4415 753 821 4416 751 821 4417 757 821 4418 751 4 4419 749 4 4420 757 4 4421 749 822 4422 747 822 4423 745 822 4424 745 818 4425 743 818 4426 741 818 4427 741 4 4428 739 4 4429 737 4 4430 737 817 4431 735 817 4432 733 817 4433 733 4 4434 731 4 4435 729 4 4436 729 4 4437 727 4 4438 725 4 4439 725 4 4440 723 4 4441 717 4 4442 723 4 4443 721 4 4444 717 4 4445 721 4 4446 719 4 4447 717 4 4448 717 4 4449 715 4 4450 713 4 4451 713 4 4452 711 4 4453 709 4 4454 709 823 4455 707 823 4456 705 823 4457 705 4 4458 703 4 4459 701 4 4460 701 824 4461 699 824 4462 697 824 4463 697 825 4464 695 825 4465 693 825 4466 693 826 4467 691 826 4468 689 826 4469 689 827 4470 687 827 4471 693 827 4472 687 4 4473 685 4 4474 693 4 4475 685 828 4476 683 828 4477 681 828 4478 681 824 4479 679 824 4480 677 824 4481 677 4 4482 675 4 4483 673 4 4484 673 823 4485 671 823 4486 669 823 4487 669 4 4488 667 4 4489 665 4 4490 665 4 4491 663 4 4492 661 4 4493 781 4 4494 777 4 4495 661 4 4496 777 4 4497 773 4 4498 661 4 4499 773 4 4500 769 4 4501 765 4 4502 765 4 4503 761 4 4504 773 4 4505 761 4 4506 757 4 4507 773 4 4508 749 4 4509 745 4 4510 757 4 4511 745 4 4512 741 4 4513 757 4 4514 741 4 4515 737 4 4516 733 4 4517 733 829 4518 729 829 4519 725 829 4520 717 4 4521 713 4 4522 725 4 4523 713 4 4524 709 4 4525 725 4 4526 709 4 4527 705 4 4528 701 4 4529 701 4 4530 697 4 4531 709 4 4532 697 4 4533 693 4 4534 709 4 4535 685 4 4536 681 4 4537 693 4 4538 681 4 4539 677 4 4540 693 4 4541 677 4 4542 673 4 4543 669 4 4544 669 830 4545 665 830 4546 661 830 4547 741 4 4548 733 4 4549 757 4 4550 733 4 4551 725 4 4552 757 4 4553 677 4 4554 669 4 4555 693 4 4556 669 4 4557 661 4 4558 693 4 4559 661 4 4560 773 4 4561 725 4 4562 773 4 4563 757 4 4564 725 4 4565 725 4 4566 709 4 4567 661 4 4568 781 831 4569 783 831 4570 782 831 4571 783 832 4572 657 832 4573 656 832 4574 782 0 4575 656 0 4576 658 0 4577 658 0 4578 660 0 4579 662 0 4580 662 0 4581 664 0 4582 666 0 4583 666 0 4584 668 0 4585 670 0 4586 670 0 4587 672 0 4588 674 0 4589 674 0 4590 676 0 4591 670 0 4592 676 833 4593 678 833 4594 670 833 4595 678 834 4596 680 834 4597 686 834 4598 680 835 4599 682 835 4600 686 835 4601 682 0 4602 684 0 4603 686 0 4604 686 0 4605 688 0 4606 690 0 4607 690 0 4608 692 0 4609 694 0 4610 694 0 4611 696 0 4612 698 0 4613 698 836 4614 700 836 4615 702 836 4616 702 0 4617 704 0 4618 706 0 4619 706 0 4620 708 0 4621 702 0 4622 708 837 4623 710 837 4624 702 837 4625 710 838 4626 712 838 4627 718 838 4628 712 839 4629 714 839 4630 718 839 4631 714 840 4632 716 840 4633 718 840 4634 718 0 4635 720 0 4636 722 0 4637 722 0 4638 724 0 4639 726 0 4640 726 0 4641 728 0 4642 734 0 4643 728 0 4644 730 0 4645 734 0 4646 730 0 4647 732 0 4648 734 0 4649 734 0 4650 736 0 4651 738 0 4652 738 0 4653 740 0 4654 734 0 4655 740 841 4656 742 841 4657 734 841 4658 742 842 4659 744 842 4660 750 842 4661 744 843 4662 746 843 4663 750 843 4664 746 0 4665 748 0 4666 750 0 4667 750 0 4668 752 0 4669 754 0 4670 754 0 4671 756 0 4672 758 0 4673 758 0 4674 760 0 4675 762 0 4676 762 844 4677 764 844 4678 766 844 4679 766 0 4680 768 0 4681 770 0 4682 770 0 4683 772 0 4684 766 0 4685 772 845 4686 774 845 4687 766 845 4688 774 846 4689 776 846 4690 782 846 4691 776 847 4692 778 847 4693 782 847 4694 778 848 4695 780 848 4696 782 848 4697 782 0 4698 658 0 4699 662 0 4700 662 849 4701 666 849 4702 782 849 4703 666 0 4704 670 0 4705 782 0 4706 686 850 4707 690 850 4708 694 850 4709 694 851 4710 698 851 4711 686 851 4712 698 852 4713 702 852 4714 686 852 4715 718 0 4716 722 0 4717 734 0 4718 722 0 4719 726 0 4720 734 0 4721 750 853 4722 754 853 4723 758 853 4724 758 854 4725 762 854 4726 750 854 4727 762 855 4728 766 855 4729 750 855 4730 670 0 4731 678 0 4732 686 0 4733 702 856 4734 710 856 4735 718 856 4736 734 0 4737 742 0 4738 750 0 4739 766 857 4740 774 857 4741 782 857 4742 782 0 4743 670 0 4744 686 0 4745 686 858 4746 702 858 4747 782 858 4748 702 859 4749 718 859 4750 782 859 4751 718 0 4752 734 0 4753 750 0 4754 750 860 4755 766 860 4756 718 860 4757

-
- - - - -

35 0 0 19 0 1 3 0 2 2 1 3 1 1 4 0 1 5 5 2 6 0 2 7 3 2 8 6 3 9 3 3 10 4 3 11 62 4 12 14 4 13 30 4 14 7 5 15 4 5 16 9 5 17 8 6 18 9 6 19 10 6 20 13 7 21 10 7 22 11 7 23 14 8 24 11 8 25 12 8 26 15 9 27 12 9 28 17 9 29 16 10 30 17 10 31 18 10 32 21 11 33 18 11 34 19 11 35 22 12 36 19 12 37 20 12 38 23 13 39 20 13 40 25 13 41 24 14 42 25 14 43 26 14 44 29 15 45 26 15 46 27 15 47 30 16 48 27 16 49 28 16 50 31 17 51 28 17 52 33 17 53 32 18 54 33 18 55 34 18 56 37 19 57 34 19 58 35 19 59 38 20 60 35 20 61 36 20 62 39 21 63 36 21 64 41 21 65 40 22 66 41 22 67 42 22 68 45 23 69 42 23 70 43 23 71 46 24 72 43 24 73 44 24 74 47 25 75 44 25 76 49 25 77 48 26 78 49 26 79 50 26 80 53 27 81 50 27 82 51 27 83 54 28 84 51 28 85 52 28 86 55 29 87 52 29 88 57 29 89 56 30 90 57 30 91 58 30 92 61 31 93 58 31 94 59 31 95 62 32 96 59 32 97 60 32 98 63 33 99 60 33 100 1 33 101 211 0 300 203 0 301 195 0 302 194 99 303 193 99 304 192 99 305 197 100 306 192 100 307 195 100 308 198 101 309 195 101 310 196 101 311 222 4 312 238 4 313 254 4 314 199 102 315 196 102 316 201 102 317 200 103 318 201 103 319 202 103 320 205 104 321 202 104 322 203 104 323 206 105 324 203 105 325 204 105 326 207 106 327 204 106 328 209 106 329 208 107 330 209 107 331 210 107 332 213 108 333 210 108 334 211 108 335 214 109 336 211 109 337 212 109 338 215 110 339 212 110 340 217 110 341 216 111 342 217 111 343 218 111 344 221 112 345 218 112 346 219 112 347 222 113 348 219 113 349 220 113 350 223 114 351 220 114 352 225 114 353 224 115 354 225 115 355 226 115 356 229 116 357 226 116 358 227 116 359 230 117 360 227 117 361 228 117 362 231 118 363 228 118 364 233 118 365 232 119 366 233 119 367 234 119 368 237 120 369 234 120 370 235 120 371 238 121 372 235 121 373 236 121 374 239 122 375 236 122 376 241 122 377 240 123 378 241 123 379 242 123 380 245 124 381 242 124 382 243 124 383 246 125 384 243 125 385 244 125 386 247 126 387 244 126 388 249 126 389 248 127 390 249 127 391 250 127 392 253 31 393 250 31 394 251 31 395 254 128 396 251 128 397 252 128 398 255 129 399 252 129 400 193 129 401 275 130 402 267 130 403 259 130 404 258 131 405 257 131 406 256 131 407 261 132 408 256 132 409 259 132 410 262 133 411 259 133 412 260 133 413 286 4 414 302 4 415 318 4 416 263 134 417 260 134 418 265 134 419 264 135 420 265 135 421 266 135 422 269 136 423 266 136 424 267 136 425 270 137 426 267 137 427 268 137 428 271 138 429 268 138 430 273 138 431 272 139 432 273 139 433 274 139 434 277 140 435 274 140 436 275 140 437 278 141 438 275 141 439 276 141 440 279 142 441 276 142 442 281 142 443 280 143 444 281 143 445 282 143 446 285 144 447 282 144 448 283 144 449 286 145 450 283 145 451 284 145 452 287 146 453 284 146 454 289 146 455 288 147 456 289 147 457 290 147 458 293 148 459 290 148 460 291 148 461 294 149 462 291 149 463 292 149 464 295 150 465 292 150 466 297 150 467 296 151 468 297 151 469 298 151 470 301 152 471 298 152 472 299 152 473 302 153 474 299 153 475 300 153 476 303 154 477 300 154 478 305 154 479 304 155 480 305 155 481 306 155 482 309 156 483 306 156 484 307 156 485 310 157 486 307 157 487 308 157 488 311 158 489 308 158 490 313 158 491 312 159 492 313 159 493 314 159 494 317 160 495 314 160 496 315 160 497 318 161 498 315 161 499 316 161 500 319 162 501 316 162 502 257 162 503 355 0 504 339 0 505 323 0 506 322 163 507 321 163 508 320 163 509 325 164 510 320 164 511 323 164 512 326 165 513 323 165 514 324 165 515 334 166 516 350 166 517 366 166 518 327 102 519 324 102 520 329 102 521 328 6 522 329 6 523 330 6 524 333 167 525 330 167 526 331 167 527 334 8 528 331 8 529 332 8 530 335 168 531 332 168 532 337 168 533 336 169 534 337 169 535 338 169 536 341 108 537 338 108 538 339 108 539 342 170 540 339 170 541 340 170 542 343 13 543 340 13 544 345 13 545 344 14 546 345 14 547 346 14 548 349 171 549 346 171 550 347 171 551 350 113 552 347 113 553 348 113 554 351 172 555 348 172 556 353 172 557 352 115 558 353 115 559 354 115 560 357 173 561 354 173 562 355 173 563 358 117 564 355 117 565 356 117 566 359 174 567 356 174 568 361 174 569 360 119 570 361 119 571 362 119 572 365 23 573 362 23 574 363 23 575 366 24 576 363 24 577 364 24 578 367 175 579 364 175 580 369 175 581 368 176 582 369 176 583 370 176 584 373 124 585 370 124 586 371 124 587 374 177 588 371 177 589 372 177 590 375 29 591 372 29 592 377 29 593 376 178 594 377 178 595 378 178 596 381 31 597 378 31 598 379 31 599 382 179 600 379 179 601 380 179 602 383 180 603 380 180 604 321 180 605 435 181 606 419 181 607 403 181 608 386 131 609 385 131 610 384 131 611 389 132 612 384 132 613 387 132 614 390 133 615 387 133 616 388 133 617 398 4 618 414 4 619 430 4 620 391 182 621 388 182 622 393 182 623 392 183 624 393 183 625 394 183 626 397 184 627 394 184 628 395 184 629 398 137 630 395 137 631 396 137 632 399 185 633 396 185 634 401 185 635 400 186 636 401 186 637 402 186 638 405 187 639 402 187 640 403 187 641 406 188 642 403 188 643 404 188 644 407 142 645 404 142 646 409 142 647 408 189 648 409 189 649 410 189 650 413 190 651 410 190 652 411 190 653 414 191 654 411 191 655 412 191 656 415 146 657 412 146 658 417 146 659 416 147 660 417 147 661 418 147 662 421 148 663 418 148 664 419 148 665 422 149 666 419 149 667 420 149 668 423 150 669 420 150 670 425 150 671 424 192 672 425 192 673 426 192 674 429 152 675 426 152 676 427 152 677 430 153 678 427 153 679 428 153 680 431 193 681 428 193 682 433 193 683 432 155 684 433 155 685 434 155 686 437 194 687 434 194 688 435 194 689 438 195 690 435 195 691 436 195 692 439 158 693 436 158 694 441 158 695 440 159 696 441 159 697 442 159 698 445 196 699 442 196 700 443 196 701 446 161 702 443 161 703 444 161 704 447 162 705 444 162 706 385 162 707 499 197 708 483 197 709 467 197 710 450 198 711 449 198 712 448 198 713 453 199 714 448 199 715 451 199 716 454 200 717 451 200 718 452 200 719 478 4 720 494 4 721 510 4 722 455 201 723 452 201 724 457 201 725 456 202 726 457 202 727 458 202 728 461 203 729 458 203 730 459 203 731 462 204 732 459 204 733 460 204 734 463 205 735 460 205 736 465 205 737 464 206 738 465 206 739 466 206 740 469 207 741 466 207 742 467 207 743 470 188 744 467 188 745 468 188 746 471 208 747 468 208 748 473 208 749 472 209 750 473 209 751 474 209 752 477 210 753 474 210 754 475 210 755 478 211 756 475 211 757 476 211 758 479 212 759 476 212 760 481 212 761 480 213 762 481 213 763 482 213 764 485 214 765 482 214 766 483 214 767 486 215 768 483 215 769 484 215 770 487 216 771 484 216 772 489 216 773 488 217 774 489 217 775 490 217 776 493 218 777 490 218 778 491 218 779 494 219 780 491 219 781 492 219 782 495 193 783 492 193 784 497 193 785 496 220 786 497 220 787 498 220 788 501 221 789 498 221 790 499 221 791 502 222 792 499 222 793 500 222 794 503 223 795 500 223 796 505 223 797 504 224 798 505 224 799 506 224 800 509 225 801 506 225 802 507 225 803 510 226 804 507 226 805 508 226 806 511 227 807 508 227 808 449 227 809 515 0 810 563 0 811 547 0 812 514 228 813 513 228 814 512 228 815 517 229 816 512 229 817 515 229 818 518 230 819 515 230 820 516 230 821 526 4 822 542 4 823 558 4 824 519 5 825 516 5 826 521 5 827 520 103 828 521 103 829 522 103 830 525 231 831 522 231 832 523 231 833 526 232 834 523 232 835 524 232 836 527 233 837 524 233 838 529 233 839 528 234 840 529 234 841 530 234 842 533 11 843 530 11 844 531 11 845 534 235 846 531 235 847 532 235 848 535 110 849 532 110 850 537 110 851 536 111 852 537 111 853 538 111 854 541 236 855 538 236 856 539 236 857 542 16 858 539 16 859 540 16 860 543 237 861 540 237 862 545 237 863 544 18 864 545 18 865 546 18 866 549 238 867 546 238 868 547 238 869 550 20 870 547 20 871 548 20 872 551 239 873 548 239 874 553 239 875 552 22 876 553 22 877 554 22 878 557 120 879 554 120 880 555 120 881 558 121 882 555 121 883 556 121 884 559 240 885 556 240 886 561 240 887 560 241 888 561 241 889 562 241 890 565 27 891 562 27 892 563 27 893 566 242 894 563 242 895 564 242 896 567 243 897 564 243 898 569 243 899 568 244 900 569 244 901 570 244 902 573 31 903 570 31 904 571 31 905 574 245 906 571 245 907 572 245 908 575 246 909 572 246 910 513 246 911 587 0 912 579 0 913 611 0 914 578 198 915 577 198 916 576 198 917 581 199 918 576 199 919 579 199 920 582 200 921 579 200 922 580 200 923 622 247 924 630 247 925 638 247 926 583 248 927 580 248 928 585 248 929 584 249 930 585 249 931 586 249 932 589 250 933 586 250 934 587 250 935 590 204 936 587 204 937 588 204 938 591 251 939 588 251 940 593 251 941 592 252 942 593 252 943 594 252 944 597 253 945 594 253 946 595 253 947 598 141 948 595 141 949 596 141 950 599 208 951 596 208 952 601 208 953 600 254 954 601 254 955 602 254 956 605 255 957 602 255 958 603 255 959 606 256 960 603 256 961 604 256 962 607 212 963 604 212 964 609 212 965 608 213 966 609 213 967 610 213 968 613 214 969 610 214 970 611 214 971 614 215 972 611 215 973 612 215 974 615 216 975 612 216 976 617 216 977 616 257 978 617 257 979 618 257 980 621 218 981 618 218 982 619 218 983 622 219 984 619 219 985 620 219 986 623 154 987 620 154 988 625 154 989 624 220 990 625 220 991 626 220 992 629 258 993 626 258 994 627 258 995 630 259 996 627 259 997 628 259 998 631 223 999 628 223 1000 633 223 1001 632 224 1002 633 224 1003 634 224 1004 637 260 1005 634 260 1006 635 260 1007 638 226 1008 635 226 1009 636 226 1010 639 227 1011 636 227 1012 577 227 1013 3 0 1446 0 0 1447 1 0 1448 1 0 1449 60 0 1450 59 0 1451 59 394 1452 58 394 1453 57 394 1454 57 0 1455 52 0 1456 59 0 1457 52 0 1458 51 0 1459 59 0 1460 51 0 1461 50 0 1462 49 0 1463 49 395 1464 44 395 1465 51 395 1466 44 396 1467 43 396 1468 51 396 1469 43 0 1470 42 0 1471 41 0 1472 41 397 1473 36 397 1474 35 397 1475 35 0 1476 34 0 1477 27 0 1478 34 0 1479 33 0 1480 27 0 1481 33 398 1482 28 398 1483 27 398 1484 27 0 1485 26 0 1486 25 0 1487 25 399 1488 20 399 1489 19 399 1490 19 0 1491 18 0 1492 17 0 1493 17 0 1494 12 0 1495 11 0 1496 11 400 1497 10 400 1498 3 400 1499 10 0 1500 9 0 1501 3 0 1502 9 0 1503 4 0 1504 3 0 1505 3 0 1506 1 0 1507 51 0 1508 1 0 1509 59 0 1510 51 0 1511 43 0 1512 41 0 1513 51 0 1514 41 0 1515 35 0 1516 51 0 1517 27 0 1518 25 0 1519 35 0 1520 25 0 1521 19 0 1522 35 0 1523 19 0 1524 17 0 1525 3 0 1526 17 401 1527 11 401 1528 3 401 1529 3 0 1530 51 0 1531 35 0 1532 2 402 1533 63 402 1534 1 402 1535 5 403 1536 2 403 1537 0 403 1538 6 404 1539 5 404 1540 3 404 1541 62 4 1542 63 4 1543 6 4 1544 63 4 1545 2 4 1546 6 4 1547 2 4 1548 5 4 1549 6 4 1550 6 405 1551 7 405 1552 8 405 1553 8 405 1554 13 405 1555 14 405 1556 14 4 1557 15 4 1558 16 4 1559 16 406 1560 21 406 1561 22 406 1562 22 4 1563 23 4 1564 30 4 1565 23 407 1566 24 407 1567 30 407 1568 24 4 1569 29 4 1570 30 4 1571 30 408 1572 31 408 1573 32 408 1574 32 409 1575 37 409 1576 38 409 1577 38 4 1578 39 4 1579 46 4 1580 39 4 1581 40 4 1582 46 4 1583 40 4 1584 45 4 1585 46 4 1586 46 410 1587 47 410 1588 48 410 1589 48 4 1590 53 4 1591 54 4 1592 54 411 1593 55 411 1594 56 411 1595 56 412 1596 61 412 1597 54 412 1598 61 4 1599 62 4 1600 54 4 1601 6 4 1602 8 4 1603 62 4 1604 8 4 1605 14 4 1606 62 4 1607 14 4 1608 16 4 1609 30 4 1610 16 4 1611 22 4 1612 30 4 1613 30 4 1614 32 4 1615 46 4 1616 32 4 1617 38 4 1618 46 4 1619 46 4 1620 48 4 1621 54 4 1622 46 4 1623 54 4 1624 30 4 1625 54 4 1626 62 4 1627 30 4 1628 7 5 1629 6 5 1630 4 5 1631 8 413 1632 7 413 1633 9 413 1634 13 7 1635 8 7 1636 10 7 1637 14 414 1638 13 414 1639 11 414 1640 15 9 1641 14 9 1642 12 9 1643 16 415 1644 15 415 1645 17 415 1646 21 416 1647 16 416 1648 18 416 1649 22 12 1650 21 12 1651 19 12 1652 23 417 1653 22 417 1654 20 417 1655 24 14 1656 23 14 1657 25 14 1658 29 418 1659 24 418 1660 26 418 1661 30 16 1662 29 16 1663 27 16 1664 31 17 1665 30 17 1666 28 17 1667 32 18 1668 31 18 1669 33 18 1670 37 19 1671 32 19 1672 34 19 1673 38 419 1674 37 419 1675 35 419 1676 39 21 1677 38 21 1678 36 21 1679 40 420 1680 39 420 1681 41 420 1682 45 120 1683 40 120 1684 42 120 1685 46 421 1686 45 421 1687 43 421 1688 47 25 1689 46 25 1690 44 25 1691 48 422 1692 47 422 1693 49 422 1694 53 423 1695 48 423 1696 50 423 1697 54 28 1698 53 28 1699 51 28 1700 55 424 1701 54 424 1702 52 424 1703 56 244 1704 55 244 1705 57 244 1706 61 425 1707 56 425 1708 58 425 1709 62 32 1710 61 32 1711 59 32 1712 63 426 1713 62 426 1714 60 426 1715 195 508 2274 192 508 2275 251 508 2276 192 509 2277 193 509 2278 251 509 2279 193 510 2280 252 510 2281 251 510 2282 251 0 2283 250 0 2284 243 0 2285 250 0 2286 249 0 2287 243 0 2288 249 511 2289 244 511 2290 243 511 2291 243 0 2292 242 0 2293 235 0 2294 242 0 2295 241 0 2296 235 0 2297 241 512 2298 236 512 2299 235 512 2300 235 0 2301 234 0 2302 233 0 2303 233 0 2304 228 0 2305 227 0 2306 227 513 2307 226 513 2308 219 513 2309 226 514 2310 225 514 2311 219 514 2312 225 0 2313 220 0 2314 219 0 2315 219 0 2316 218 0 2317 217 0 2318 217 0 2319 212 0 2320 219 0 2321 212 515 2322 211 515 2323 219 515 2324 211 0 2325 210 0 2326 209 0 2327 209 0 2328 204 0 2329 211 0 2330 204 516 2331 203 516 2332 211 516 2333 203 0 2334 202 0 2335 201 0 2336 201 0 2337 196 0 2338 203 0 2339 196 0 2340 195 0 2341 203 0 2342 235 0 2343 233 0 2344 243 0 2345 233 0 2346 227 0 2347 243 0 2348 195 517 2349 251 517 2350 227 517 2351 251 518 2352 243 518 2353 227 518 2354 227 519 2355 219 519 2356 195 519 2357 219 0 2358 211 0 2359 195 0 2360 194 520 2361 255 520 2362 193 520 2363 197 521 2364 194 521 2365 192 521 2366 198 522 2367 197 522 2368 195 522 2369 254 523 2370 255 523 2371 194 523 2372 194 4 2373 197 4 2374 198 4 2375 198 4 2376 199 4 2377 200 4 2378 200 524 2379 205 524 2380 206 524 2381 206 4 2382 207 4 2383 208 4 2384 208 525 2385 213 525 2386 214 525 2387 214 4 2388 215 4 2389 216 4 2390 216 4 2391 221 4 2392 214 4 2393 221 4 2394 222 4 2395 214 4 2396 222 526 2397 223 526 2398 224 526 2399 224 4 2400 229 4 2401 230 4 2402 230 4 2403 231 4 2404 238 4 2405 231 4 2406 232 4 2407 238 4 2408 232 4 2409 237 4 2410 238 4 2411 238 527 2412 239 527 2413 240 527 2414 240 4 2415 245 4 2416 246 4 2417 246 528 2418 247 528 2419 254 528 2420 247 407 2421 248 407 2422 254 407 2423 248 4 2424 253 4 2425 254 4 2426 254 529 2427 194 529 2428 206 529 2429 194 530 2430 198 530 2431 206 530 2432 198 4 2433 200 4 2434 206 4 2435 206 531 2436 208 531 2437 214 531 2438 222 4 2439 224 4 2440 238 4 2441 224 4 2442 230 4 2443 238 4 2444 238 532 2445 240 532 2446 254 532 2447 240 4 2448 246 4 2449 254 4 2450 206 533 2451 214 533 2452 254 533 2453 214 4 2454 222 4 2455 254 4 2456 199 102 2457 198 102 2458 196 102 2459 200 534 2460 199 534 2461 201 534 2462 205 104 2463 200 104 2464 202 104 2465 206 535 2466 205 535 2467 203 535 2468 207 536 2469 206 536 2470 204 536 2471 208 537 2472 207 537 2473 209 537 2474 213 538 2475 208 538 2476 210 538 2477 214 539 2478 213 539 2479 211 539 2480 215 540 2481 214 540 2482 212 540 2483 216 111 2484 215 111 2485 217 111 2486 221 541 2487 216 541 2488 218 541 2489 222 542 2490 221 542 2491 219 542 2492 223 543 2493 222 543 2494 220 543 2495 224 544 2496 223 544 2497 225 544 2498 229 545 2499 224 545 2500 226 545 2501 230 546 2502 229 546 2503 227 546 2504 231 547 2505 230 547 2506 228 547 2507 232 548 2508 231 548 2509 233 548 2510 237 23 2511 232 23 2512 234 23 2513 238 549 2514 237 549 2515 235 549 2516 239 550 2517 238 550 2518 236 550 2519 240 551 2520 239 551 2521 241 551 2522 245 552 2523 240 552 2524 242 552 2525 246 553 2526 245 553 2527 243 553 2528 247 554 2529 246 554 2530 244 554 2531 248 555 2532 247 555 2533 249 555 2534 253 425 2535 248 425 2536 250 425 2537 254 556 2538 253 556 2539 251 556 2540 255 557 2541 254 557 2542 252 557 2543 259 0 2544 256 0 2545 257 0 2546 257 0 2547 316 0 2548 315 0 2549 315 0 2550 314 0 2551 313 0 2552 313 0 2553 308 0 2554 315 0 2555 308 0 2556 307 0 2557 315 0 2558 307 0 2559 306 0 2560 305 0 2561 305 0 2562 300 0 2563 307 0 2564 300 0 2565 299 0 2566 307 0 2567 299 558 2568 298 558 2569 297 558 2570 297 0 2571 292 0 2572 299 0 2573 292 0 2574 291 0 2575 299 0 2576 291 0 2577 290 0 2578 283 0 2579 290 0 2580 289 0 2581 283 0 2582 289 559 2583 284 559 2584 283 559 2585 283 560 2586 282 560 2587 281 560 2588 281 0 2589 276 0 2590 283 0 2591 276 561 2592 275 561 2593 283 561 2594 275 0 2595 274 0 2596 273 0 2597 273 0 2598 268 0 2599 275 0 2600 268 0 2601 267 0 2602 275 0 2603 267 0 2604 266 0 2605 265 0 2606 265 0 2607 260 0 2608 259 0 2609 259 0 2610 257 0 2611 307 0 2612 257 562 2613 315 562 2614 307 562 2615 267 563 2616 265 563 2617 259 563 2618 307 564 2619 299 564 2620 259 564 2621 299 0 2622 291 0 2623 259 0 2624 291 565 2625 283 565 2626 259 565 2627 283 566 2628 275 566 2629 259 566 2630 258 567 2631 319 567 2632 257 567 2633 261 568 2634 258 568 2635 256 568 2636 262 569 2637 261 569 2638 259 569 2639 318 4 2640 319 4 2641 262 4 2642 319 4 2643 258 4 2644 262 4 2645 258 4 2646 261 4 2647 262 4 2648 262 4 2649 263 4 2650 270 4 2651 263 4 2652 264 4 2653 270 4 2654 264 4 2655 269 4 2656 270 4 2657 270 570 2658 271 570 2659 278 570 2660 271 571 2661 272 571 2662 278 571 2663 272 572 2664 277 572 2665 278 572 2666 278 572 2667 279 572 2668 280 572 2669 280 4 2670 285 4 2671 286 4 2672 286 573 2673 287 573 2674 288 573 2675 288 574 2676 293 574 2677 294 574 2678 294 4 2679 295 4 2680 296 4 2681 296 575 2682 301 575 2683 302 575 2684 302 576 2685 303 576 2686 304 576 2687 304 577 2688 309 577 2689 302 577 2690 309 578 2691 310 578 2692 302 578 2693 310 579 2694 311 579 2695 318 579 2696 311 580 2697 312 580 2698 318 580 2699 312 4 2700 317 4 2701 318 4 2702 278 581 2703 280 581 2704 286 581 2705 286 4 2706 288 4 2707 302 4 2708 288 4 2709 294 4 2710 302 4 2711 294 582 2712 296 582 2713 302 582 2714 318 4 2715 262 4 2716 270 4 2717 270 4 2718 278 4 2719 318 4 2720 278 583 2721 286 583 2722 318 583 2723 302 4 2724 310 4 2725 318 4 2726 263 584 2727 262 584 2728 260 584 2729 264 585 2730 263 585 2731 265 585 2732 269 586 2733 264 586 2734 266 586 2735 270 137 2736 269 137 2737 267 137 2738 271 587 2739 270 587 2740 268 587 2741 272 186 2742 271 186 2743 273 186 2744 277 187 2745 272 187 2746 274 187 2747 278 588 2748 277 588 2749 275 588 2750 279 589 2751 278 589 2752 276 589 2753 280 590 2754 279 590 2755 281 590 2756 285 144 2757 280 144 2758 282 144 2759 286 591 2760 285 591 2761 283 591 2762 287 592 2763 286 592 2764 284 592 2765 288 593 2766 287 593 2767 289 593 2768 293 594 2769 288 594 2770 290 594 2771 294 595 2772 293 595 2773 291 595 2774 295 150 2775 294 150 2776 292 150 2777 296 151 2778 295 151 2779 297 151 2780 301 152 2781 296 152 2782 298 152 2783 302 596 2784 301 596 2785 299 596 2786 303 597 2787 302 597 2788 300 597 2789 304 155 2790 303 155 2791 305 155 2792 309 156 2793 304 156 2794 306 156 2795 310 598 2796 309 598 2797 307 598 2798 311 158 2799 310 158 2800 308 158 2801 312 159 2802 311 159 2803 313 159 2804 317 599 2805 312 599 2806 314 599 2807 318 161 2808 317 161 2809 315 161 2810 319 600 2811 318 600 2812 316 600 2813 323 0 2814 320 0 2815 321 0 2816 321 601 2817 380 601 2818 379 601 2819 379 602 2820 378 602 2821 377 602 2822 377 0 2823 372 0 2824 379 0 2825 372 0 2826 371 0 2827 379 0 2828 371 0 2829 370 0 2830 369 0 2831 369 0 2832 364 0 2833 371 0 2834 364 0 2835 363 0 2836 371 0 2837 363 0 2838 362 0 2839 355 0 2840 362 0 2841 361 0 2842 355 0 2843 361 0 2844 356 0 2845 355 0 2846 355 513 2847 354 513 2848 347 513 2849 354 514 2850 353 514 2851 347 514 2852 353 0 2853 348 0 2854 347 0 2855 347 0 2856 346 0 2857 345 0 2858 345 603 2859 340 603 2860 339 603 2861 339 0 2862 338 0 2863 337 0 2864 337 0 2865 332 0 2866 331 0 2867 331 400 2868 330 400 2869 323 400 2870 330 0 2871 329 0 2872 323 0 2873 329 397 2874 324 397 2875 323 397 2876 323 0 2877 321 0 2878 371 0 2879 321 0 2880 379 0 2881 371 0 2882 347 0 2883 345 0 2884 355 0 2885 345 0 2886 339 0 2887 355 0 2888 339 0 2889 337 0 2890 323 0 2891 337 604 2892 331 604 2893 323 604 2894 371 0 2895 363 0 2896 355 0 2897 323 605 2898 371 605 2899 355 605 2900 322 606 2901 383 606 2902 321 606 2903 325 521 2904 322 521 2905 320 521 2906 326 607 2907 325 607 2908 323 607 2909 382 523 2910 383 523 2911 322 523 2912 322 4 2913 325 4 2914 326 4 2915 326 4 2916 327 4 2917 328 4 2918 328 4 2919 333 4 2920 334 4 2921 334 608 2922 335 608 2923 336 608 2924 336 609 2925 341 609 2926 342 609 2927 342 4 2928 343 4 2929 350 4 2930 343 4 2931 344 4 2932 350 4 2933 344 4 2934 349 4 2935 350 4 2936 350 610 2937 351 610 2938 352 610 2939 352 4 2940 357 4 2941 358 4 2942 358 4 2943 359 4 2944 366 4 2945 359 4 2946 360 4 2947 366 4 2948 360 4 2949 365 4 2950 366 4 2951 366 411 2952 367 411 2953 368 411 2954 368 611 2955 373 611 2956 374 611 2957 374 4 2958 375 4 2959 376 4 2960 376 4 2961 381 4 2962 374 4 2963 381 4 2964 382 4 2965 374 4 2966 382 4 2967 322 4 2968 326 4 2969 326 4 2970 328 4 2971 382 4 2972 328 4 2973 334 4 2974 382 4 2975 334 612 2976 336 612 2977 350 612 2978 336 4 2979 342 4 2980 350 4 2981 350 4 2982 352 4 2983 366 4 2984 352 4 2985 358 4 2986 366 4 2987 366 4 2988 368 4 2989 374 4 2990 366 613 2991 374 613 2992 382 613 2993 382 614 2994 334 614 2995 366 614 2996 327 102 2997 326 102 2998 324 102 2999 328 413 3000 327 413 3001 329 413 3002 333 615 3003 328 615 3004 330 615 3005 334 414 3006 333 414 3007 331 414 3008 335 168 3009 334 168 3010 332 168 3011 336 537 3012 335 537 3013 337 537 3014 341 616 3015 336 616 3016 338 616 3017 342 617 3018 341 617 3019 339 617 3020 343 417 3021 342 417 3022 340 417 3023 344 14 3024 343 14 3025 345 14 3026 349 618 3027 344 618 3028 346 618 3029 350 542 3030 349 542 3031 347 542 3032 351 619 3033 350 619 3034 348 619 3035 352 620 3036 351 620 3037 353 620 3038 357 621 3039 352 621 3040 354 621 3041 358 622 3042 357 622 3043 355 622 3044 359 623 3045 358 623 3046 356 623 3047 360 548 3048 359 548 3049 361 548 3050 365 120 3051 360 120 3052 362 120 3053 366 421 3054 365 421 3055 363 421 3056 367 624 3057 366 624 3058 364 624 3059 368 551 3060 367 551 3061 369 551 3062 373 625 3063 368 625 3064 370 625 3065 374 177 3066 373 177 3067 371 177 3068 375 424 3069 374 424 3070 372 424 3071 376 626 3072 375 626 3073 377 626 3074 381 425 3075 376 425 3076 378 425 3077 382 179 3078 381 179 3079 379 179 3080 383 557 3081 382 557 3082 380 557 3083 387 0 3084 384 0 3085 385 0 3086 385 0 3087 444 0 3088 443 0 3089 443 0 3090 442 0 3091 441 0 3092 441 627 3093 436 627 3094 435 627 3095 435 0 3096 434 0 3097 433 0 3098 433 0 3099 428 0 3100 427 0 3101 427 628 3102 426 628 3103 419 628 3104 426 0 3105 425 0 3106 419 0 3107 425 629 3108 420 629 3109 419 629 3110 419 0 3111 418 0 3112 411 0 3113 418 0 3114 417 0 3115 411 0 3116 417 630 3117 412 630 3118 411 630 3119 411 0 3120 410 0 3121 403 0 3122 410 0 3123 409 0 3124 403 0 3125 409 0 3126 404 0 3127 403 0 3128 403 0 3129 402 0 3130 401 0 3131 401 631 3132 396 631 3133 395 631 3134 395 0 3135 394 0 3136 393 0 3137 393 0 3138 388 0 3139 387 0 3140 387 0 3141 385 0 3142 435 0 3143 385 562 3144 443 562 3145 435 562 3146 443 632 3147 441 632 3148 435 632 3149 435 633 3150 433 633 3151 419 633 3152 433 634 3153 427 634 3154 419 634 3155 403 635 3156 401 635 3157 387 635 3158 401 636 3159 395 636 3160 387 636 3161 395 637 3162 393 637 3163 387 637 3164 419 0 3165 411 0 3166 403 0 3167 387 638 3168 435 638 3169 403 638 3170 386 567 3171 447 567 3172 385 567 3173 389 568 3174 386 568 3175 384 568 3176 390 569 3177 389 569 3178 387 569 3179 446 4 3180 447 4 3181 390 4 3182 447 4 3183 386 4 3184 390 4 3185 386 4 3186 389 4 3187 390 4 3188 390 4 3189 391 4 3190 392 4 3191 392 4 3192 397 4 3193 390 4 3194 397 639 3195 398 639 3196 390 639 3197 398 640 3198 399 640 3199 406 640 3200 399 641 3201 400 641 3202 406 641 3203 400 642 3204 405 642 3205 406 642 3206 406 643 3207 407 643 3208 408 643 3209 408 4 3210 413 4 3211 414 4 3212 414 644 3213 415 644 3214 416 644 3215 416 645 3216 421 645 3217 422 645 3218 422 4 3219 423 4 3220 424 4 3221 424 646 3222 429 646 3223 430 646 3224 430 647 3225 431 647 3226 432 647 3227 432 648 3228 437 648 3229 430 648 3230 437 649 3231 438 649 3232 430 649 3233 438 650 3234 439 650 3235 446 650 3236 439 651 3237 440 651 3238 446 651 3239 440 4 3240 445 4 3241 446 4 3242 406 4 3243 408 4 3244 398 4 3245 408 4 3246 414 4 3247 398 4 3248 414 4 3249 416 4 3250 430 4 3251 416 4 3252 422 4 3253 430 4 3254 422 652 3255 424 652 3256 430 652 3257 446 4 3258 390 4 3259 398 4 3260 430 4 3261 438 4 3262 446 4 3263 446 4 3264 398 4 3265 430 4 3266 391 653 3267 390 653 3268 388 653 3269 392 654 3270 391 654 3271 393 654 3272 397 655 3273 392 655 3274 394 655 3275 398 137 3276 397 137 3277 395 137 3278 399 656 3279 398 656 3280 396 656 3281 400 139 3282 399 139 3283 401 139 3284 405 140 3285 400 140 3286 402 140 3287 406 657 3288 405 657 3289 403 657 3290 407 589 3291 406 589 3292 404 589 3293 408 658 3294 407 658 3295 409 658 3296 413 190 3297 408 190 3298 410 190 3299 414 659 3300 413 659 3301 411 659 3302 415 592 3303 414 592 3304 412 592 3305 416 593 3306 415 593 3307 417 593 3308 421 594 3309 416 594 3310 418 594 3311 422 595 3312 421 595 3313 419 595 3314 423 150 3315 422 150 3316 420 150 3317 424 192 3318 423 192 3319 425 192 3320 429 152 3321 424 152 3322 426 152 3323 430 596 3324 429 596 3325 427 596 3326 431 660 3327 430 660 3328 428 660 3329 432 661 3330 431 661 3331 433 661 3332 437 156 3333 432 156 3334 434 156 3335 438 662 3336 437 662 3337 435 662 3338 439 158 3339 438 158 3340 436 158 3341 440 159 3342 439 159 3343 441 159 3344 445 663 3345 440 663 3346 442 663 3347 446 161 3348 445 161 3349 443 161 3350 447 600 3351 446 600 3352 444 600 3353 451 0 3354 448 0 3355 449 0 3356 449 0 3357 508 0 3358 451 0 3359 508 664 3360 507 664 3361 451 664 3362 507 665 3363 506 665 3364 505 665 3365 505 666 3366 500 666 3367 499 666 3368 499 667 3369 498 667 3370 497 667 3371 497 668 3372 492 668 3373 491 668 3374 491 0 3375 490 0 3376 483 0 3377 490 0 3378 489 0 3379 483 0 3380 489 669 3381 484 669 3382 483 669 3383 483 670 3384 482 670 3385 475 670 3386 482 671 3387 481 671 3388 475 671 3389 481 672 3390 476 672 3391 475 672 3392 475 0 3393 474 0 3394 467 0 3395 474 673 3396 473 673 3397 467 673 3398 473 674 3399 468 674 3400 467 674 3401 467 675 3402 466 675 3403 465 675 3404 465 627 3405 460 627 3406 459 627 3407 459 676 3408 458 676 3409 457 676 3410 457 0 3411 452 0 3412 459 0 3413 452 0 3414 451 0 3415 459 0 3416 507 677 3417 505 677 3418 451 677 3419 505 0 3420 499 0 3421 451 0 3422 499 678 3423 497 678 3424 483 678 3425 497 0 3426 491 0 3427 483 0 3428 467 679 3429 465 679 3430 451 679 3431 465 0 3432 459 0 3433 451 0 3434 483 0 3435 475 0 3436 467 0 3437 451 680 3438 499 680 3439 467 680 3440 450 681 3441 511 681 3442 449 681 3443 453 682 3444 450 682 3445 448 682 3446 454 683 3447 453 683 3448 451 683 3449 510 684 3450 511 684 3451 450 684 3452 450 685 3453 453 685 3454 454 685 3455 454 4 3456 455 4 3457 456 4 3458 456 4 3459 461 4 3460 462 4 3461 462 4 3462 463 4 3463 470 4 3464 463 4 3465 464 4 3466 470 4 3467 464 686 3468 469 686 3469 470 686 3470 470 687 3471 471 687 3472 472 687 3473 472 4 3474 477 4 3475 478 4 3476 478 688 3477 479 688 3478 480 688 3479 480 4 3480 485 4 3481 486 4 3482 486 4 3483 487 4 3484 488 4 3485 488 4 3486 493 4 3487 486 4 3488 493 4 3489 494 4 3490 486 4 3491 494 689 3492 495 689 3493 496 689 3494 496 4 3495 501 4 3496 494 4 3497 501 4 3498 502 4 3499 494 4 3500 502 4 3501 503 4 3502 510 4 3503 503 690 3504 504 690 3505 510 690 3506 504 4 3507 509 4 3508 510 4 3509 510 4 3510 450 4 3511 454 4 3512 454 4 3513 456 4 3514 510 4 3515 456 4 3516 462 4 3517 510 4 3518 470 691 3519 472 691 3520 478 691 3521 478 4 3522 480 4 3523 494 4 3524 480 4 3525 486 4 3526 494 4 3527 462 4 3528 470 4 3529 510 4 3530 470 4 3531 478 4 3532 510 4 3533 494 692 3534 502 692 3535 510 692 3536 455 693 3537 454 693 3538 452 693 3539 456 694 3540 455 694 3541 457 694 3542 461 695 3543 456 695 3544 458 695 3545 462 696 3546 461 696 3547 459 696 3548 463 697 3549 462 697 3550 460 697 3551 464 698 3552 463 698 3553 465 698 3554 469 253 3555 464 253 3556 466 253 3557 470 657 3558 469 657 3559 467 657 3560 471 208 3561 470 208 3562 468 208 3563 472 699 3564 471 699 3565 473 699 3566 477 700 3567 472 700 3568 474 700 3569 478 701 3570 477 701 3571 475 701 3572 479 702 3573 478 702 3574 476 702 3575 480 703 3576 479 703 3577 481 703 3578 485 704 3579 480 704 3580 482 704 3581 486 705 3582 485 705 3583 483 705 3584 487 706 3585 486 706 3586 484 706 3587 488 707 3588 487 707 3589 489 707 3590 493 218 3591 488 218 3592 490 218 3593 494 219 3594 493 219 3595 491 219 3596 495 660 3597 494 660 3598 492 660 3599 496 708 3600 495 708 3601 497 708 3602 501 709 3603 496 709 3604 498 709 3605 502 710 3606 501 710 3607 499 710 3608 503 711 3609 502 711 3610 500 711 3611 504 712 3612 503 712 3613 505 712 3614 509 713 3615 504 713 3616 506 713 3617 510 226 3618 509 226 3619 507 226 3620 511 714 3621 510 714 3622 508 714 3623 515 0 3624 512 0 3625 513 0 3626 513 0 3627 572 0 3628 571 0 3629 571 0 3630 570 0 3631 563 0 3632 570 715 3633 569 715 3634 563 715 3635 569 0 3636 564 0 3637 563 0 3638 563 0 3639 562 0 3640 555 0 3641 562 716 3642 561 716 3643 555 716 3644 561 717 3645 556 717 3646 555 717 3647 555 0 3648 554 0 3649 553 0 3650 553 397 3651 548 397 3652 547 397 3653 547 0 3654 546 0 3655 539 0 3656 546 0 3657 545 0 3658 539 0 3659 545 718 3660 540 718 3661 539 718 3662 539 0 3663 538 0 3664 537 0 3665 537 0 3666 532 0 3667 539 0 3668 532 0 3669 531 0 3670 539 0 3671 531 0 3672 530 0 3673 529 0 3674 529 0 3675 524 0 3676 531 0 3677 524 516 3678 523 516 3679 531 516 3680 523 719 3681 522 719 3682 515 719 3683 522 0 3684 521 0 3685 515 0 3686 521 0 3687 516 0 3688 515 0 3689 515 0 3690 513 0 3691 563 0 3692 513 0 3693 571 0 3694 563 0 3695 555 0 3696 553 0 3697 563 0 3698 553 0 3699 547 0 3700 563 0 3701 547 0 3702 539 0 3703 515 0 3704 539 0 3705 531 0 3706 515 0 3707 531 0 3708 523 0 3709 515 0 3710 514 720 3711 575 720 3712 513 720 3713 517 403 3714 514 403 3715 512 403 3716 518 721 3717 517 721 3718 515 721 3719 574 4 3720 575 4 3721 518 4 3722 575 4 3723 514 4 3724 518 4 3725 514 4 3726 517 4 3727 518 4 3728 518 4 3729 519 4 3730 526 4 3731 519 4 3732 520 4 3733 526 4 3734 520 722 3735 525 722 3736 526 722 3737 526 4 3738 527 4 3739 528 4 3740 528 525 3741 533 525 3742 534 525 3743 534 4 3744 535 4 3745 536 4 3746 536 4 3747 541 4 3748 534 4 3749 541 4 3750 542 4 3751 534 4 3752 542 408 3753 543 408 3754 544 408 3755 544 723 3756 549 723 3757 550 723 3758 550 4 3759 551 4 3760 558 4 3761 551 4 3762 552 4 3763 558 4 3764 552 4 3765 557 4 3766 558 4 3767 558 724 3768 559 724 3769 560 724 3770 560 4 3771 565 4 3772 566 4 3773 566 725 3774 567 725 3775 568 725 3776 568 726 3777 573 726 3778 566 726 3779 573 4 3780 574 4 3781 566 4 3782 526 4 3783 528 4 3784 534 4 3785 542 4 3786 544 4 3787 558 4 3788 544 4 3789 550 4 3790 558 4 3791 558 4 3792 560 4 3793 574 4 3794 560 4 3795 566 4 3796 574 4 3797 574 4 3798 518 4 3799 526 4 3800 526 4 3801 534 4 3802 542 4 3803 574 4 3804 526 4 3805 558 4 3806 519 5 3807 518 5 3808 516 5 3809 520 534 3810 519 534 3811 521 534 3812 525 231 3813 520 231 3814 522 231 3815 526 727 3816 525 727 3817 523 727 3818 527 233 3819 526 233 3820 524 233 3821 528 415 3822 527 415 3823 529 415 3824 533 728 3825 528 728 3826 530 728 3827 534 235 3828 533 235 3829 531 235 3830 535 540 3831 534 540 3832 532 540 3833 536 111 3834 535 111 3835 537 111 3836 541 729 3837 536 729 3838 538 729 3839 542 16 3840 541 16 3841 539 16 3842 543 237 3843 542 237 3844 540 237 3845 544 730 3846 543 730 3847 545 730 3848 549 238 3849 544 238 3850 546 238 3851 550 20 3852 549 20 3853 547 20 3854 551 731 3855 550 731 3856 548 731 3857 552 420 3858 551 420 3859 553 420 3860 557 23 3861 552 23 3862 554 23 3863 558 549 3864 557 549 3865 555 549 3866 559 732 3867 558 732 3868 556 732 3869 560 422 3870 559 422 3871 561 422 3872 565 733 3873 560 733 3874 562 733 3875 566 734 3876 565 734 3877 563 734 3878 567 735 3879 566 735 3880 564 735 3881 568 30 3882 567 30 3883 569 30 3884 573 425 3885 568 425 3886 570 425 3887 574 736 3888 573 736 3889 571 736 3890 575 426 3891 574 426 3892 572 426 3893 579 0 3894 576 0 3895 577 0 3896 577 0 3897 636 0 3898 579 0 3899 636 664 3900 635 664 3901 579 664 3902 635 665 3903 634 665 3904 633 665 3905 633 737 3906 628 737 3907 627 737 3908 627 738 3909 626 738 3910 625 738 3911 625 0 3912 620 0 3913 627 0 3914 620 0 3915 619 0 3916 627 0 3917 619 0 3918 618 0 3919 617 0 3920 617 739 3921 612 739 3922 611 739 3923 611 670 3924 610 670 3925 603 670 3926 610 740 3927 609 740 3928 603 740 3929 609 741 3930 604 741 3931 603 741 3932 603 0 3933 602 0 3934 601 0 3935 601 0 3936 596 0 3937 603 0 3938 596 561 3939 595 561 3940 603 561 3941 595 742 3942 594 742 3943 593 742 3944 593 0 3945 588 0 3946 595 0 3947 588 0 3948 587 0 3949 595 0 3950 587 627 3951 586 627 3952 585 627 3953 585 0 3954 580 0 3955 587 0 3956 580 0 3957 579 0 3958 587 0 3959 635 636 3960 633 636 3961 579 636 3962 633 0 3963 627 0 3964 579 0 3965 619 743 3966 617 743 3967 611 743 3968 627 744 3969 619 744 3970 579 744 3971 619 0 3972 611 0 3973 579 0 3974 611 0 3975 603 0 3976 595 0 3977 595 745 3978 587 745 3979 611 745 3980 578 681 3981 639 681 3982 577 681 3983 581 682 3984 578 682 3985 576 682 3986 582 683 3987 581 683 3988 579 683 3989 638 746 3990 639 746 3991 578 746 3992 578 747 3993 581 747 3994 582 747 3995 582 4 3996 583 4 3997 584 4 3998 584 4 3999 589 4 4000 582 4 4001 589 4 4002 590 4 4003 582 4 4004 590 4 4005 591 4 4006 598 4 4007 591 4 4008 592 4 4009 598 4 4010 592 748 4011 597 748 4012 598 748 4013 598 749 4014 599 749 4015 600 749 4016 600 750 4017 605 750 4018 598 750 4019 605 4 4020 606 4 4021 598 4 4022 606 688 4023 607 688 4024 608 688 4025 608 4 4026 613 4 4027 614 4 4028 614 4 4029 615 4 4030 622 4 4031 615 751 4032 616 751 4033 622 751 4034 616 752 4035 621 752 4036 622 752 4037 622 753 4038 623 753 4039 624 753 4040 624 4 4041 629 4 4042 622 4 4043 629 4 4044 630 4 4045 622 4 4046 630 4 4047 631 4 4048 638 4 4049 631 651 4050 632 651 4051 638 651 4052 632 4 4053 637 4 4054 638 4 4055 638 4 4056 578 4 4057 582 4 4058 606 4 4059 608 4 4060 614 4 4061 638 4 4062 582 4 4063 590 4 4064 590 4 4065 598 4 4066 638 4 4067 598 4 4068 606 4 4069 638 4 4070 606 4 4071 614 4 4072 638 4 4073 614 4 4074 622 4 4075 638 4 4076 583 754 4077 582 754 4078 580 754 4079 584 755 4080 583 755 4081 585 755 4082 589 756 4083 584 756 4084 586 756 4085 590 696 4086 589 696 4087 587 696 4088 591 757 4089 590 757 4090 588 757 4091 592 758 4092 591 758 4093 593 758 4094 597 207 4095 592 207 4096 594 207 4097 598 588 4098 597 588 4099 595 588 4100 599 208 4101 598 208 4102 596 208 4103 600 759 4104 599 759 4105 601 759 4106 605 760 4107 600 760 4108 602 760 4109 606 761 4110 605 761 4111 603 761 4112 607 702 4113 606 702 4114 604 702 4115 608 703 4116 607 703 4117 609 703 4118 613 704 4119 608 704 4120 610 704 4121 614 705 4122 613 705 4123 611 705 4124 615 706 4125 614 706 4126 612 706 4127 616 762 4128 615 762 4129 617 762 4130 621 218 4131 616 218 4132 618 218 4133 622 219 4134 621 219 4135 619 219 4136 623 597 4137 622 597 4138 620 597 4139 624 220 4140 623 220 4141 625 220 4142 629 709 4143 624 709 4144 626 709 4145 630 763 4146 629 763 4147 627 763 4148 631 711 4149 630 711 4150 628 711 4151 632 712 4152 631 712 4153 633 712 4154 637 764 4155 632 764 4156 634 764 4157 638 226 4158 637 226 4159 635 226 4160 639 714 4161 638 714 4162 636 714 4163

-
- - - - -

652 0 1032 648 0 1033 649 0 1034 650 261 1035 649 261 1036 648 261 1037 653 262 1038 648 262 1039 651 262 1040 654 263 1041 651 263 1042 652 263 1043 655 4 1044 653 4 1045 654 4 1046 655 264 1047 652 264 1048 649 264 1049 785 330 1248 786 330 1249 784 330 1250 787 331 1251 788 331 1252 786 331 1253 789 332 1254 790 332 1255 788 332 1256 791 333 1257 792 333 1258 790 333 1259 793 334 1260 794 334 1261 792 334 1262 795 335 1263 796 335 1264 794 335 1265 797 336 1266 798 336 1267 796 336 1268 799 337 1269 800 337 1270 798 337 1271 801 338 1272 802 338 1273 800 338 1274 803 339 1275 804 339 1276 802 339 1277 805 340 1278 806 340 1279 804 340 1280 807 341 1281 808 341 1282 806 341 1283 809 342 1284 810 342 1285 808 342 1286 811 343 1287 812 343 1288 810 343 1289 813 344 1290 814 344 1291 812 344 1292 815 345 1293 816 345 1294 814 345 1295 817 346 1296 818 346 1297 816 346 1298 819 347 1299 820 347 1300 818 347 1301 821 348 1302 822 348 1303 820 348 1304 823 349 1305 824 349 1306 822 349 1307 825 350 1308 826 350 1309 824 350 1310 827 351 1311 828 351 1312 826 351 1313 829 352 1314 830 352 1315 828 352 1316 831 353 1317 832 353 1318 830 353 1319 833 354 1320 834 354 1321 832 354 1322 835 355 1323 836 355 1324 834 355 1325 837 356 1326 838 356 1327 836 356 1328 839 357 1329 840 357 1330 838 357 1331 841 358 1332 842 358 1333 840 358 1334 843 359 1335 844 359 1336 842 359 1337 845 360 1338 846 360 1339 844 360 1340 847 361 1341 848 361 1342 846 361 1343 849 362 1344 850 362 1345 848 362 1346 851 363 1347 852 363 1348 850 363 1349 853 364 1350 854 364 1351 852 364 1352 855 365 1353 856 365 1354 854 365 1355 857 366 1356 858 366 1357 856 366 1358 859 367 1359 860 367 1360 858 367 1361 861 368 1362 862 368 1363 860 368 1364 863 369 1365 864 369 1366 862 369 1367 865 370 1368 866 370 1369 864 370 1370 867 371 1371 868 371 1372 866 371 1373 869 372 1374 870 372 1375 868 372 1376 871 373 1377 872 373 1378 870 373 1379 873 374 1380 874 374 1381 872 374 1382 875 375 1383 876 375 1384 874 375 1385 877 376 1386 878 376 1387 876 376 1388 879 377 1389 880 377 1390 878 377 1391 881 378 1392 882 378 1393 880 378 1394 883 379 1395 884 379 1396 882 379 1397 885 380 1398 886 380 1399 884 380 1400 887 381 1401 888 381 1402 886 381 1403 889 382 1404 890 382 1405 888 382 1406 891 383 1407 892 383 1408 890 383 1409 893 384 1410 894 384 1411 892 384 1412 895 385 1413 896 385 1414 894 385 1415 897 386 1416 898 386 1417 896 386 1418 899 387 1419 900 387 1420 898 387 1421 901 388 1422 902 388 1423 900 388 1424 903 389 1425 904 389 1426 902 389 1427 905 390 1428 906 390 1429 904 390 1430 907 391 1431 908 391 1432 906 391 1433 805 4 1434 789 4 1435 853 4 1436 909 392 1437 910 392 1438 908 392 1439 911 393 1440 784 393 1441 910 393 1442 846 0 1443 878 0 1444 910 0 1445 652 0 4182 651 0 4183 648 0 4184 650 261 4185 655 261 4186 649 261 4187 653 262 4188 650 262 4189 648 262 4190 654 263 4191 653 263 4192 651 263 4193 655 4 4194 650 4 4195 653 4 4196 655 264 4197 654 264 4198 652 264 4199 785 861 4758 787 861 4759 786 861 4760 787 331 4761 789 331 4762 788 331 4763 789 332 4764 791 332 4765 790 332 4766 791 862 4767 793 862 4768 792 862 4769 793 863 4770 795 863 4771 794 863 4772 795 864 4773 797 864 4774 796 864 4775 797 336 4776 799 336 4777 798 336 4778 799 337 4779 801 337 4780 800 337 4781 801 865 4782 803 865 4783 802 865 4784 803 866 4785 805 866 4786 804 866 4787 805 867 4788 807 867 4789 806 867 4790 807 341 4791 809 341 4792 808 341 4793 809 868 4794 811 868 4795 810 868 4796 811 869 4797 813 869 4798 812 869 4799 813 870 4800 815 870 4801 814 870 4802 815 871 4803 817 871 4804 816 871 4805 817 872 4806 819 872 4807 818 872 4808 819 873 4809 821 873 4810 820 873 4811 821 874 4812 823 874 4813 822 874 4814 823 875 4815 825 875 4816 824 875 4817 825 350 4818 827 350 4819 826 350 4820 827 876 4821 829 876 4822 828 876 4823 829 877 4824 831 877 4825 830 877 4826 831 878 4827 833 878 4828 832 878 4829 833 354 4830 835 354 4831 834 354 4832 835 355 4833 837 355 4834 836 355 4835 837 879 4836 839 879 4837 838 879 4838 839 880 4839 841 880 4840 840 880 4841 841 881 4842 843 881 4843 842 881 4844 843 359 4845 845 359 4846 844 359 4847 845 360 4848 847 360 4849 846 360 4850 847 882 4851 849 882 4852 848 882 4853 849 883 4854 851 883 4855 850 883 4856 851 363 4857 853 363 4858 852 363 4859 853 364 4860 855 364 4861 854 364 4862 855 365 4863 857 365 4864 856 365 4865 857 884 4866 859 884 4867 858 884 4868 859 885 4869 861 885 4870 860 885 4871 861 368 4872 863 368 4873 862 368 4874 863 369 4875 865 369 4876 864 369 4877 865 886 4878 867 886 4879 866 886 4880 867 887 4881 869 887 4882 868 887 4883 869 888 4884 871 888 4885 870 888 4886 871 373 4887 873 373 4888 872 373 4889 873 889 4890 875 889 4891 874 889 4892 875 890 4893 877 890 4894 876 890 4895 877 891 4896 879 891 4897 878 891 4898 879 892 4899 881 892 4900 880 892 4901 881 893 4902 883 893 4903 882 893 4904 883 894 4905 885 894 4906 884 894 4907 885 895 4908 887 895 4909 886 895 4910 887 896 4911 889 896 4912 888 896 4913 889 382 4914 891 382 4915 890 382 4916 891 897 4917 893 897 4918 892 897 4919 893 898 4920 895 898 4921 894 898 4922 895 899 4923 897 899 4924 896 899 4925 897 386 4926 899 386 4927 898 386 4928 899 387 4929 901 387 4930 900 387 4931 901 900 4932 903 900 4933 902 900 4934 903 901 4935 905 901 4936 904 901 4937 905 390 4938 907 390 4939 906 390 4940 907 391 4941 909 391 4942 908 391 4943 789 902 4944 787 902 4945 785 902 4946 785 4 4947 911 4 4948 789 4 4949 911 4 4950 909 4 4951 789 4 4952 909 467 4953 907 467 4954 905 467 4955 905 903 4956 903 903 4957 901 903 4958 901 4 4959 899 4 4960 897 4 4961 897 4 4962 895 4 4963 893 4 4964 893 4 4965 891 4 4966 889 4 4967 889 4 4968 887 4 4969 885 4 4970 885 466 4971 883 466 4972 881 466 4973 881 4 4974 879 4 4975 885 4 4976 879 4 4977 877 4 4978 885 4 4979 877 4 4980 875 4 4981 873 4 4982 873 4 4983 871 4 4984 869 4 4985 869 4 4986 867 4 4987 865 4 4988 865 4 4989 863 4 4990 861 4 4991 861 904 4992 859 904 4993 857 904 4994 857 467 4995 855 467 4996 853 467 4997 853 4 4998 851 4 4999 845 4 5000 851 4 5001 849 4 5002 845 4 5003 849 4 5004 847 4 5005 845 4 5006 845 464 5007 843 464 5008 841 464 5009 841 905 5010 839 905 5011 837 905 5012 837 4 5013 835 4 5014 833 4 5015 833 4 5016 831 4 5017 829 4 5018 829 4 5019 827 4 5020 825 4 5021 825 4 5022 823 4 5023 821 4 5024 821 469 5025 819 469 5026 817 469 5027 817 4 5028 815 4 5029 821 4 5030 815 4 5031 813 4 5032 821 4 5033 813 4 5034 811 4 5035 809 4 5036 809 4 5037 807 4 5038 805 4 5039 805 4 5040 803 4 5041 801 4 5042 801 4 5043 799 4 5044 797 4 5045 797 906 5046 795 906 5047 793 906 5048 793 464 5049 791 464 5050 789 464 5051 909 907 5052 905 907 5053 901 907 5054 901 4 5055 897 4 5056 893 4 5057 893 908 5058 889 908 5059 885 908 5060 877 908 5061 873 908 5062 869 908 5063 869 4 5064 865 4 5065 861 4 5066 861 473 5067 857 473 5068 853 473 5069 845 909 5070 841 909 5071 837 909 5072 837 4 5073 833 4 5074 829 4 5075 829 910 5076 825 910 5077 821 910 5078 813 910 5079 809 910 5080 805 910 5081 805 4 5082 801 4 5083 797 4 5084 797 471 5085 793 471 5086 789 471 5087 789 4 5088 909 4 5089 901 4 5090 901 4 5091 893 4 5092 885 4 5093 885 911 5094 877 911 5095 869 911 5096 869 912 5097 861 912 5098 853 912 5099 853 4 5100 845 4 5101 837 4 5102 837 4 5103 829 4 5104 821 4 5105 821 913 5106 813 913 5107 805 913 5108 805 914 5109 797 914 5110 789 914 5111 789 476 5112 901 476 5113 885 476 5114 885 4 5115 869 4 5116 789 4 5117 869 4 5118 853 4 5119 789 4 5120 853 477 5121 837 477 5122 821 477 5123 821 4 5124 805 4 5125 853 4 5126 909 392 5127 911 392 5128 910 392 5129 911 915 5130 785 915 5131 784 915 5132 910 0 5133 784 0 5134 786 0 5135 786 0 5136 788 0 5137 790 0 5138 790 916 5139 792 916 5140 794 916 5141 794 0 5142 796 0 5143 790 0 5144 796 0 5145 798 0 5146 790 0 5147 798 491 5148 800 491 5149 802 491 5150 802 0 5151 804 0 5152 798 0 5153 804 0 5154 806 0 5155 798 0 5156 806 493 5157 808 493 5158 814 493 5159 808 494 5160 810 494 5161 814 494 5162 810 917 5163 812 917 5164 814 917 5165 814 0 5166 816 0 5167 818 0 5168 818 918 5169 820 918 5170 822 918 5171 822 0 5172 824 0 5173 826 0 5174 826 0 5175 828 0 5176 822 0 5177 828 496 5178 830 496 5179 822 496 5180 830 497 5181 832 497 5182 834 497 5183 834 0 5184 836 0 5185 830 0 5186 836 0 5187 838 0 5188 830 0 5189 838 0 5190 840 0 5191 846 0 5192 840 0 5193 842 0 5194 846 0 5195 842 919 5196 844 919 5197 846 919 5198 846 0 5199 848 0 5200 850 0 5201 850 0 5202 852 0 5203 854 0 5204 854 920 5205 856 920 5206 858 920 5207 858 0 5208 860 0 5209 854 0 5210 860 0 5211 862 0 5212 854 0 5213 862 481 5214 864 481 5215 866 481 5216 866 0 5217 868 0 5218 862 0 5219 868 0 5220 870 0 5221 862 0 5222 870 483 5223 872 483 5224 878 483 5225 872 484 5226 874 484 5227 878 484 5228 874 921 5229 876 921 5230 878 921 5231 878 0 5232 880 0 5233 882 0 5234 882 922 5235 884 922 5236 886 922 5237 886 0 5238 888 0 5239 890 0 5240 890 0 5241 892 0 5242 886 0 5243 892 486 5244 894 486 5245 886 486 5246 894 487 5247 896 487 5248 898 487 5249 898 0 5250 900 0 5251 894 0 5252 900 0 5253 902 0 5254 894 0 5255 902 0 5256 904 0 5257 910 0 5258 904 0 5259 906 0 5260 910 0 5261 906 923 5262 908 923 5263 910 923 5264 910 0 5265 786 0 5266 798 0 5267 786 0 5268 790 0 5269 798 0 5270 814 0 5271 818 0 5272 830 0 5273 818 500 5274 822 500 5275 830 500 5276 846 0 5277 850 0 5278 862 0 5279 850 0 5280 854 0 5281 862 0 5282 878 0 5283 882 0 5284 894 0 5285 882 499 5286 886 499 5287 894 499 5288 798 0 5289 806 0 5290 814 0 5291 830 0 5292 838 0 5293 846 0 5294 862 0 5295 870 0 5296 878 0 5297 894 0 5298 902 0 5299 910 0 5300 910 0 5301 798 0 5302 814 0 5303 814 0 5304 830 0 5305 846 0 5306 846 0 5307 862 0 5308 878 0 5309 878 0 5310 894 0 5311 910 0 5312 910 0 5313 814 0 5314 846 0 5315

-
-
-
-
- - - - 1 0 0 0.00244534 0 1 0 4.87998e-4 0 0 1 1.200897 0 0 0 1 - - - - 1 0 0 5.39839e-4 0 1 0 0.00155586 0 0 1.6 0.4 0 0 0 1 - - - - - - - - - - - - - - - -
diff --git a/src/picknik_ur_mock_hw_config/meshes/base.png b/src/picknik_ur_mock_hw_config/meshes/base.png deleted file mode 100644 index bd42b6a1..00000000 Binary files a/src/picknik_ur_mock_hw_config/meshes/base.png and /dev/null differ diff --git a/src/picknik_ur_mock_hw_config/meshes/cnc-collision.dae b/src/picknik_ur_mock_hw_config/meshes/cnc-collision.dae deleted file mode 100644 index 091b0124..00000000 --- a/src/picknik_ur_mock_hw_config/meshes/cnc-collision.dae +++ /dev/null @@ -1,208 +0,0 @@ - - - - - Blender User - Blender 3.6.1 commit date:2023-07-17, commit time:12:50, hash:8bda729ef4dc - - 2023-08-01T21:32:52 - 2023-08-01T21:32:52 - - Z_UP - - - - - - - - -1 -1 -1 -1 -1 1 -1 1 -1 -1 1 1 1 -1 -1 1 -1 1 1 1 -1 1 1 1 - - - - - - - - - - -1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1 - - - - - - - - - - 0.625 0 0.375 0.25 0.375 0 0.625 0.25 0.375 0.5 0.375 0.25 0.625 0.5 0.375 0.75 0.375 0.5 0.625 0.75 0.375 1 0.375 0.75 0.375 0.5 0.125 0.75 0.125 0.5 0.875 0.5 0.625 0.75 0.625 0.5 0.625 0 0.625 0.25 0.375 0.25 0.625 0.25 0.625 0.5 0.375 0.5 0.625 0.5 0.625 0.75 0.375 0.75 0.625 0.75 0.625 1 0.375 1 0.375 0.5 0.375 0.75 0.125 0.75 0.875 0.5 0.875 0.75 0.625 0.75 - - - - - - - - - - - - - - -

1 0 0 2 0 1 0 0 2 3 1 3 6 1 4 2 1 5 7 2 6 4 2 7 6 2 8 5 3 9 0 3 10 4 3 11 6 4 12 0 4 13 2 4 14 3 5 15 5 5 16 7 5 17 1 0 18 3 0 19 2 0 20 3 1 21 7 1 22 6 1 23 7 2 24 5 2 25 4 2 26 5 3 27 1 3 28 0 3 29 6 4 30 4 4 31 0 4 32 3 5 33 1 5 34 5 5 35

-
-
-
- - - - -1 -1 0.03761059 -1 -1 0.9118407 -1 1 0.03761059 -1 1 0.9118407 1 -1 0.03761059 1 -1 0.9118407 1 1 0.03761059 1 1 0.9118407 - - - - - - - - - - -1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1 - - - - - - - - - - 0.625 0 0.375 0.25 0.375 0 0.625 0.25 0.375 0.5 0.375 0.25 0.625 0.5 0.375 0.75 0.375 0.5 0.625 0.75 0.375 1 0.375 0.75 0.375 0.5 0.125 0.75 0.125 0.5 0.875 0.5 0.625 0.75 0.625 0.5 0.625 0 0.625 0.25 0.375 0.25 0.625 0.25 0.625 0.5 0.375 0.5 0.625 0.5 0.625 0.75 0.375 0.75 0.625 0.75 0.625 1 0.375 1 0.375 0.5 0.375 0.75 0.125 0.75 0.875 0.5 0.875 0.75 0.625 0.75 - - - - - - - - - - - - - - -

1 0 0 2 0 1 0 0 2 3 1 3 6 1 4 2 1 5 7 2 6 4 2 7 6 2 8 5 3 9 0 3 10 4 3 11 6 4 12 0 4 13 2 4 14 3 5 15 5 5 16 7 5 17 1 0 18 3 0 19 2 0 20 3 1 21 7 1 22 6 1 23 7 2 24 5 2 25 4 2 26 5 3 27 1 3 28 0 3 29 6 4 30 4 4 31 0 4 32 3 5 33 1 5 34 5 5 35

-
-
-
- - - - -1 -1 0.03761059 -1 -1 0.9118407 -1 1 0.03761059 -1 1 0.9118407 1 -1 0.03761059 1 -1 0.9118407 1 1 0.03761059 1 1 0.9118407 - - - - - - - - - - -1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1 - - - - - - - - - - 0.625 0 0.375 0.25 0.375 0 0.625 0.25 0.375 0.5 0.375 0.25 0.625 0.5 0.375 0.75 0.375 0.5 0.625 0.75 0.375 1 0.375 0.75 0.375 0.5 0.125 0.75 0.125 0.5 0.875 0.5 0.625 0.75 0.625 0.5 0.625 0 0.625 0.25 0.375 0.25 0.625 0.25 0.625 0.5 0.375 0.5 0.625 0.5 0.625 0.75 0.375 0.75 0.625 0.75 0.625 1 0.375 1 0.375 0.5 0.375 0.75 0.125 0.75 0.875 0.5 0.875 0.75 0.625 0.75 - - - - - - - - - - - - - - -

1 0 0 2 0 1 0 0 2 3 1 3 6 1 4 2 1 5 7 2 6 4 2 7 6 2 8 5 3 9 0 3 10 4 3 11 6 4 12 0 4 13 2 4 14 3 5 15 5 5 16 7 5 17 1 0 18 3 0 19 2 0 20 3 1 21 7 1 22 6 1 23 7 2 24 5 2 25 4 2 26 5 3 27 1 3 28 0 3 29 6 4 30 4 4 31 0 4 32 3 5 33 1 5 34 5 5 35

-
-
-
- - - - -1 -1 -1.43962 -1 -1 1 -1 1 -1.43962 -1 1 1 1 -1 -1.43962 1 -1 1 1 1 -1.43962 1 1 1 - - - - - - - - - - -1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1 - - - - - - - - - - 0.625 0 0.375 0.25 0.375 0 0.625 0.25 0.375 0.5 0.375 0.25 0.625 0.5 0.375 0.75 0.375 0.5 0.625 0.75 0.375 1 0.375 0.75 0.375 0.5 0.125 0.75 0.125 0.5 0.875 0.5 0.625 0.75 0.625 0.5 0.625 0 0.625 0.25 0.375 0.25 0.625 0.25 0.625 0.5 0.375 0.5 0.625 0.5 0.625 0.75 0.375 0.75 0.625 0.75 0.625 1 0.375 1 0.375 0.5 0.375 0.75 0.125 0.75 0.875 0.5 0.875 0.75 0.625 0.75 - - - - - - - - - - - - - - -

1 0 0 2 0 1 0 0 2 3 1 3 6 1 4 2 1 5 7 2 6 4 2 7 6 2 8 5 3 9 0 3 10 4 3 11 6 4 12 0 4 13 2 4 14 3 5 15 5 5 16 7 5 17 1 0 18 3 0 19 2 0 20 3 1 21 7 1 22 6 1 23 7 2 24 5 2 25 4 2 26 5 3 27 1 3 28 0 3 29 6 4 30 4 4 31 0 4 32 3 5 33 1 5 34 5 5 35

-
-
-
-
- - - - 0.8820289 0 0 -0.1269467 0 0.6688613 0 0.04338684 0 0 0.04052223 1.869295 0 0 0 1 - - - - 0.2883302 0 0 -0.7209587 0 0.6688613 0 0.04338684 0 0 0.9536631 0.9553806 0 0 0 1 - - - - 0.2372117 0 0 0.5176404 0 0.6688613 0 0.04338684 0 0 0.9536631 0.9553806 0 0 0 1 - - - - 0.8820289 0 0 -0.1269467 0 0.6688613 0 0.04338684 0 0 0.4037348 0.5826219 0 0 0 1 - - - - - - - -
\ No newline at end of file diff --git a/src/picknik_ur_mock_hw_config/meshes/cnc.dae b/src/picknik_ur_mock_hw_config/meshes/cnc.dae deleted file mode 100644 index 137bf15e..00000000 --- a/src/picknik_ur_mock_hw_config/meshes/cnc.dae +++ /dev/null @@ -1,787 +0,0 @@ - - - - - Blender User - Blender 3.6.1 commit date:2023-07-17, commit time:12:50, hash:8bda729ef4dc - - 2023-07-31T11:27:49 - 2023-07-31T11:27:49 - - Z_UP - - - - - - 0 0 0 - 1 - 0 - 0.00111109 - 75 - 0.15 - - - - - 2 - 0 - 1 - 1 - 1 - 1 - 1 - 0 - 0 - 0 - 0 - 29.99998 - 75 - 0.15 - 0 - 1 - 2 - 0.04999995 - 30.002 - 1 - 2880 - 3 - 1 - 0.1 - 1 - 0.1 - 0.1 - 1 - - - - - - - - - - cnc_png - - - - - cnc_png-surface - - - - - - 0 0 0 1 - - - - - - 1 - - - 1.45 - - - - - - - - - - cnc_png - - - - - cnc_png-surface - - - - - - 0 0 0 1 - - - - - - 1.45 - - - - - - - - - - cnc_png - - - - - cnc_png-surface - - - - - - 0 0 0 1 - - - - - - 1.45 - - - - - - - - - - cnc_png - - - - - cnc_png-surface - - - - - - 0 0 0 1 - - - - - - 1 - - - 1.45 - - - - - - - - - cnc.png - - - - - - - - - - - - - - - - - - - - - -1 -1 -1 -1 -1 1 -1 1 -1 -1 1 1 1 -1 -1 1 -1 1 1 1 -1 1 1 1 -0.7163323 1 -1 -0.7163323 1 1 -0.7163323 -1 -1 -0.7163323 -1 1 1 -1.314597 1 1 -1.314597 -1 -0.7163323 -1.314597 -1 -0.7163323 -1.314597 1 - - - - - - - - - - -1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1 - - - - - - - - - - 0.05983591 0.2203093 0.1109375 0.1692076 0.1109375 0.2203093 0.05983585 0.1619596 0.1109375 0.1181058 0.1109375 0.1619596 0.05983585 0.1181058 0.1109375 0.06700402 0.1109375 0.1181058 0.05983585 0.02315038 0.1109375 0.0159024 0.1109375 0.02315038 0.1109375 0.1181058 0.1547913 0.06700402 0.1547913 0.1181058 0.008734107 0.1181058 0.01598215 0.06700402 0.01598215 0.1181058 0.01598215 0.1181058 0.05983585 0.06700402 0.05983585 0.1181058 0.1547913 0.1181058 0.1620392 0.06700402 0.1620392 0.1181058 0.01598215 0.06700402 0.05983585 0.06700402 0.05983585 0.06700402 0.05983585 0.1692076 0.1109375 0.1619596 0.1109375 0.1692076 0.05983585 0.06700402 0.1109375 0.02315038 0.1109375 0.06700402 0.05983585 0.06700402 0.1109375 0.06700402 0.1109375 0.06700402 0.1109375 0.02315038 0.05983585 0.02315038 0.05983585 0.02315038 0.1109375 0.06700402 0.1547913 0.06700402 0.1547913 0.06700402 0.05983591 0.2203093 0.05983585 0.1692076 0.1109375 0.1692076 0.05983585 0.1619596 0.05983585 0.1181058 0.1109375 0.1181058 0.05983585 0.1181058 0.05983585 0.06700402 0.1109375 0.06700402 0.05983585 0.02315038 0.05983585 0.0159024 0.1109375 0.0159024 0.1109375 0.1181058 0.1109375 0.06700402 0.1547913 0.06700402 0.008734107 0.1181058 0.008734107 0.06700402 0.01598215 0.06700402 0.01598215 0.1181058 0.01598215 0.06700402 0.05983585 0.06700402 0.1547913 0.1181058 0.1547913 0.06700402 0.1620392 0.06700402 0.01598215 0.06700402 0.01598215 0.06700402 0.05983585 0.06700402 0.05983585 0.1692076 0.05983585 0.1619596 0.1109375 0.1619596 0.05983585 0.06700402 0.05983585 0.02315038 0.1109375 0.02315038 0.05983585 0.06700402 0.05983585 0.06700402 0.1109375 0.06700402 0.1109375 0.02315038 0.1109375 0.02315038 0.05983585 0.02315038 0.1109375 0.06700402 0.1109375 0.06700402 0.1547913 0.06700402 - - - - - - - - - - - - - - -

1 0 0 2 0 1 0 0 2 9 1 3 6 1 4 8 1 5 7 2 6 4 2 7 6 2 8 11 3 9 0 3 10 10 3 11 6 4 12 10 4 13 8 4 14 3 5 15 11 5 16 9 5 17 9 5 18 5 5 19 7 5 20 8 4 21 0 4 22 2 4 23 11 5 24 12 5 25 5 5 26 3 1 27 8 1 28 2 1 29 12 3 30 14 3 31 13 3 32 5 2 33 13 2 34 4 2 35 10 0 36 15 0 37 11 0 38 4 4 39 14 4 40 10 4 41 1 0 42 3 0 43 2 0 44 9 1 45 7 1 46 6 1 47 7 2 48 5 2 49 4 2 50 11 3 51 1 3 52 0 3 53 6 4 54 4 4 55 10 4 56 3 5 57 1 5 58 11 5 59 9 5 60 11 5 61 5 5 62 8 4 63 10 4 64 0 4 65 11 5 66 15 5 67 12 5 68 3 1 69 9 1 70 8 1 71 12 3 72 15 3 73 14 3 74 5 2 75 12 2 76 13 2 77 10 0 78 14 0 79 15 0 80 4 4 81 13 4 82 14 4 83

-
-
-
- - - - -0.4785996 0.573 0.04663276 -0.4785996 -0.437 0.04663276 -0.4785996 0.573 0.6446328 -0.4785996 -0.437 0.6446328 0.4814004 -0.437 0.04663276 0.4814004 -0.437 0.6446328 0.4814004 0.573 0.04663276 0.4814004 0.573 0.6446328 0.4245738 -0.3561338 0.03140497 0.4245738 -0.3561338 0.05280429 0.4295397 -0.3566228 0.03140497 0.4295397 -0.3566228 0.05280429 0.4343147 -0.3580713 0.03140497 0.4343147 -0.3580713 0.05280429 0.4387154 -0.3604236 0.03140497 0.4387154 -0.3604236 0.05280429 0.4425727 -0.3635891 0.03140497 0.4425727 -0.3635891 0.05280429 0.4457382 -0.3674464 0.03140497 0.4457382 -0.3674464 0.05280429 0.4480904 -0.371847 0.03140497 0.4480904 -0.371847 0.05280429 0.449539 -0.3766221 0.03140497 0.449539 -0.3766221 0.05280429 0.450028 -0.381588 0.03140497 0.450028 -0.381588 0.05280429 0.449539 -0.3865538 0.03140497 0.449539 -0.3865538 0.05280429 0.4480904 -0.3913289 0.03140497 0.4480904 -0.3913289 0.05280429 0.4457382 -0.3957296 0.03140497 0.4457382 -0.3957296 0.05280429 0.4425727 -0.3995869 0.03140497 0.4425727 -0.3995869 0.05280429 0.4387154 -0.4027524 0.03140497 0.4387154 -0.4027524 0.05280429 0.4343147 -0.4051046 0.03140497 0.4343147 -0.4051046 0.05280429 0.4295397 -0.4065531 0.03140497 0.4295397 -0.4065531 0.05280429 0.4245738 -0.4070422 0.03140497 0.4245738 -0.4070422 0.05280429 0.4196079 -0.4065531 0.03140497 0.4196079 -0.4065531 0.05280429 0.4148329 -0.4051046 0.03140497 0.4148329 -0.4051046 0.05280429 0.4104322 -0.4027524 0.03140497 0.4104322 -0.4027524 0.05280429 0.406575 -0.3995869 0.03140497 0.406575 -0.3995869 0.05280429 0.4034094 -0.3957296 0.03140497 0.4034094 -0.3957296 0.05280429 0.4010571 -0.3913289 0.03140497 0.4010571 -0.3913289 0.05280429 0.3996087 -0.3865538 0.03140497 0.3996087 -0.3865538 0.05280429 0.3991196 -0.381588 0.03140497 0.3991196 -0.381588 0.05280429 0.3996087 -0.3766221 0.03140497 0.3996087 -0.3766221 0.05280429 0.4010571 -0.371847 0.03140497 0.4010571 -0.371847 0.05280429 0.4034094 -0.3674464 0.03140497 0.4034094 -0.3674464 0.05280429 0.406575 -0.3635891 0.03140497 0.406575 -0.3635891 0.05280429 0.4104322 -0.3604236 0.03140497 0.4104322 -0.3604236 0.05280429 0.4148329 -0.3580713 0.03140497 0.4148329 -0.3580713 0.05280429 0.4196079 -0.3566228 0.03140497 0.4196079 -0.3566228 0.05280429 0.4245738 -0.3341087 -3.90045e-4 0.4245738 -0.3341087 0.03113627 0.4338366 -0.335021 -3.90045e-4 0.4338366 -0.335021 0.03113627 0.4427434 -0.3377228 -3.90045e-4 0.4427434 -0.3377228 0.03113627 0.4509519 -0.3421104 -3.90045e-4 0.4509519 -0.3421104 0.03113627 0.4581468 -0.3480151 -3.90045e-4 0.4581468 -0.3480151 0.03113627 0.4640514 -0.3552099 -3.90045e-4 0.4640514 -0.3552099 0.03113627 0.468439 -0.3634185 -3.90045e-4 0.468439 -0.3634185 0.03113627 0.4711408 -0.3723253 -3.90045e-4 0.4711408 -0.3723253 0.03113627 0.4720531 -0.381588 -3.90045e-4 0.4720531 -0.381588 0.03113627 0.4711408 -0.3908507 -3.90045e-4 0.4711408 -0.3908507 0.03113627 0.468439 -0.3997575 -3.90045e-4 0.468439 -0.3997575 0.03113627 0.4640514 -0.4079661 -3.90045e-4 0.4640514 -0.4079661 0.03113627 0.4581468 -0.4151609 -3.90045e-4 0.4581468 -0.4151609 0.03113627 0.4509519 -0.4210656 -3.90045e-4 0.4509519 -0.4210656 0.03113627 0.4427434 -0.4254531 -3.90045e-4 0.4427434 -0.4254531 0.03113627 0.4338366 -0.428155 -3.90045e-4 0.4338366 -0.428155 0.03113627 0.4245738 -0.4290673 -3.90045e-4 0.4245738 -0.4290673 0.03113627 0.4153111 -0.428155 -3.90045e-4 0.4153111 -0.428155 0.03113627 0.4064043 -0.4254531 -3.90045e-4 0.4064043 -0.4254531 0.03113627 0.3981958 -0.4210656 -3.90045e-4 0.3981958 -0.4210656 0.03113627 0.3910009 -0.4151609 -3.90045e-4 0.3910009 -0.4151609 0.03113627 0.3850963 -0.4079661 -3.90045e-4 0.3850963 -0.4079661 0.03113627 0.3807087 -0.3997575 -3.90045e-4 0.3807087 -0.3997575 0.03113627 0.3780069 -0.3908507 -3.90045e-4 0.3780069 -0.3908507 0.03113627 0.3770946 -0.381588 -3.90045e-4 0.3770946 -0.381588 0.03113627 0.3780069 -0.3723253 -3.90045e-4 0.3780069 -0.3723253 0.03113627 0.3807087 -0.3634185 -3.90045e-4 0.3807087 -0.3634185 0.03113627 0.3850963 -0.3552099 -3.90045e-4 0.3850963 -0.3552099 0.03113627 0.3910009 -0.3480151 -3.90045e-4 0.3910009 -0.3480151 0.03113627 0.3981958 -0.3421104 -3.90045e-4 0.3981958 -0.3421104 0.03113627 0.4064043 -0.3377228 -3.90045e-4 0.4064043 -0.3377228 0.03113627 0.4153111 -0.335021 -3.90045e-4 0.4153111 -0.335021 0.03113627 -0.4232395 -0.3561338 0.03140497 -0.4232395 -0.3561338 0.05280429 -0.4182737 -0.3566228 0.03140497 -0.4182737 -0.3566228 0.05280429 -0.4134986 -0.3580713 0.03140497 -0.4134986 -0.3580713 0.05280429 -0.4090979 -0.3604236 0.03140497 -0.4090979 -0.3604236 0.05280429 -0.4052407 -0.3635891 0.03140497 -0.4052407 -0.3635891 0.05280429 -0.4020751 -0.3674464 0.03140497 -0.4020751 -0.3674464 0.05280429 -0.3997229 -0.371847 0.03140497 -0.3997229 -0.371847 0.05280429 -0.3982744 -0.3766221 0.03140497 -0.3982744 -0.3766221 0.05280429 -0.3977853 -0.381588 0.03140497 -0.3977853 -0.381588 0.05280429 -0.3982744 -0.3865538 0.03140497 -0.3982744 -0.3865538 0.05280429 -0.3997229 -0.3913289 0.03140497 -0.3997229 -0.3913289 0.05280429 -0.4020751 -0.3957296 0.03140497 -0.4020751 -0.3957296 0.05280429 -0.4052407 -0.3995869 0.03140497 -0.4052407 -0.3995869 0.05280429 -0.4090979 -0.4027524 0.03140497 -0.4090979 -0.4027524 0.05280429 -0.4134986 -0.4051046 0.03140497 -0.4134986 -0.4051046 0.05280429 -0.4182737 -0.4065531 0.03140497 -0.4182737 -0.4065531 0.05280429 -0.4232395 -0.4070422 0.03140497 -0.4232395 -0.4070422 0.05280429 -0.4282054 -0.4065531 0.03140497 -0.4282054 -0.4065531 0.05280429 -0.4329805 -0.4051046 0.03140497 -0.4329805 -0.4051046 0.05280429 -0.4373812 -0.4027524 0.03140497 -0.4373812 -0.4027524 0.05280429 -0.4412384 -0.3995869 0.03140497 -0.4412384 -0.3995869 0.05280429 -0.444404 -0.3957296 0.03140497 -0.444404 -0.3957296 0.05280429 -0.4467562 -0.3913289 0.03140497 -0.4467562 -0.3913289 0.05280429 -0.4482047 -0.3865538 0.03140497 -0.4482047 -0.3865538 0.05280429 -0.4486938 -0.381588 0.03140497 -0.4486938 -0.381588 0.05280429 -0.4482047 -0.3766221 0.03140497 -0.4482047 -0.3766221 0.05280429 -0.4467562 -0.371847 0.03140497 -0.4467562 -0.371847 0.05280429 -0.444404 -0.3674464 0.03140497 -0.444404 -0.3674464 0.05280429 -0.4412384 -0.3635891 0.03140497 -0.4412384 -0.3635891 0.05280429 -0.4373812 -0.3604236 0.03140497 -0.4373812 -0.3604236 0.05280429 -0.4329805 -0.3580713 0.03140497 -0.4329805 -0.3580713 0.05280429 -0.4282054 -0.3566228 0.03140497 -0.4282054 -0.3566228 0.05280429 -0.4232395 -0.3341087 -3.90045e-4 -0.4232395 -0.3341087 0.03113627 -0.4139767 -0.335021 -3.90045e-4 -0.4139767 -0.335021 0.03113627 -0.40507 -0.3377228 -3.90045e-4 -0.40507 -0.3377228 0.03113627 -0.3968614 -0.3421104 -3.90045e-4 -0.3968614 -0.3421104 0.03113627 -0.3896666 -0.3480151 -3.90045e-4 -0.3896666 -0.3480151 0.03113627 -0.383762 -0.3552099 -3.90045e-4 -0.383762 -0.3552099 0.03113627 -0.3793744 -0.3634185 -3.90045e-4 -0.3793744 -0.3634185 0.03113627 -0.3766725 -0.3723253 -3.90045e-4 -0.3766725 -0.3723253 0.03113627 -0.3757602 -0.381588 -3.90045e-4 -0.3757602 -0.381588 0.03113627 -0.3766725 -0.3908507 -3.90045e-4 -0.3766725 -0.3908507 0.03113627 -0.3793744 -0.3997575 -3.90045e-4 -0.3793744 -0.3997575 0.03113627 -0.383762 -0.4079661 -3.90045e-4 -0.383762 -0.4079661 0.03113627 -0.3896666 -0.4151609 -3.90045e-4 -0.3896666 -0.4151609 0.03113627 -0.3968614 -0.4210656 -3.90045e-4 -0.3968614 -0.4210656 0.03113627 -0.40507 -0.4254531 -3.90045e-4 -0.40507 -0.4254531 0.03113627 -0.4139767 -0.428155 -3.90045e-4 -0.4139767 -0.428155 0.03113627 -0.4232395 -0.4290673 -3.90045e-4 -0.4232395 -0.4290673 0.03113627 -0.4325023 -0.428155 -3.90045e-4 -0.4325023 -0.428155 0.03113627 -0.4414091 -0.4254531 -3.90045e-4 -0.4414091 -0.4254531 0.03113627 -0.4496176 -0.4210656 -3.90045e-4 -0.4496176 -0.4210656 0.03113627 -0.4568125 -0.4151609 -3.90045e-4 -0.4568125 -0.4151609 0.03113627 -0.4627171 -0.4079661 -3.90045e-4 -0.4627171 -0.4079661 0.03113627 -0.4671046 -0.3997575 -3.90045e-4 -0.4671046 -0.3997575 0.03113627 -0.4698065 -0.3908507 -3.90045e-4 -0.4698065 -0.3908507 0.03113627 -0.4707188 -0.381588 -3.90045e-4 -0.4707188 -0.381588 0.03113627 -0.4698065 -0.3723253 -3.90045e-4 -0.4698065 -0.3723253 0.03113627 -0.4671046 -0.3634185 -3.90045e-4 -0.4671046 -0.3634185 0.03113627 -0.4627171 -0.3552099 -3.90045e-4 -0.4627171 -0.3552099 0.03113627 -0.4568125 -0.3480151 -3.90045e-4 -0.4568125 -0.3480151 0.03113627 -0.4496176 -0.3421104 -3.90045e-4 -0.4496176 -0.3421104 0.03113627 -0.4414091 -0.3377228 -3.90045e-4 -0.4414091 -0.3377228 0.03113627 -0.4325023 -0.335021 -3.90045e-4 -0.4325023 -0.335021 0.03113627 -0.4232395 0.5392211 0.03140497 -0.4232395 0.5392211 0.05280429 -0.4182737 0.538732 0.03140497 -0.4182737 0.538732 0.05280429 -0.4134986 0.5372835 0.03140497 -0.4134986 0.5372835 0.05280429 -0.4090979 0.5349313 0.03140497 -0.4090979 0.5349313 0.05280429 -0.4052407 0.5317658 0.03140497 -0.4052407 0.5317658 0.05280429 -0.4020751 0.5279085 0.03140497 -0.4020751 0.5279085 0.05280429 -0.3997229 0.5235078 0.03140497 -0.3997229 0.5235078 0.05280429 -0.3982744 0.5187328 0.03140497 -0.3982744 0.5187328 0.05280429 -0.3977853 0.5137669 0.03140497 -0.3977853 0.5137669 0.05280429 -0.3982744 0.508801 0.03140497 -0.3982744 0.508801 0.05280429 -0.3997229 0.504026 0.03140497 -0.3997229 0.504026 0.05280429 -0.4020751 0.4996253 0.03140497 -0.4020751 0.4996253 0.05280429 -0.4052407 0.495768 0.03140497 -0.4052407 0.495768 0.05280429 -0.4090979 0.4926025 0.03140497 -0.4090979 0.4926025 0.05280429 -0.4134986 0.4902502 0.03140497 -0.4134986 0.4902502 0.05280429 -0.4182737 0.4888017 0.03140497 -0.4182737 0.4888017 0.05280429 -0.4232395 0.4883127 0.03140497 -0.4232395 0.4883127 0.05280429 -0.4282054 0.4888017 0.03140497 -0.4282054 0.4888017 0.05280429 -0.4329805 0.4902502 0.03140497 -0.4329805 0.4902502 0.05280429 -0.4373812 0.4926025 0.03140497 -0.4373812 0.4926025 0.05280429 -0.4412384 0.495768 0.03140497 -0.4412384 0.495768 0.05280429 -0.444404 0.4996253 0.03140497 -0.444404 0.4996253 0.05280429 -0.4467562 0.504026 0.03140497 -0.4467562 0.504026 0.05280429 -0.4482047 0.508801 0.03140497 -0.4482047 0.508801 0.05280429 -0.4486938 0.5137669 0.03140497 -0.4486938 0.5137669 0.05280429 -0.4482047 0.5187328 0.03140497 -0.4482047 0.5187328 0.05280429 -0.4467562 0.5235078 0.03140497 -0.4467562 0.5235078 0.05280429 -0.444404 0.5279085 0.03140497 -0.444404 0.5279085 0.05280429 -0.4412384 0.5317658 0.03140497 -0.4412384 0.5317658 0.05280429 -0.4373812 0.5349313 0.03140497 -0.4373812 0.5349313 0.05280429 -0.4329805 0.5372835 0.03140497 -0.4329805 0.5372835 0.05280429 -0.4282054 0.538732 0.03140497 -0.4282054 0.538732 0.05280429 -0.4232395 0.5612462 -3.90045e-4 -0.4232395 0.5612462 0.03113627 -0.4139767 0.5603339 -3.90045e-4 -0.4139767 0.5603339 0.03113627 -0.40507 0.557632 -3.90045e-4 -0.40507 0.557632 0.03113627 -0.3968614 0.5532445 -3.90045e-4 -0.3968614 0.5532445 0.03113627 -0.3896666 0.5473398 -3.90045e-4 -0.3896666 0.5473398 0.03113627 -0.383762 0.5401449 -3.90045e-4 -0.383762 0.5401449 0.03113627 -0.3793744 0.5319364 -3.90045e-4 -0.3793744 0.5319364 0.03113627 -0.3766725 0.5230296 -3.90045e-4 -0.3766725 0.5230296 0.03113627 -0.3757602 0.5137669 -3.90045e-4 -0.3757602 0.5137669 0.03113627 -0.3766725 0.5045041 -3.90045e-4 -0.3766725 0.5045041 0.03113627 -0.3793744 0.4955973 -3.90045e-4 -0.3793744 0.4955973 0.03113627 -0.383762 0.4873888 -3.90045e-4 -0.383762 0.4873888 0.03113627 -0.3896666 0.4801939 -3.90045e-4 -0.3896666 0.4801939 0.03113627 -0.3968614 0.4742892 -3.90045e-4 -0.3968614 0.4742892 0.03113627 -0.40507 0.4699017 -3.90045e-4 -0.40507 0.4699017 0.03113627 -0.4139767 0.4671999 -3.90045e-4 -0.4139767 0.4671999 0.03113627 -0.4232395 0.4662876 -3.90045e-4 -0.4232395 0.4662876 0.03113627 -0.4325023 0.4671999 -3.90045e-4 -0.4325023 0.4671999 0.03113627 -0.4414091 0.4699017 -3.90045e-4 -0.4414091 0.4699017 0.03113627 -0.4496176 0.4742892 -3.90045e-4 -0.4496176 0.4742892 0.03113627 -0.4568125 0.4801939 -3.90045e-4 -0.4568125 0.4801939 0.03113627 -0.4627171 0.4873888 -3.90045e-4 -0.4627171 0.4873888 0.03113627 -0.4671046 0.4955973 -3.90045e-4 -0.4671046 0.4955973 0.03113627 -0.4698065 0.5045041 -3.90045e-4 -0.4698065 0.5045041 0.03113627 -0.4707188 0.5137669 -3.90045e-4 -0.4707188 0.5137669 0.03113627 -0.4698065 0.5230296 -3.90045e-4 -0.4698065 0.5230296 0.03113627 -0.4671046 0.5319364 -3.90045e-4 -0.4671046 0.5319364 0.03113627 -0.4627171 0.5401449 -3.90045e-4 -0.4627171 0.5401449 0.03113627 -0.4568125 0.5473398 -3.90045e-4 -0.4568125 0.5473398 0.03113627 -0.4496176 0.5532445 -3.90045e-4 -0.4496176 0.5532445 0.03113627 -0.4414091 0.557632 -3.90045e-4 -0.4414091 0.557632 0.03113627 -0.4325023 0.5603339 -3.90045e-4 -0.4325023 0.5603339 0.03113627 0.4245738 0.5392211 0.03140497 0.4245738 0.5392211 0.05280429 0.4295397 0.538732 0.03140497 0.4295397 0.538732 0.05280429 0.4343147 0.5372835 0.03140497 0.4343147 0.5372835 0.05280429 0.4387154 0.5349313 0.03140497 0.4387154 0.5349313 0.05280429 0.4425727 0.5317658 0.03140497 0.4425727 0.5317658 0.05280429 0.4457382 0.5279085 0.03140497 0.4457382 0.5279085 0.05280429 0.4480904 0.5235078 0.03140497 0.4480904 0.5235078 0.05280429 0.449539 0.5187328 0.03140497 0.449539 0.5187328 0.05280429 0.450028 0.5137669 0.03140497 0.450028 0.5137669 0.05280429 0.449539 0.508801 0.03140497 0.449539 0.508801 0.05280429 0.4480904 0.504026 0.03140497 0.4480904 0.504026 0.05280429 0.4457382 0.4996253 0.03140497 0.4457382 0.4996253 0.05280429 0.4425727 0.495768 0.03140497 0.4425727 0.495768 0.05280429 0.4387154 0.4926025 0.03140497 0.4387154 0.4926025 0.05280429 0.4343147 0.4902502 0.03140497 0.4343147 0.4902502 0.05280429 0.4295397 0.4888017 0.03140497 0.4295397 0.4888017 0.05280429 0.4245738 0.4883127 0.03140497 0.4245738 0.4883127 0.05280429 0.4196079 0.4888017 0.03140497 0.4196079 0.4888017 0.05280429 0.4148329 0.4902502 0.03140497 0.4148329 0.4902502 0.05280429 0.4104322 0.4926025 0.03140497 0.4104322 0.4926025 0.05280429 0.406575 0.495768 0.03140497 0.406575 0.495768 0.05280429 0.4034094 0.4996253 0.03140497 0.4034094 0.4996253 0.05280429 0.4010571 0.504026 0.03140497 0.4010571 0.504026 0.05280429 0.3996087 0.508801 0.03140497 0.3996087 0.508801 0.05280429 0.3991196 0.5137669 0.03140497 0.3991196 0.5137669 0.05280429 0.3996087 0.5187328 0.03140497 0.3996087 0.5187328 0.05280429 0.4010571 0.5235078 0.03140497 0.4010571 0.5235078 0.05280429 0.4034094 0.5279085 0.03140497 0.4034094 0.5279085 0.05280429 0.406575 0.5317658 0.03140497 0.406575 0.5317658 0.05280429 0.4104322 0.5349313 0.03140497 0.4104322 0.5349313 0.05280429 0.4148329 0.5372835 0.03140497 0.4148329 0.5372835 0.05280429 0.4196079 0.538732 0.03140497 0.4196079 0.538732 0.05280429 0.4245738 0.5612462 -3.90045e-4 0.4245738 0.5612462 0.03113627 0.4338366 0.5603339 -3.90045e-4 0.4338366 0.5603339 0.03113627 0.4427434 0.557632 -3.90045e-4 0.4427434 0.557632 0.03113627 0.4509519 0.5532445 -3.90045e-4 0.4581468 0.5473398 -3.90045e-4 0.4640514 0.5401449 -3.90045e-4 0.468439 0.5319364 -3.90045e-4 0.4711408 0.5230296 -3.90045e-4 0.4720531 0.5137669 -3.90045e-4 0.4711408 0.5045041 -3.90045e-4 0.468439 0.4955973 -3.90045e-4 0.4640514 0.4873888 -3.90045e-4 0.4581468 0.4801939 -3.90045e-4 0.4509519 0.4742892 -3.90045e-4 0.4427434 0.4699017 -3.90045e-4 0.4338366 0.4671999 -3.90045e-4 0.4245738 0.4662876 -3.90045e-4 0.4245738 0.4662876 0.03113627 0.4153111 0.4671999 -3.90045e-4 0.4153111 0.4671999 0.03113627 0.4064043 0.4699017 -3.90045e-4 0.4064043 0.4699017 0.03113627 0.3981958 0.4742892 -3.90045e-4 0.3981958 0.4742892 0.03113627 0.3910009 0.4801939 -3.90045e-4 0.3910009 0.4801939 0.03113627 0.3850963 0.4873888 -3.90045e-4 0.3850963 0.4873888 0.03113627 0.3807087 0.4955973 -3.90045e-4 0.3807087 0.4955973 0.03113627 0.3780069 0.5045041 -3.90045e-4 0.3780069 0.5045041 0.03113627 0.3770946 0.5137669 -3.90045e-4 0.3770946 0.5137669 0.03113627 0.3780069 0.5230296 -3.90045e-4 0.3780069 0.5230296 0.03113627 0.3807087 0.5319364 -3.90045e-4 0.3807087 0.5319364 0.03113627 0.3850963 0.5401449 -3.90045e-4 0.3850963 0.5401449 0.03113627 0.3910009 0.5473398 -3.90045e-4 0.3910009 0.5473398 0.03113627 0.3981958 0.5532445 -3.90045e-4 0.3981958 0.5532445 0.03113627 0.4064043 0.557632 -3.90045e-4 0.4064043 0.557632 0.03113627 0.4153111 0.5603339 -3.90045e-4 0.4153111 0.5603339 0.03113627 0.4814004 -0.437 0.04663276 0.4814004 -0.437 0.6446328 0.4814004 0.573 0.04663276 0.4814004 0.573 0.6446328 0.4338366 0.5603339 0.03113627 0.4245738 0.5612462 0.03113627 0.4427434 0.557632 0.03113627 0.4427434 0.557632 -3.90045e-4 0.4509519 0.5532445 -3.90045e-4 0.4509519 0.5532445 0.03113627 0.4581468 0.5473398 -3.90045e-4 0.4581468 0.5473398 0.03113627 0.4640514 0.5401449 -3.90045e-4 0.4640514 0.5401449 0.03113627 0.468439 0.5319364 -3.90045e-4 0.468439 0.5319364 0.03113627 0.4711408 0.5230296 -3.90045e-4 0.4711408 0.5230296 0.03113627 0.4720531 0.5137669 -3.90045e-4 0.4720531 0.5137669 0.03113627 0.4711408 0.5045041 -3.90045e-4 0.4711408 0.5045041 0.03113627 0.468439 0.4955973 -3.90045e-4 0.468439 0.4955973 0.03113627 0.4640514 0.4873888 -3.90045e-4 0.4640514 0.4873888 0.03113627 0.4581468 0.4801939 -3.90045e-4 0.4581468 0.4801939 0.03113627 0.4509519 0.4742892 -3.90045e-4 0.4509519 0.4742892 0.03113627 0.4427434 0.4699017 -3.90045e-4 0.4427434 0.4699017 0.03113627 0.4338366 0.4671999 -3.90045e-4 0.4338366 0.4671999 0.03113627 0.4245738 0.4662876 -3.90045e-4 0.4245738 0.4662876 0.03113627 0.4153111 0.4671999 0.03113627 0.4064043 0.4699017 0.03113627 0.3981958 0.4742892 0.03113627 0.3910009 0.4801939 0.03113627 0.3850963 0.4873888 0.03113627 0.3807087 0.4955973 0.03113627 0.3780069 0.5045041 0.03113627 0.3770946 0.5137669 0.03113627 0.3780069 0.5230296 0.03113627 0.3807087 0.5319364 0.03113627 0.3850963 0.5401449 0.03113627 0.3910009 0.5473398 0.03113627 0.3981958 0.5532445 0.03113627 0.4064043 0.557632 0.03113627 0.4153111 0.5603339 0.03113627 - - - - - - - - - - 0 -1 0 0 0 -1 -1 0 0 0 0 1 0 1 0 0.09801566 0.995185 0 0.2902821 0.9569412 0 0.4714004 0.8819194 0 0.6343966 0.7730078 0 0.7730033 0.634402 0 0.8819207 0.4713978 0 0.9569418 0.2902802 0 0.9951849 0.09801608 0 0.9951849 -0.09801608 0 0.9569418 -0.2902802 0 0.8819207 -0.4713978 0 0.7730119 -0.6343916 0 0.634388 -0.7730148 0 0.4714004 -0.8819194 0 0.2902821 -0.9569412 0 0.09801393 -0.9951851 0 -0.09801733 -0.9951847 0 -0.2902821 -0.9569412 0 -0.4713932 -0.8819232 0 -0.6343966 -0.7730078 0 -0.7730033 -0.634402 0 -0.8819207 -0.4713978 0 -0.9569418 -0.2902802 0 -0.9951849 -0.09801608 0 -0.9951849 0.09801608 0 -0.9569418 0.2902802 0 -0.8819207 0.4713978 0 -0.7730119 0.6343916 0 -0.634388 0.7730148 0 -0.4714077 0.8819155 0 1.79676e-7 0 1 -0.2902821 0.9569412 0 -0.09801393 0.9951851 0 0.09801816 0.9951847 0 0.2902843 0.9569405 0 0.4713951 0.8819222 0 0.6343924 0.7730113 0 0.7730129 0.6343904 0 0.8819212 0.4713969 0 0.9569393 0.2902881 0 0.9951849 0.09801578 0 0.9951849 -0.09801578 0 0.9569409 -0.2902832 0 0.8819212 -0.4713969 0 0.7730098 -0.6343942 0 0.6343942 -0.7730097 0 0.4713978 -0.8819208 0 0.2902861 -0.9569399 0 0.09801501 -0.995185 0 -0.09801441 -0.9951851 0 -0.2902861 -0.9569399 0 -0.4713978 -0.8819208 0 -0.6343973 -0.7730072 0 -0.7730098 -0.6343942 0 -0.8819212 -0.4713969 0 -0.9569426 -0.2902773 0 -0.9951843 -0.09802204 0 -0.9951849 0.09801578 0 -0.9569393 0.2902881 0 -0.8819212 0.4713969 0 -0.7730129 0.6343904 0 -0.6343892 0.7730138 0 -0.4713951 0.8819222 0 0 0 1 -0.2902843 0.9569405 0 -0.09801757 0.9951848 0 0 0 -1 0.7730119 0.6343916 0 0.9569369 -0.2902961 0 -0.09801566 -0.995185 0 -0.7730119 -0.6343916 0 -0.9951832 -0.09803336 0 -0.9951866 0.09799885 0 -0.4714004 0.8819194 0 -0.09801566 0.995185 0 0.09801757 0.9951848 0 0.2902861 0.9569399 0 0.9951843 0.09802204 0 0.8819238 -0.471392 0 0.7730067 -0.6343979 0 0.6343973 -0.7730072 0 0.2902843 -0.9569405 0 -0.09801501 -0.995185 0 -0.2902843 -0.9569405 0 -0.9569409 -0.2902832 0 -0.9951849 -0.09801578 0 -0.2902861 0.9569399 0 0.09802156 0.9951843 0 0.2902767 0.9569428 0 0.8819221 0.4713953 0 0.9569408 0.2902835 0 0.9951849 0.09801548 0 0.9951849 -0.09801548 0 0.9569359 -0.2902995 0 0.8819221 -0.4713953 0 -0.8819221 -0.4713953 0 -0.9569408 -0.2902835 0 -0.9951832 -0.09803277 0 -0.9951866 0.09799826 0 -0.9569408 0.2902835 0 -0.8819221 0.4713953 0 0 0 1 -0.2902767 0.9569428 0 -0.09802156 0.9951843 0 -2.16887e-7 0 -1 0.2902891 0.9569391 0 0.47139 0.8819248 0 0.6343942 0.7730097 0 0.7730142 0.6343888 0 0.8819205 0.4713982 0 0.9569391 0.290289 0 0.995185 -0.09801518 0 0.9569405 -0.290284 0 -0.9569405 -0.290284 0 -0.995185 -0.09801518 0 -0.9569391 0.290289 0 -0.8819205 0.4713982 0 -0.7730142 0.6343888 0 -0.6343911 0.7730123 0 -0.47139 0.8819248 0 -0.2902891 0.9569391 0 0.9569408 -0.2902835 0 -0.9951849 -0.09801548 0 -0.9951849 0.09801548 0 -0.09801989 0.9951846 0 0.2902873 0.9569396 0 -0.9569423 -0.2902783 0 -0.9951843 -0.09802144 0 -0.2902873 0.9569396 0 1 0 0 0.09801393 0.9951851 0 0.2902822 0.9569412 0 0.4714006 0.8819193 0 0.6343882 0.7730147 0 0.773012 0.6343914 0 0.9951849 0.09801608 0 0.9951849 -0.09801608 0 0.7730034 -0.6344019 0 0.6343967 -0.7730076 0 0.4714006 -0.8819193 0 0.2902822 -0.9569412 0 0.09801566 -0.995185 0 -0.09801393 -0.9951851 0 -0.2902822 -0.9569412 0 -0.4714078 -0.8819155 0 -0.6343882 -0.7730147 0 -0.773012 -0.6343914 0 -0.9951849 -0.09801608 0 -0.9951849 0.09801608 0 -0.7730034 0.6344019 0 -0.6343967 0.7730076 0 -0.4713933 0.8819231 0 7.48969e-7 0 1 5.99118e-6 0 1 1.1983e-5 0 1 1.19832e-5 0 1 -7.48898e-7 0 1 -5.99132e-6 0 1 -1.19832e-5 0 1 -1.19829e-5 0 1 -5.99118e-6 0 1 -1.08296e-6 0 1 1.08295e-6 0 1 -1.79676e-7 0 1 -0.2902822 0.9569412 0 -0.09801733 0.9951847 0 -1.01156e-6 0 -1 2.99559e-6 0 -1 -2.06271e-6 0 -1 4.04609e-6 0 -1 1.49787e-6 0 -1 1.01152e-6 0 -1 -2.99573e-6 0 -1 2.06271e-6 0 -1 -4.04609e-6 0 -1 -1.4978e-6 0 -1 1.08296e-6 0 -1 -1.08296e-6 0 -1 0.2902861 0.9569399 0 0.4713978 0.8819208 0 0.6343924 0.7730112 0 0.7730098 0.6343941 0 0.8819212 0.4713969 0 0.9569411 0.2902823 0 0.9569391 -0.290289 0 0.8819212 -0.4713969 0 0.773013 -0.6343904 0 0.6343944 -0.7730097 0 0.4713951 -0.8819222 0 0.2902843 -0.9569405 0 0.09801501 -0.995185 0 -0.09801441 -0.9951851 0 -0.2902843 -0.9569405 0 -0.4713951 -0.8819222 0 -0.6343912 -0.7730122 0 -0.773013 -0.6343904 0 -0.8819212 -0.4713969 0 -0.9569391 -0.290289 0 -0.9951843 0.09802204 0 -0.9569429 0.2902765 0 -0.8819212 0.4713969 0 -0.7730098 0.6343941 0 -0.6343955 0.7730087 0 -0.4713978 0.8819208 0 -4.30512e-7 0 1 1.722e-6 0 1 -1.722e-6 0 1 1.24675e-7 0 1 -1.24675e-7 0 1 0 0 1 -0.2902861 0.9569399 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.9569369 0.2902961 0 0.773012 -0.6343914 0 -0.4714006 -0.8819193 0 -0.9951866 -0.09799879 0 -0.9951832 0.09803336 0 -0.773012 0.6343914 0 0.2902843 0.9569405 0 0.6343955 0.7730087 0 0.7730067 0.6343979 0 0.8819239 0.471392 0 0.9951843 -0.09802204 0 0.2902861 -0.9569399 0 0.09801441 -0.9951851 0 -0.2902861 -0.9569399 0 -0.9569411 0.2902823 0 -0.2902843 0.9569405 0 -0.09801816 0.9951847 0 0.09801983 0.9951846 0 0.9569359 0.2902995 0 0.995185 0.09801548 0 0.995185 -0.09801548 0 -0.9951866 -0.0979982 0 -0.9951833 0.09803277 0 2.99617e-6 0 1 -1.01133e-6 0 1 5.99175e-6 0 1 5.99147e-6 0 1 1.19821e-5 0 1 5.99233e-6 0 1 -7.48969e-7 0 1 4.12555e-6 0 1 -5.99147e-6 0 1 -1.19822e-5 0 1 -1.19821e-5 0 1 -5.99175e-6 0 1 -5.86095e-7 0 1 -0.09802156 0.9951843 0 -2.06274e-6 0 -1 4.0459e-6 0 -1 1.49794e-6 0 -1 -2.99588e-6 0 -1 2.06274e-6 0 -1 -4.04583e-6 0 -1 1.79676e-7 0 -1 0.4713927 0.8819234 0 0.6343974 0.7730071 0 0.773008 0.6343964 0 0.8819231 0.4713934 0 0.9569408 0.2902832 0 0.9951844 -0.09802144 0 0.9569388 -0.2902899 0 -0.9569388 -0.2902899 0 -0.995185 -0.09801512 0 -0.9569408 0.2902832 0 -0.8819205 0.4713982 0 -0.773011 0.6343926 0 -0.6343974 0.7730071 0 -0.4713927 0.8819234 0 4.30512e-7 0 1 -8.61024e-7 0 1 1.72195e-6 0 1 -1.72195e-6 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.995185 -0.09801548 0 -0.995185 0.09801548 0 -0.09802323 0.9951841 0 -0.9569426 0.2902774 0 0.6343944 0.7730097 0 0.773011 0.6343926 0 0.8819205 0.4713982 0 0.995185 -0.09801512 0 - - - - - - - - - - 0.3532367 0.4109067 0.4451267 0.4681466 0.3532367 0.4681466 0.3532367 0.5648227 0.4451267 0.4681466 0.4451267 0.5648227 0.5023667 0.4681466 0.4451267 0.5648227 0.4451267 0.4681466 0.3532367 0.6220626 0.4451267 0.7187388 0.3532367 0.7187388 0.4376942 0.9356175 0.4376942 0.9370717 0.4376942 0.9370717 0.4451267 0.6220626 0.3532367 0.5648227 0.4451267 0.5648227 0.3675158 0.843872 0.3442469 0.8453262 0.3442469 0.843872 0.3675158 0.8453262 0.3442469 0.8467807 0.3442469 0.8453262 0.3675158 0.8467807 0.3442469 0.8482348 0.3442469 0.8467807 0.3675158 0.8482348 0.3442469 0.8496892 0.3442469 0.8482348 0.3675158 0.8496892 0.3442469 0.8511435 0.3442469 0.8496892 0.3675158 0.8511435 0.3442469 0.8525979 0.3442469 0.8511435 0.3675158 0.8525979 0.3442469 0.8540522 0.3442469 0.8525979 0.3675158 0.8540522 0.3442469 0.8555065 0.3442469 0.8540522 0.3675158 0.8555065 0.3442469 0.8569609 0.3442469 0.8555065 0.3675158 0.8569609 0.3442469 0.8584151 0.3442469 0.8569609 0.3675158 0.8584151 0.3442469 0.8598694 0.3442469 0.8584151 0.3675158 0.8598694 0.3442469 0.8613237 0.3442469 0.8598694 0.3675158 0.8613237 0.3442469 0.8627781 0.3442469 0.8613237 0.3675158 0.8627781 0.3442469 0.8642324 0.3442469 0.8627781 0.3675158 0.8642324 0.3442469 0.8656867 0.3442469 0.8642324 0.3675158 0.8656867 0.3442469 0.8671411 0.3442469 0.8656867 0.3675158 0.8671411 0.3442469 0.8685953 0.3442469 0.8671411 0.3675158 0.8685953 0.3442469 0.8700496 0.3442469 0.8685953 0.3675158 0.8700496 0.3442469 0.8715039 0.3442469 0.8700496 0.3675158 0.8715039 0.3442469 0.8729583 0.3442469 0.8715039 0.3675158 0.8729583 0.3442469 0.8744126 0.3442469 0.8729583 0.3675158 0.8744126 0.3442469 0.8758669 0.3442469 0.8744126 0.3675158 0.8758669 0.3442469 0.8773211 0.3442469 0.8758669 0.3675158 0.8773211 0.3442469 0.8787754 0.3442469 0.8773211 0.3675158 0.8787754 0.3442469 0.8802298 0.3442469 0.8787754 0.3675158 0.8802298 0.3442469 0.8816841 0.3442469 0.8802298 0.3675158 0.8816841 0.3442469 0.8831384 0.3442469 0.8816841 0.3675158 0.8831384 0.3442469 0.8845928 0.3442469 0.8831384 0.3675158 0.8845928 0.3442469 0.8860471 0.3442469 0.8845928 0.3675158 0.8860471 0.3442469 0.8875013 0.3442469 0.8860471 0.3446739 0.9450687 0.3586043 0.9376227 0.3660504 0.9515531 0.3675158 0.8875013 0.3442469 0.8889556 0.3442469 0.8875013 0.3675158 0.8889556 0.3442469 0.89041 0.3442469 0.8889556 0.4600486 0.9229089 0.4478385 0.9128882 0.437818 0.9250984 0.3909085 0.843872 0.3676396 0.8453262 0.3676396 0.843872 0.3909085 0.8453262 0.3676396 0.8467807 0.3676396 0.8453262 0.3909085 0.8467807 0.3676396 0.8482348 0.3676396 0.8467807 0.3909085 0.8482348 0.3676396 0.8496892 0.3676396 0.8482348 0.3909085 0.8496892 0.3676396 0.8511435 0.3676396 0.8496892 0.3909085 0.8511435 0.3676396 0.8525979 0.3676396 0.8511435 0.3909085 0.8525979 0.3676396 0.8540522 0.3676396 0.8525979 0.3909085 0.8540522 0.3676396 0.8555065 0.3676396 0.8540522 0.3909085 0.8555065 0.3676396 0.8569609 0.3676396 0.8555065 0.3909085 0.8569609 0.3676396 0.8584151 0.3676396 0.8569609 0.3909085 0.8584151 0.3676396 0.8598694 0.3676396 0.8584151 0.3909085 0.8598694 0.3676396 0.8613237 0.3676396 0.8598694 0.3909085 0.8613237 0.3676396 0.8627781 0.3676396 0.8613237 0.3909085 0.8627781 0.3676396 0.8642324 0.3676396 0.8627781 0.3909085 0.8642324 0.3676396 0.8656867 0.3676396 0.8642324 0.3909085 0.8656867 0.3676396 0.8671411 0.3676396 0.8656867 0.3909085 0.8671411 0.3676396 0.8685953 0.3676396 0.8671411 0.3909085 0.8685953 0.3676396 0.8700496 0.3676396 0.8685953 0.3909085 0.8700496 0.3676396 0.8715039 0.3676396 0.8700496 0.3909085 0.8715039 0.3676396 0.8729583 0.3676396 0.8715039 0.3909085 0.8729583 0.3676396 0.8744126 0.3676396 0.8729583 0.3909085 0.8744126 0.3676396 0.8758669 0.3676396 0.8744126 0.3909085 0.8758669 0.3676396 0.8773211 0.3676396 0.8758669 0.3909085 0.8773211 0.3676396 0.8787754 0.3676396 0.8773211 0.3909085 0.8787754 0.3676396 0.8802298 0.3676396 0.8787754 0.3909085 0.8802298 0.3676396 0.8816841 0.3676396 0.8802298 0.3909085 0.8816841 0.3676396 0.8831384 0.3676396 0.8816841 0.3909085 0.8831384 0.3676396 0.8845928 0.3676396 0.8831384 0.3909085 0.8845928 0.3676396 0.8860471 0.3676396 0.8845928 0.3909085 0.8860471 0.3676396 0.8875013 0.3676396 0.8860471 0.3755126 0.958999 0.3680667 0.9450687 0.3819971 0.9376227 0.3909085 0.8875013 0.3676396 0.8889556 0.3676396 0.8875013 0.3909085 0.8889556 0.3676396 0.89041 0.3676396 0.8889556 0.4703059 0.9594261 0.4803264 0.947216 0.4681164 0.9371955 0.4143013 0.843872 0.3910323 0.8453262 0.3910323 0.843872 0.4143013 0.8453262 0.3910323 0.8467807 0.3910323 0.8453262 0.4143013 0.8467807 0.3910323 0.8482348 0.3910323 0.8467807 0.4143013 0.8482348 0.3910323 0.8496892 0.3910323 0.8482348 0.4143013 0.8496892 0.3910323 0.8511435 0.3910323 0.8496892 0.4143013 0.8511435 0.3910323 0.8525979 0.3910323 0.8511435 0.4143013 0.8525979 0.3910323 0.8540522 0.3910323 0.8525979 0.4143013 0.8540522 0.3910323 0.8555065 0.3910323 0.8540522 0.4143013 0.8555065 0.3910323 0.8569609 0.3910323 0.8555065 0.4143013 0.8569609 0.3910323 0.8584151 0.3910323 0.8569609 0.4143013 0.8584151 0.3910323 0.8598694 0.3910323 0.8584151 0.4143013 0.8598694 0.3910323 0.8613237 0.3910323 0.8598694 0.4143013 0.8613237 0.3910323 0.8627781 0.3910323 0.8613237 0.4143013 0.8627781 0.3910323 0.8642324 0.3910323 0.8627781 0.4143013 0.8642324 0.3910323 0.8656867 0.3910323 0.8642324 0.4143013 0.8656867 0.3910323 0.8671411 0.3910323 0.8656867 0.4143013 0.8671411 0.3910323 0.8685953 0.3910323 0.8671411 0.4143013 0.8685953 0.3910323 0.8700496 0.3910323 0.8685953 0.4143013 0.8700496 0.3910323 0.8715039 0.3910323 0.8700496 0.4143013 0.8715039 0.3910323 0.8729583 0.3910323 0.8715039 0.4143013 0.8729583 0.3910323 0.8744126 0.3910323 0.8729583 0.4143013 0.8744126 0.3910323 0.8758669 0.3910323 0.8744126 0.4143013 0.8758669 0.3910323 0.8773211 0.3910323 0.8758669 0.4143013 0.8773211 0.3910323 0.8787754 0.3910323 0.8773211 0.4143013 0.8787754 0.3910323 0.8802298 0.3910323 0.8787754 0.4143013 0.8802298 0.3910323 0.8816841 0.3910323 0.8802298 0.4143013 0.8816841 0.3910323 0.8831384 0.3910323 0.8816841 0.4143013 0.8831384 0.3910323 0.8845928 0.3910323 0.8831384 0.4143013 0.8845928 0.3910323 0.8860471 0.3910323 0.8845928 0.4143013 0.8860471 0.3910323 0.8875013 0.3910323 0.8860471 0.3914595 0.9450687 0.40539 0.9376227 0.4128358 0.9515531 0.4143013 0.8875013 0.3910323 0.8889556 0.3910323 0.8875013 0.4143013 0.8889556 0.3910323 0.89041 0.3910323 0.8889556 0.3664774 0.9695706 0.3542674 0.9595499 0.3442469 0.97176 0.3675158 0.8905338 0.3442469 0.8919881 0.3442469 0.8905338 0.3675158 0.8919881 0.3442469 0.8934424 0.3442469 0.8919881 0.3675158 0.8934424 0.3442469 0.8948968 0.3442469 0.8934424 0.3675158 0.8948968 0.3442469 0.8963511 0.3442469 0.8948968 0.3675158 0.8963511 0.3442469 0.8978053 0.3442469 0.8963511 0.3675158 0.8978053 0.3442469 0.8992596 0.3442469 0.8978053 0.3675158 0.8992596 0.3442469 0.9007139 0.3442469 0.8992596 0.3675158 0.9007139 0.3442469 0.9021683 0.3442469 0.9007139 0.3675158 0.9021683 0.3442469 0.9036226 0.3442469 0.9021683 0.3675158 0.9036226 0.3442469 0.9050769 0.3442469 0.9036226 0.3675158 0.9050769 0.3442469 0.9065311 0.3442469 0.9050769 0.3675158 0.9065311 0.3442469 0.9079855 0.3442469 0.9065311 0.3675158 0.9079855 0.3442469 0.9094398 0.3442469 0.9079855 0.3675158 0.9094398 0.3442469 0.9108941 0.3442469 0.9094398 0.3675158 0.9108941 0.3442469 0.9123485 0.3442469 0.9108941 0.3675158 0.9123485 0.3442469 0.9138028 0.3442469 0.9123485 0.3675158 0.9138028 0.3442469 0.9152571 0.3442469 0.9138028 0.3675158 0.9152571 0.3442469 0.9167113 0.3442469 0.9152571 0.3675158 0.9167113 0.3442469 0.9181656 0.3442469 0.9167113 0.3675158 0.9181656 0.3442469 0.91962 0.3442469 0.9181656 0.3675158 0.91962 0.3442469 0.9210743 0.3442469 0.91962 0.3675158 0.9210743 0.3442469 0.9225286 0.3442469 0.9210743 0.3675158 0.9225286 0.3442469 0.923983 0.3442469 0.9225286 0.3675158 0.923983 0.3442469 0.9254373 0.3442469 0.923983 0.3675158 0.9254373 0.3442469 0.9268915 0.3442469 0.9254373 0.3675158 0.9268915 0.3442469 0.928346 0.3442469 0.9268915 0.3675158 0.928346 0.3442469 0.9298002 0.3442469 0.928346 0.3675158 0.9298002 0.3442469 0.9312545 0.3442469 0.9298002 0.3675158 0.9312545 0.3442469 0.9327088 0.3442469 0.9312545 0.3675158 0.9327088 0.3442469 0.9341632 0.3442469 0.9327088 0.4212599 0.958999 0.4138139 0.9450687 0.4277444 0.9376227 0.3675158 0.9341632 0.3442469 0.9356175 0.3442469 0.9341632 0.3675158 0.9356175 0.3442469 0.9370717 0.3442469 0.9356175 0.3788114 0.9817806 0.3888319 0.9695706 0.3766219 0.9595499 0.3909085 0.8905338 0.3676396 0.8919881 0.3676396 0.8905338 0.3909085 0.8919881 0.3676396 0.8934424 0.3676396 0.8919881 0.3909085 0.8934424 0.3676396 0.8948968 0.3676396 0.8934424 0.3909085 0.8948968 0.3676396 0.8963511 0.3676396 0.8948968 0.3909085 0.8963511 0.3676396 0.8978053 0.3676396 0.8963511 0.3909085 0.8978053 0.3676396 0.8992596 0.3676396 0.8978053 0.3909085 0.8992596 0.3676396 0.9007139 0.3676396 0.8992596 0.3909085 0.9007139 0.3676396 0.9021683 0.3676396 0.9007139 0.3909085 0.9021683 0.3676396 0.9036226 0.3676396 0.9021683 0.3909085 0.9036226 0.3676396 0.9050769 0.3676396 0.9036226 0.3909085 0.9050769 0.3676396 0.9065311 0.3676396 0.9050769 0.3909085 0.9065311 0.3676396 0.9079855 0.3676396 0.9065311 0.3909085 0.9079855 0.3676396 0.9094398 0.3676396 0.9079855 0.3909085 0.9094398 0.3676396 0.9108941 0.3676396 0.9094398 0.3909085 0.9108941 0.3676396 0.9123485 0.3676396 0.9108941 0.3909085 0.9123485 0.3676396 0.9138028 0.3676396 0.9123485 0.3909085 0.9138028 0.3676396 0.9152571 0.3676396 0.9138028 0.3909085 0.9152571 0.3676396 0.9167113 0.3676396 0.9152571 0.3909085 0.9167113 0.3676396 0.9181656 0.3676396 0.9167113 0.3909085 0.9181656 0.3676396 0.91962 0.3676396 0.9181656 0.3909085 0.91962 0.3676396 0.9210743 0.3676396 0.91962 0.3909085 0.9210743 0.3676396 0.9225286 0.3676396 0.9210743 0.3909085 0.9225286 0.3676396 0.923983 0.3676396 0.9225286 0.3909085 0.923983 0.3676396 0.9254373 0.3676396 0.923983 0.3909085 0.9254373 0.3676396 0.9268915 0.3676396 0.9254373 0.3909085 0.9268915 0.3676396 0.928346 0.3676396 0.9268915 0.3909085 0.928346 0.3676396 0.9298002 0.3676396 0.928346 0.3909085 0.9298002 0.3676396 0.9312545 0.3676396 0.9298002 0.3909085 0.9312545 0.3676396 0.9327088 0.3676396 0.9312545 0.3909085 0.9327088 0.3676396 0.9341632 0.3676396 0.9327088 0.4436144 0.958999 0.4361684 0.9450687 0.4500988 0.9376227 0.3909085 0.9341632 0.3676396 0.9356175 0.3676396 0.9341632 0.3909085 0.9356175 0.3676396 0.9370717 0.3676396 0.9356175 0.4000146 0.9595499 0.3924755 0.9635797 0.389994 0.97176 0.4143013 0.8905338 0.3910323 0.8919881 0.3910323 0.8905338 0.4143013 0.8919881 0.3910323 0.8934424 0.3910323 0.8919881 0.4143013 0.8934424 0.3910323 0.8948968 0.3910323 0.8934424 0.4143013 0.8948968 0.3910323 0.8963511 0.3910323 0.8948968 0.4143013 0.8963511 0.3910323 0.8978053 0.3910323 0.8963511 0.4143013 0.8978053 0.3910323 0.8992596 0.3910323 0.8978053 0.4143013 0.8992596 0.3910323 0.9007139 0.3910323 0.8992596 0.4143013 0.9007139 0.3910323 0.9021683 0.3910323 0.9007139 0.4143013 0.9021683 0.3910323 0.9036226 0.3910323 0.9021683 0.4143013 0.9036226 0.3910323 0.9050769 0.3910323 0.9036226 0.4143013 0.9050769 0.3910323 0.9065311 0.3910323 0.9050769 0.4143013 0.9065311 0.3910323 0.9079855 0.3910323 0.9065311 0.4143013 0.9079855 0.3910323 0.9094398 0.3910323 0.9079855 0.4143013 0.9094398 0.3910323 0.9108941 0.3910323 0.9094398 0.4143013 0.9108941 0.3910323 0.9123485 0.3910323 0.9108941 0.4143013 0.9123485 0.3910323 0.9138028 0.3910323 0.9123485 0.4143013 0.9138028 0.3910323 0.9152571 0.3910323 0.9138028 0.4143013 0.9152571 0.3910323 0.9167113 0.3910323 0.9152571 0.4143013 0.9167113 0.3910323 0.9181656 0.3910323 0.9167113 0.4143013 0.9181656 0.3910323 0.91962 0.3910323 0.9181656 0.4143013 0.91962 0.3910323 0.9210743 0.3910323 0.91962 0.4143013 0.9210743 0.3910323 0.9225286 0.3910323 0.9210743 0.4143013 0.9225286 0.3910323 0.923983 0.3910323 0.9225286 0.4143013 0.923983 0.3910323 0.9254373 0.3910323 0.923983 0.4143013 0.9254373 0.3910323 0.9268915 0.3910323 0.9254373 0.4143013 0.9268915 0.3910323 0.928346 0.3910323 0.9268915 0.4143013 0.928346 0.3910323 0.9298002 0.3910323 0.928346 0.4143013 0.9298002 0.3910323 0.9312545 0.3910323 0.9298002 0.4143013 0.9312545 0.3910323 0.9327088 0.3910323 0.9312545 0.4143013 0.9327088 0.3910323 0.9341632 0.3910323 0.9327088 0.4382451 0.851745 0.4521755 0.8442991 0.4596215 0.8582295 0.4143013 0.9341632 0.3910323 0.9356175 0.3910323 0.9341632 0.4143013 0.9356175 0.3910323 0.9370717 0.3910323 0.9356175 0.425597 0.9817806 0.4356175 0.9695706 0.4234074 0.9595499 0.4376942 0.843872 0.4144251 0.8453262 0.4144251 0.843872 0.4376942 0.8453262 0.4144251 0.8467807 0.4144251 0.8453262 0.4376942 0.8467807 0.4144251 0.8482348 0.4144251 0.8467807 0.4376942 0.8482348 0.4144251 0.8496892 0.4144251 0.8482348 0.4376942 0.8496892 0.4144251 0.8511435 0.4144251 0.8496892 0.4376942 0.8511435 0.4144251 0.8525979 0.4144251 0.8511435 0.4376942 0.8525979 0.4144251 0.8540522 0.4144251 0.8525979 0.4376942 0.8540522 0.4144251 0.8555065 0.4144251 0.8540522 0.4376942 0.8555065 0.4144251 0.8569609 0.4144251 0.8555065 0.4376942 0.8569609 0.4144251 0.8584151 0.4144251 0.8569609 0.4376942 0.8584151 0.4144251 0.8598694 0.4144251 0.8584151 0.4376942 0.8598694 0.4144251 0.8613237 0.4144251 0.8598694 0.4376942 0.8613237 0.4144251 0.8627781 0.4144251 0.8613237 0.4376942 0.8627781 0.4144251 0.8642324 0.4144251 0.8627781 0.4376942 0.8642324 0.4144251 0.8656867 0.4144251 0.8642324 0.4376942 0.8656867 0.4144251 0.8671411 0.4144251 0.8656867 0.4376942 0.8671411 0.4144251 0.8685953 0.4144251 0.8671411 0.4376942 0.8685953 0.4144251 0.8700496 0.4144251 0.8685953 0.4376942 0.8700496 0.4144251 0.8715039 0.4144251 0.8700496 0.4376942 0.8715039 0.4144251 0.8729583 0.4144251 0.8715039 0.4376942 0.8729583 0.4144251 0.8744126 0.4144251 0.8729583 0.4376942 0.8744126 0.4144251 0.8758669 0.4144251 0.8744126 0.4376942 0.8758669 0.4144251 0.8773211 0.4144251 0.8758669 0.4376942 0.8773211 0.4144251 0.8787754 0.4144251 0.8773211 0.4376942 0.8787754 0.4144251 0.8802298 0.4144251 0.8787754 0.4376942 0.8802298 0.4144251 0.8816841 0.4144251 0.8802298 0.4376942 0.8816841 0.4144251 0.8831384 0.4144251 0.8816841 0.4376942 0.8831384 0.4144251 0.8845928 0.4144251 0.8831384 0.4376942 0.8845928 0.4144251 0.8860471 0.4144251 0.8845928 0.4376942 0.8860471 0.4144251 0.8875013 0.4144251 0.8860471 0.445691 0.8880299 0.4382451 0.8740995 0.4521755 0.8666536 0.4376942 0.8875013 0.4144251 0.8889556 0.4144251 0.8875013 0.4376942 0.8889556 0.4144251 0.89041 0.4144251 0.8889556 0.4457618 0.9595499 0.4382228 0.9635797 0.4357413 0.97176 0.4376942 0.8905338 0.4144251 0.8919881 0.4144251 0.8905338 0.4376942 0.8919881 0.4144251 0.8934424 0.4144251 0.8919881 0.4376942 0.8905338 0.4376942 0.8919881 0.4376942 0.8919881 0.4376942 0.9225286 0.4376942 0.923983 0.4376942 0.923983 0.4798992 0.9739076 0.4803264 0.97176 0.4803264 0.97176 0.4639459 0.9805157 0.4659689 0.9813535 0.4659689 0.9813535 0.4376942 0.928346 0.4376942 0.9298002 0.4376942 0.9298002 0.4376942 0.9152571 0.4376942 0.9167113 0.4376942 0.9167113 0.4724533 0.9813535 0.474476 0.9805157 0.474476 0.9805157 0.4376942 0.9341632 0.4376942 0.9356175 0.4376942 0.9356175 0.4376942 0.9210743 0.4376942 0.9225286 0.4376942 0.9225286 0.3532367 0.6220626 0.3532367 0.5648227 0.3532367 0.5648227 0.4790613 0.9759305 0.4798992 0.9739076 0.4798992 0.9739076 0.4621254 0.9792992 0.4639459 0.9805157 0.4639459 0.9805157 0.4376942 0.9268915 0.4376942 0.928346 0.4376942 0.928346 0.4376942 0.9138028 0.4376942 0.9152571 0.4376942 0.9152571 0.4376942 0.9138028 0.4144251 0.9152571 0.4144251 0.9138028 0.4376942 0.9152571 0.4144251 0.9167113 0.4144251 0.9152571 0.4376942 0.9167113 0.4144251 0.9181656 0.4144251 0.9167113 0.4376942 0.9181656 0.4144251 0.91962 0.4144251 0.9181656 0.4376942 0.91962 0.4144251 0.9210743 0.4144251 0.91962 0.4376942 0.9210743 0.4144251 0.9225286 0.4144251 0.9210743 0.4376942 0.9225286 0.4144251 0.923983 0.4144251 0.9225286 0.4376942 0.923983 0.4144251 0.9254373 0.4144251 0.923983 0.4376942 0.9254373 0.4144251 0.9268915 0.4144251 0.9254373 0.4376942 0.9268915 0.4144251 0.928346 0.4144251 0.9268915 0.4376942 0.928346 0.4144251 0.9298002 0.4144251 0.928346 0.4376942 0.9298002 0.4144251 0.9312545 0.4144251 0.9298002 0.4376942 0.9312545 0.4144251 0.9327088 0.4144251 0.9312545 0.4376942 0.9327088 0.4144251 0.9341632 0.4144251 0.9327088 0.3532367 0.7187388 0.3532367 0.6220626 0.3532367 0.6220626 0.4376942 0.9341632 0.4144251 0.9356175 0.4144251 0.9341632 0.4376942 0.9356175 0.4144251 0.9370717 0.4144251 0.9356175 0.4703059 0.9817806 0.4803264 0.9695706 0.4681164 0.9595499 0.2959966 0.5648227 0.3532367 0.4681466 0.3532367 0.5648227 0.4376942 0.8934424 0.4144251 0.8948968 0.4144251 0.8934424 0.4376942 0.8948968 0.4144251 0.8963511 0.4144251 0.8948968 0.4376942 0.8963511 0.4144251 0.8978053 0.4144251 0.8963511 0.4376942 0.8978053 0.4144251 0.8992596 0.4144251 0.8978053 0.4376942 0.8992596 0.4144251 0.9007139 0.4144251 0.8992596 0.4376942 0.9007139 0.4144251 0.9021683 0.4144251 0.9007139 0.4376942 0.9021683 0.4144251 0.9036226 0.4144251 0.9021683 0.4376942 0.9036226 0.4144251 0.9050769 0.4144251 0.9036226 0.4376942 0.9050769 0.4144251 0.9065311 0.4144251 0.9050769 0.4376942 0.9065311 0.4144251 0.9079855 0.4144251 0.9065311 0.4376942 0.9079855 0.4144251 0.9094398 0.4144251 0.9079855 0.4376942 0.9094398 0.4144251 0.9108941 0.4144251 0.9094398 0.4376942 0.9108941 0.4144251 0.9123485 0.4144251 0.9108941 0.4376942 0.9123485 0.4144251 0.9138028 0.4144251 0.9123485 0.4382451 0.8984069 0.4521755 0.8909608 0.4596215 0.9048914 0.474476 0.9805157 0.4762967 0.9792992 0.4762967 0.9792992 0.4376942 0.9167113 0.4376942 0.9181656 0.4376942 0.9181656 0.4376942 0.9298002 0.4376942 0.9312545 0.4376942 0.9312545 0.4659689 0.9813535 0.4681164 0.9817806 0.4681164 0.9817806 0.4803264 0.97176 0.4803264 0.9695706 0.4803264 0.9695706 0.4376942 0.923983 0.4376942 0.9254373 0.4376942 0.9254373 0.4762967 0.9792992 0.4778449 0.977751 0.4778449 0.977751 0.4376942 0.8919881 0.4376942 0.8934424 0.4376942 0.8934424 0.4376942 0.9181656 0.4376942 0.91962 0.4376942 0.91962 0.4376942 0.9312545 0.4376942 0.9327088 0.4376942 0.9327088 0.4681164 0.9817806 0.4703059 0.9817806 0.4703059 0.9817806 0.4803264 0.9695706 0.4798992 0.9674231 0.4798992 0.9674231 0.4376942 0.8934424 0.4144251 0.8934424 0.4144251 0.8934424 0.4376942 0.9254373 0.4376942 0.9268915 0.4376942 0.9268915 0.4605772 0.977751 0.4621254 0.9792992 0.4621254 0.9792992 0.4778449 0.977751 0.4790613 0.9759305 0.4790613 0.9759305 0.3532367 0.4681466 0.3532367 0.4109067 0.3532367 0.4109067 0.4144251 0.9138028 0.4376942 0.9138028 0.4376942 0.9138028 0.3532367 0.5648227 0.3532367 0.4681466 0.3532367 0.4681466 0.4376942 0.91962 0.4376942 0.9210743 0.4376942 0.9210743 0.4376942 0.9327088 0.4376942 0.9341632 0.4376942 0.9341632 0.4703059 0.9817806 0.4724533 0.9813535 0.4724533 0.9813535 0.3532367 0.4109067 0.4451267 0.4109067 0.4451267 0.4681466 0.3532367 0.5648227 0.3532367 0.4681466 0.4451267 0.4681466 0.5023667 0.4681466 0.5023666 0.5648227 0.4451267 0.5648227 0.3532367 0.6220626 0.4451267 0.6220626 0.4451267 0.7187388 0.4376942 0.9356175 0.4376942 0.9356175 0.4376942 0.9370717 0.4451267 0.6220626 0.3532367 0.6220626 0.3532367 0.5648227 0.3675158 0.843872 0.3675158 0.8453262 0.3442469 0.8453262 0.3675158 0.8453262 0.3675158 0.8467807 0.3442469 0.8467807 0.3675158 0.8467807 0.3675158 0.8482348 0.3442469 0.8482348 0.3675158 0.8482348 0.3675158 0.8496892 0.3442469 0.8496892 0.3675158 0.8496892 0.3675158 0.8511435 0.3442469 0.8511435 0.3675158 0.8511435 0.3675158 0.8525979 0.3442469 0.8525979 0.3675158 0.8525979 0.3675158 0.8540522 0.3442469 0.8540522 0.3675158 0.8540522 0.3675158 0.8555065 0.3442469 0.8555065 0.3675158 0.8555065 0.3675158 0.8569609 0.3442469 0.8569609 0.3675158 0.8569609 0.3675158 0.8584151 0.3442469 0.8584151 0.3675158 0.8584151 0.3675158 0.8598694 0.3442469 0.8598694 0.3675158 0.8598694 0.3675158 0.8613237 0.3442469 0.8613237 0.3675158 0.8613237 0.3675158 0.8627781 0.3442469 0.8627781 0.3675158 0.8627781 0.3675158 0.8642324 0.3442469 0.8642324 0.3675158 0.8642324 0.3675158 0.8656867 0.3442469 0.8656867 0.3675158 0.8656867 0.3675158 0.8671411 0.3442469 0.8671411 0.3675158 0.8671411 0.3675158 0.8685953 0.3442469 0.8685953 0.3675158 0.8685953 0.3675158 0.8700496 0.3442469 0.8700496 0.3675158 0.8700496 0.3675158 0.8715039 0.3442469 0.8715039 0.3675158 0.8715039 0.3675158 0.8729583 0.3442469 0.8729583 0.3675158 0.8729583 0.3675158 0.8744126 0.3442469 0.8744126 0.3675158 0.8744126 0.3675158 0.8758669 0.3442469 0.8758669 0.3675158 0.8758669 0.3675158 0.8773211 0.3442469 0.8773211 0.3675158 0.8773211 0.3675158 0.8787754 0.3442469 0.8787754 0.3675158 0.8787754 0.3675158 0.8802298 0.3442469 0.8802298 0.3675158 0.8802298 0.3675158 0.8816841 0.3442469 0.8816841 0.3675158 0.8816841 0.3675158 0.8831384 0.3442469 0.8831384 0.3675158 0.8831384 0.3675158 0.8845928 0.3442469 0.8845928 0.3675158 0.8845928 0.3675158 0.8860471 0.3442469 0.8860471 0.3675158 0.8860471 0.3675158 0.8875013 0.3442469 0.8875013 0.3660504 0.9515531 0.3652124 0.953576 0.363996 0.9553965 0.363996 0.9553965 0.3624477 0.9569447 0.3606272 0.9581611 0.3606272 0.9581611 0.3586043 0.958999 0.3521199 0.958999 0.3586043 0.958999 0.3564569 0.9594261 0.3521199 0.958999 0.3564569 0.9594261 0.3542674 0.9594261 0.3521199 0.958999 0.3521199 0.958999 0.350097 0.9581611 0.3482764 0.9569447 0.3482764 0.9569447 0.3467283 0.9553965 0.3455118 0.953576 0.3455118 0.953576 0.3446739 0.9515531 0.3442469 0.9494056 0.3442469 0.9494056 0.3442469 0.9472162 0.3455118 0.953576 0.3442469 0.9472162 0.3446739 0.9450687 0.3455118 0.953576 0.3446739 0.9450687 0.3455118 0.9430459 0.3467283 0.9412252 0.3467283 0.9412252 0.3482764 0.9396771 0.350097 0.9384607 0.350097 0.9384607 0.3521199 0.9376227 0.3586043 0.9376227 0.3521199 0.9376227 0.3542674 0.9371955 0.3586043 0.9376227 0.3542674 0.9371955 0.3564569 0.9371955 0.3586043 0.9376227 0.3586043 0.9376227 0.3606272 0.9384607 0.3624477 0.9396771 0.3624477 0.9396771 0.363996 0.9412252 0.3652124 0.9430459 0.3652124 0.9430459 0.3660504 0.9450687 0.3664774 0.9472162 0.3664774 0.9472162 0.3664774 0.9494056 0.3652124 0.9430459 0.3664774 0.9494056 0.3660504 0.9515531 0.3652124 0.9430459 0.3660504 0.9515531 0.363996 0.9553965 0.3521199 0.958999 0.363996 0.9553965 0.3606272 0.9581611 0.3521199 0.958999 0.3521199 0.958999 0.3482764 0.9569447 0.3446739 0.9450687 0.3482764 0.9569447 0.3455118 0.953576 0.3446739 0.9450687 0.3446739 0.9450687 0.3467283 0.9412252 0.3586043 0.9376227 0.3467283 0.9412252 0.350097 0.9384607 0.3586043 0.9376227 0.3586043 0.9376227 0.3624477 0.9396771 0.3660504 0.9515531 0.3624477 0.9396771 0.3652124 0.9430459 0.3660504 0.9515531 0.3660504 0.9515531 0.3521199 0.958999 0.3446739 0.9450687 0.3675158 0.8875013 0.3675158 0.8889556 0.3442469 0.8889556 0.3675158 0.8889556 0.3675158 0.89041 0.3442469 0.89041 0.437818 0.9250984 0.4382451 0.9272457 0.4418476 0.9326375 0.4382451 0.9272457 0.4390829 0.9292686 0.4418476 0.9326375 0.4390829 0.9292686 0.4402994 0.9310891 0.4418476 0.9326375 0.4418476 0.9326375 0.4436681 0.9338538 0.445691 0.9346918 0.445691 0.9346918 0.4478385 0.9351189 0.4500281 0.9351189 0.4500281 0.9351189 0.4521755 0.9346918 0.457567 0.9310891 0.4521755 0.9346918 0.4541983 0.9338538 0.457567 0.9310891 0.4541983 0.9338538 0.4560188 0.9326375 0.457567 0.9310891 0.457567 0.9310891 0.4587835 0.9292686 0.4596215 0.9272457 0.4596215 0.9272457 0.4600486 0.9250984 0.4600486 0.9229089 0.4600486 0.9229089 0.4596215 0.9207614 0.4560188 0.9153698 0.4596215 0.9207614 0.4587835 0.9187385 0.4560188 0.9153698 0.4587835 0.9187385 0.457567 0.916918 0.4560188 0.9153698 0.4560188 0.9153698 0.4541983 0.9141532 0.4521755 0.9133153 0.4521755 0.9133153 0.4500281 0.9128882 0.4478385 0.9128882 0.4478385 0.9128882 0.445691 0.9133153 0.4402994 0.916918 0.445691 0.9133153 0.4436681 0.9141532 0.4402994 0.916918 0.4436681 0.9141532 0.4418476 0.9153698 0.4402994 0.916918 0.4402994 0.916918 0.4390829 0.9187385 0.4382451 0.9207614 0.4382451 0.9207614 0.437818 0.9229089 0.437818 0.9250984 0.4418476 0.9326375 0.445691 0.9346918 0.437818 0.9250984 0.445691 0.9346918 0.4500281 0.9351189 0.437818 0.9250984 0.457567 0.9310891 0.4596215 0.9272457 0.4500281 0.9351189 0.4596215 0.9272457 0.4600486 0.9229089 0.4500281 0.9351189 0.4560188 0.9153698 0.4521755 0.9133153 0.4600486 0.9229089 0.4521755 0.9133153 0.4478385 0.9128882 0.4600486 0.9229089 0.4402994 0.916918 0.4382451 0.9207614 0.4478385 0.9128882 0.4382451 0.9207614 0.437818 0.9250984 0.4478385 0.9128882 0.437818 0.9250984 0.4500281 0.9351189 0.4600486 0.9229089 0.3909085 0.843872 0.3909085 0.8453262 0.3676396 0.8453262 0.3909085 0.8453262 0.3909085 0.8467807 0.3676396 0.8467807 0.3909085 0.8467807 0.3909085 0.8482348 0.3676396 0.8482348 0.3909085 0.8482348 0.3909085 0.8496892 0.3676396 0.8496892 0.3909085 0.8496892 0.3909085 0.8511435 0.3676396 0.8511435 0.3909085 0.8511435 0.3909085 0.8525979 0.3676396 0.8525979 0.3909085 0.8525979 0.3909085 0.8540522 0.3676396 0.8540522 0.3909085 0.8540522 0.3909085 0.8555065 0.3676396 0.8555065 0.3909085 0.8555065 0.3909085 0.8569609 0.3676396 0.8569609 0.3909085 0.8569609 0.3909085 0.8584151 0.3676396 0.8584151 0.3909085 0.8584151 0.3909085 0.8598694 0.3676396 0.8598694 0.3909085 0.8598694 0.3909085 0.8613237 0.3676396 0.8613237 0.3909085 0.8613237 0.3909085 0.8627781 0.3676396 0.8627781 0.3909085 0.8627781 0.3909085 0.8642324 0.3676396 0.8642324 0.3909085 0.8642324 0.3909085 0.8656867 0.3676396 0.8656867 0.3909085 0.8656867 0.3909085 0.8671411 0.3676396 0.8671411 0.3909085 0.8671411 0.3909085 0.8685953 0.3676396 0.8685953 0.3909085 0.8685953 0.3909085 0.8700496 0.3676396 0.8700496 0.3909085 0.8700496 0.3909085 0.8715039 0.3676396 0.8715039 0.3909085 0.8715039 0.3909085 0.8729583 0.3676396 0.8729583 0.3909085 0.8729583 0.3909085 0.8744126 0.3676396 0.8744126 0.3909085 0.8744126 0.3909085 0.8758669 0.3676396 0.8758669 0.3909085 0.8758669 0.3909085 0.8773211 0.3676396 0.8773211 0.3909085 0.8773211 0.3909085 0.8787754 0.3676396 0.8787754 0.3909085 0.8787754 0.3909085 0.8802298 0.3676396 0.8802298 0.3909085 0.8802298 0.3909085 0.8816841 0.3676396 0.8816841 0.3909085 0.8816841 0.3909085 0.8831384 0.3676396 0.8831384 0.3909085 0.8831384 0.3909085 0.8845928 0.3676396 0.8845928 0.3909085 0.8845928 0.3909085 0.8860471 0.3676396 0.8860471 0.3909085 0.8860471 0.3909085 0.8875013 0.3676396 0.8875013 0.3894431 0.9515531 0.3886052 0.953576 0.3873887 0.9553965 0.3873887 0.9553965 0.3858405 0.9569447 0.3894431 0.9515531 0.3858405 0.9569447 0.38402 0.9581612 0.3894431 0.9515531 0.38402 0.9581612 0.3819971 0.958999 0.3755126 0.958999 0.3819971 0.958999 0.3798496 0.9594261 0.3755126 0.958999 0.3798496 0.9594261 0.3776601 0.9594261 0.3755126 0.958999 0.3755126 0.958999 0.3734898 0.9581612 0.3689047 0.953576 0.3734898 0.9581612 0.3716693 0.9569447 0.3689047 0.953576 0.3716693 0.9569447 0.3701211 0.9553965 0.3689047 0.953576 0.3689047 0.953576 0.3680667 0.9515531 0.3680667 0.9450687 0.3680667 0.9515531 0.3676396 0.9494056 0.3680667 0.9450687 0.3676396 0.9494056 0.3676396 0.9472162 0.3680667 0.9450687 0.3680667 0.9450687 0.3689047 0.9430459 0.3701211 0.9412252 0.3701211 0.9412252 0.3716693 0.9396771 0.3734899 0.9384607 0.3734899 0.9384607 0.3755127 0.9376227 0.3776601 0.9371955 0.3776601 0.9371955 0.3798496 0.9371955 0.3734899 0.9384607 0.3798496 0.9371955 0.3819971 0.9376227 0.3734899 0.9384607 0.3819971 0.9376227 0.38402 0.9384607 0.3858405 0.9396771 0.3858405 0.9396771 0.3873887 0.9412252 0.3819971 0.9376227 0.3873887 0.9412252 0.3886052 0.9430459 0.3819971 0.9376227 0.3886052 0.9430459 0.3894431 0.9450687 0.3894431 0.9515531 0.3894431 0.9450687 0.3898703 0.9472162 0.3894431 0.9515531 0.3898703 0.9472162 0.3898703 0.9494056 0.3894431 0.9515531 0.3680667 0.9450687 0.3701211 0.9412252 0.3819971 0.9376227 0.3701211 0.9412252 0.3734899 0.9384607 0.3819971 0.9376227 0.3894431 0.9515531 0.38402 0.9581612 0.3755126 0.958999 0.3755126 0.958999 0.3689047 0.953576 0.3680667 0.9450687 0.3819971 0.9376227 0.3886052 0.9430459 0.3894431 0.9515531 0.3894431 0.9515531 0.3755126 0.958999 0.3819971 0.9376227 0.3909085 0.8875013 0.3909085 0.8889556 0.3676396 0.8889556 0.3909085 0.8889556 0.3909085 0.89041 0.3676396 0.89041 0.4580957 0.9494056 0.4585229 0.9515531 0.4593607 0.953576 0.4593607 0.953576 0.4605772 0.9553965 0.4580957 0.9494056 0.4605772 0.9553965 0.4621254 0.9569447 0.4580957 0.9494056 0.4621254 0.9569447 0.4639459 0.9581611 0.4659689 0.958999 0.4659689 0.958999 0.4681164 0.9594261 0.4621254 0.9569447 0.4681164 0.9594261 0.4703059 0.9594261 0.4621254 0.9569447 0.4703059 0.9594261 0.4724533 0.958999 0.474476 0.9581611 0.474476 0.9581611 0.4762967 0.9569447 0.4703059 0.9594261 0.4762967 0.9569447 0.4778449 0.9553965 0.4703059 0.9594261 0.4778449 0.9553965 0.4790613 0.953576 0.4798992 0.9515531 0.4798992 0.9515531 0.4803264 0.9494056 0.4778449 0.9553965 0.4803264 0.9494056 0.4803264 0.947216 0.4778449 0.9553965 0.4803264 0.947216 0.4798992 0.9450687 0.4762967 0.9396771 0.4798992 0.9450687 0.4790613 0.9430459 0.4762967 0.9396771 0.4790613 0.9430459 0.4778449 0.9412252 0.4762967 0.9396771 0.4762967 0.9396771 0.474476 0.9384607 0.4724532 0.9376227 0.4724532 0.9376227 0.4703059 0.9371955 0.4681164 0.9371955 0.4681164 0.9371955 0.4659689 0.9376227 0.4639459 0.9384607 0.4639459 0.9384607 0.4621254 0.9396771 0.4605772 0.9412252 0.4605772 0.9412252 0.4593607 0.9430459 0.4585229 0.9450687 0.4585229 0.9450687 0.4580957 0.9472162 0.4605772 0.9412252 0.4580957 0.9472162 0.4580957 0.9494056 0.4605772 0.9412252 0.4762967 0.9396771 0.4724532 0.9376227 0.4803264 0.947216 0.4724532 0.9376227 0.4681164 0.9371955 0.4803264 0.947216 0.4681164 0.9371955 0.4639459 0.9384607 0.4580957 0.9494056 0.4639459 0.9384607 0.4605772 0.9412252 0.4580957 0.9494056 0.4580957 0.9494056 0.4621254 0.9569447 0.4703059 0.9594261 0.4703059 0.9594261 0.4778449 0.9553965 0.4803264 0.947216 0.4580957 0.9494056 0.4703059 0.9594261 0.4681164 0.9371955 0.4143013 0.843872 0.4143013 0.8453262 0.3910323 0.8453262 0.4143013 0.8453262 0.4143013 0.8467807 0.3910323 0.8467807 0.4143013 0.8467807 0.4143013 0.8482348 0.3910323 0.8482348 0.4143013 0.8482348 0.4143013 0.8496892 0.3910323 0.8496892 0.4143013 0.8496892 0.4143013 0.8511435 0.3910323 0.8511435 0.4143013 0.8511435 0.4143013 0.8525979 0.3910323 0.8525979 0.4143013 0.8525979 0.4143013 0.8540522 0.3910323 0.8540522 0.4143013 0.8540522 0.4143013 0.8555065 0.3910323 0.8555065 0.4143013 0.8555065 0.4143013 0.8569609 0.3910323 0.8569609 0.4143013 0.8569609 0.4143013 0.8584151 0.3910323 0.8584151 0.4143013 0.8584151 0.4143013 0.8598694 0.3910323 0.8598694 0.4143013 0.8598694 0.4143013 0.8613237 0.3910323 0.8613237 0.4143013 0.8613237 0.4143013 0.8627781 0.3910323 0.8627781 0.4143013 0.8627781 0.4143013 0.8642324 0.3910323 0.8642324 0.4143013 0.8642324 0.4143013 0.8656867 0.3910323 0.8656867 0.4143013 0.8656867 0.4143013 0.8671411 0.3910323 0.8671411 0.4143013 0.8671411 0.4143013 0.8685953 0.3910323 0.8685953 0.4143013 0.8685953 0.4143013 0.8700496 0.3910323 0.8700496 0.4143013 0.8700496 0.4143013 0.8715039 0.3910323 0.8715039 0.4143013 0.8715039 0.4143013 0.8729583 0.3910323 0.8729583 0.4143013 0.8729583 0.4143013 0.8744126 0.3910323 0.8744126 0.4143013 0.8744126 0.4143013 0.8758669 0.3910323 0.8758669 0.4143013 0.8758669 0.4143013 0.8773211 0.3910323 0.8773211 0.4143013 0.8773211 0.4143013 0.8787754 0.3910323 0.8787754 0.4143013 0.8787754 0.4143013 0.8802298 0.3910323 0.8802298 0.4143013 0.8802298 0.4143013 0.8816841 0.3910323 0.8816841 0.4143013 0.8816841 0.4143013 0.8831384 0.3910323 0.8831384 0.4143013 0.8831384 0.4143013 0.8845928 0.3910323 0.8845928 0.4143013 0.8845928 0.4143013 0.8860471 0.3910323 0.8860471 0.4143013 0.8860471 0.4143013 0.8875013 0.3910323 0.8875013 0.4128358 0.9515531 0.411998 0.953576 0.4107815 0.9553965 0.4107815 0.9553965 0.4092333 0.9569447 0.4074128 0.9581612 0.4074128 0.9581612 0.40539 0.958999 0.3989055 0.958999 0.40539 0.958999 0.4032424 0.9594261 0.3989055 0.958999 0.4032424 0.9594261 0.4010529 0.9594261 0.3989055 0.958999 0.3989055 0.958999 0.3968827 0.9581611 0.3950622 0.9569447 0.3950622 0.9569447 0.3935138 0.9553965 0.3922974 0.953576 0.3922974 0.953576 0.3914595 0.9515531 0.3910323 0.9494056 0.3910323 0.9494056 0.3910323 0.9472162 0.3922974 0.953576 0.3910323 0.9472162 0.3914595 0.9450687 0.3922974 0.953576 0.3914595 0.9450687 0.3922974 0.9430459 0.3935138 0.9412252 0.3935138 0.9412252 0.3950622 0.9396771 0.3968827 0.9384607 0.3968827 0.9384607 0.3989055 0.9376227 0.40539 0.9376227 0.3989055 0.9376227 0.4010529 0.9371955 0.40539 0.9376227 0.4010529 0.9371955 0.4032424 0.9371955 0.40539 0.9376227 0.40539 0.9376227 0.4074128 0.9384607 0.4092333 0.9396771 0.4092333 0.9396771 0.4107815 0.9412252 0.411998 0.9430459 0.411998 0.9430459 0.4128358 0.9450687 0.413263 0.9472162 0.413263 0.9472162 0.413263 0.9494056 0.411998 0.9430459 0.413263 0.9494056 0.4128358 0.9515531 0.411998 0.9430459 0.4128358 0.9515531 0.4107815 0.9553965 0.3989055 0.958999 0.4107815 0.9553965 0.4074128 0.9581612 0.3989055 0.958999 0.3989055 0.958999 0.3950622 0.9569447 0.3914595 0.9450687 0.3950622 0.9569447 0.3922974 0.953576 0.3914595 0.9450687 0.3914595 0.9450687 0.3935138 0.9412252 0.40539 0.9376227 0.3935138 0.9412252 0.3968827 0.9384607 0.40539 0.9376227 0.40539 0.9376227 0.4092333 0.9396771 0.4128358 0.9515531 0.4092333 0.9396771 0.411998 0.9430459 0.4128358 0.9515531 0.4128358 0.9515531 0.3989055 0.958999 0.3914595 0.9450687 0.4143013 0.8875013 0.4143013 0.8889556 0.3910323 0.8889556 0.4143013 0.8889556 0.4143013 0.89041 0.3910323 0.89041 0.3442469 0.97176 0.3446739 0.9739076 0.3482764 0.9792992 0.3446739 0.9739076 0.3455118 0.9759305 0.3482764 0.9792992 0.3455118 0.9759305 0.3467283 0.977751 0.3482764 0.9792992 0.3482764 0.9792992 0.350097 0.9805155 0.3521199 0.9813535 0.3521199 0.9813535 0.3542674 0.9817806 0.3564569 0.9817806 0.3564569 0.9817806 0.3586043 0.9813535 0.363996 0.977751 0.3586043 0.9813535 0.3606272 0.9805155 0.363996 0.977751 0.3606272 0.9805155 0.3624477 0.9792992 0.363996 0.977751 0.363996 0.977751 0.3652124 0.9759305 0.3660504 0.9739076 0.3660504 0.9739076 0.3664774 0.97176 0.3664774 0.9695706 0.3664774 0.9695706 0.3660504 0.9674231 0.3624477 0.9620316 0.3660504 0.9674231 0.3652124 0.9654002 0.3624477 0.9620316 0.3652124 0.9654002 0.363996 0.9635797 0.3624477 0.9620316 0.3624477 0.9620316 0.3606272 0.9608151 0.3586043 0.9599772 0.3586043 0.9599772 0.3564569 0.9595499 0.3542674 0.9595499 0.3542674 0.9595499 0.3521199 0.9599772 0.3467283 0.9635797 0.3521199 0.9599772 0.350097 0.9608151 0.3467283 0.9635797 0.350097 0.9608151 0.3482764 0.9620316 0.3467283 0.9635797 0.3467283 0.9635797 0.3455118 0.9654002 0.3446739 0.9674231 0.3446739 0.9674231 0.3442469 0.9695706 0.3442469 0.97176 0.3482764 0.9792992 0.3521199 0.9813535 0.3442469 0.97176 0.3521199 0.9813535 0.3564569 0.9817806 0.3442469 0.97176 0.363996 0.977751 0.3660504 0.9739076 0.3564569 0.9817806 0.3660504 0.9739076 0.3664774 0.9695706 0.3564569 0.9817806 0.3624477 0.9620316 0.3586043 0.9599772 0.3664774 0.9695706 0.3586043 0.9599772 0.3542674 0.9595499 0.3664774 0.9695706 0.3467283 0.9635797 0.3446739 0.9674231 0.3542674 0.9595499 0.3446739 0.9674231 0.3442469 0.97176 0.3542674 0.9595499 0.3442469 0.97176 0.3564569 0.9817806 0.3664774 0.9695706 0.3675158 0.8905338 0.3675158 0.8919881 0.3442469 0.8919881 0.3675158 0.8919881 0.3675158 0.8934424 0.3442469 0.8934424 0.3675158 0.8934424 0.3675158 0.8948968 0.3442469 0.8948968 0.3675158 0.8948968 0.3675158 0.8963511 0.3442469 0.8963511 0.3675158 0.8963511 0.3675158 0.8978053 0.3442469 0.8978053 0.3675158 0.8978053 0.3675158 0.8992596 0.3442469 0.8992596 0.3675158 0.8992596 0.3675158 0.9007139 0.3442469 0.9007139 0.3675158 0.9007139 0.3675158 0.9021683 0.3442469 0.9021683 0.3675158 0.9021683 0.3675158 0.9036226 0.3442469 0.9036226 0.3675158 0.9036226 0.3675158 0.9050769 0.3442469 0.9050769 0.3675158 0.9050769 0.3675158 0.9065311 0.3442469 0.9065311 0.3675158 0.9065311 0.3675158 0.9079855 0.3442469 0.9079855 0.3675158 0.9079855 0.3675158 0.9094398 0.3442469 0.9094398 0.3675158 0.9094398 0.3675158 0.9108941 0.3442469 0.9108941 0.3675158 0.9108941 0.3675158 0.9123485 0.3442469 0.9123485 0.3675158 0.9123485 0.3675158 0.9138028 0.3442469 0.9138028 0.3675158 0.9138028 0.3675158 0.9152571 0.3442469 0.9152571 0.3675158 0.9152571 0.3675158 0.9167113 0.3442469 0.9167113 0.3675158 0.9167113 0.3675158 0.9181656 0.3442469 0.9181656 0.3675158 0.9181656 0.3675158 0.91962 0.3442469 0.91962 0.3675158 0.91962 0.3675158 0.9210743 0.3442469 0.9210743 0.3675158 0.9210743 0.3675158 0.9225286 0.3442469 0.9225286 0.3675158 0.9225286 0.3675158 0.923983 0.3442469 0.923983 0.3675158 0.923983 0.3675158 0.9254373 0.3442469 0.9254373 0.3675158 0.9254373 0.3675158 0.9268915 0.3442469 0.9268915 0.3675158 0.9268915 0.3675158 0.928346 0.3442469 0.928346 0.3675158 0.928346 0.3675158 0.9298002 0.3442469 0.9298002 0.3675158 0.9298002 0.3675158 0.9312545 0.3442469 0.9312545 0.3675158 0.9312545 0.3675158 0.9327088 0.3442469 0.9327088 0.3675158 0.9327088 0.3675158 0.9341632 0.3442469 0.9341632 0.4351904 0.9515531 0.4343524 0.953576 0.433136 0.9553965 0.433136 0.9553965 0.4315878 0.9569447 0.4351904 0.9515531 0.4315878 0.9569447 0.4297673 0.9581612 0.4351904 0.9515531 0.4297673 0.9581612 0.4277444 0.958999 0.4212599 0.958999 0.4277444 0.958999 0.425597 0.9594261 0.4212599 0.958999 0.425597 0.9594261 0.4234074 0.9594261 0.4212599 0.958999 0.4212599 0.958999 0.419237 0.9581612 0.4146519 0.953576 0.419237 0.9581612 0.4174165 0.9569447 0.4146519 0.953576 0.4174165 0.9569447 0.4158683 0.9553965 0.4146519 0.953576 0.4146519 0.953576 0.4138139 0.9515531 0.4138139 0.9450687 0.4138139 0.9515531 0.4133868 0.9494056 0.4138139 0.9450687 0.4133868 0.9494056 0.4133868 0.9472162 0.4138139 0.9450687 0.4138139 0.9450687 0.4146519 0.9430459 0.4158683 0.9412252 0.4158683 0.9412252 0.4174165 0.9396771 0.419237 0.9384607 0.419237 0.9384607 0.4212599 0.9376227 0.4234074 0.9371955 0.4234074 0.9371955 0.425597 0.9371955 0.419237 0.9384607 0.425597 0.9371955 0.4277444 0.9376227 0.419237 0.9384607 0.4277444 0.9376227 0.4297673 0.9384607 0.4315878 0.9396771 0.4315878 0.9396771 0.433136 0.9412252 0.4277444 0.9376227 0.433136 0.9412252 0.4343524 0.9430459 0.4277444 0.9376227 0.4343524 0.9430459 0.4351904 0.9450687 0.4351904 0.9515531 0.4351904 0.9450687 0.4356175 0.9472162 0.4351904 0.9515531 0.4356175 0.9472162 0.4356175 0.9494056 0.4351904 0.9515531 0.4138139 0.9450687 0.4158683 0.9412252 0.4277444 0.9376227 0.4158683 0.9412252 0.419237 0.9384607 0.4277444 0.9376227 0.4351904 0.9515531 0.4297673 0.9581612 0.4212599 0.958999 0.4212599 0.958999 0.4146519 0.953576 0.4138139 0.9450687 0.4277444 0.9376227 0.4343524 0.9430459 0.4351904 0.9515531 0.4351904 0.9515531 0.4212599 0.958999 0.4277444 0.9376227 0.3675158 0.9341632 0.3675158 0.9356175 0.3442469 0.9356175 0.3675158 0.9356175 0.3675158 0.9370717 0.3442469 0.9370717 0.3666012 0.97176 0.3670285 0.9739076 0.3678663 0.9759305 0.3678663 0.9759305 0.3690828 0.977751 0.3666012 0.97176 0.3690828 0.977751 0.370631 0.9792992 0.3666012 0.97176 0.370631 0.9792992 0.3724515 0.9805157 0.3744744 0.9813535 0.3744744 0.9813535 0.3766219 0.9817806 0.370631 0.9792992 0.3766219 0.9817806 0.3788114 0.9817806 0.370631 0.9792992 0.3788114 0.9817806 0.3809587 0.9813535 0.3829817 0.9805155 0.3829817 0.9805155 0.3848022 0.9792992 0.3788114 0.9817806 0.3848022 0.9792992 0.3863505 0.977751 0.3788114 0.9817806 0.3863505 0.977751 0.3875669 0.9759305 0.3884047 0.9739076 0.3884047 0.9739076 0.3888319 0.97176 0.3863505 0.977751 0.3888319 0.97176 0.3888319 0.9695706 0.3863505 0.977751 0.3888319 0.9695706 0.3884047 0.9674231 0.3848022 0.9620316 0.3884047 0.9674231 0.3875669 0.9654002 0.3848022 0.9620316 0.3875669 0.9654002 0.3863505 0.9635797 0.3848022 0.9620316 0.3848022 0.9620316 0.3829817 0.9608151 0.3809587 0.9599772 0.3809587 0.9599772 0.3788114 0.9595499 0.3766219 0.9595499 0.3766219 0.9595499 0.3744744 0.9599772 0.3724515 0.9608151 0.3724515 0.9608151 0.3706309 0.9620316 0.3690828 0.9635797 0.3690828 0.9635797 0.3678663 0.9654002 0.3670285 0.9674231 0.3670285 0.9674231 0.3666012 0.9695706 0.3690828 0.9635797 0.3666012 0.9695706 0.3666012 0.97176 0.3690828 0.9635797 0.3848022 0.9620316 0.3809587 0.9599772 0.3888319 0.9695706 0.3809587 0.9599772 0.3766219 0.9595499 0.3888319 0.9695706 0.3766219 0.9595499 0.3724515 0.9608151 0.3666012 0.97176 0.3724515 0.9608151 0.3690828 0.9635797 0.3666012 0.97176 0.3666012 0.97176 0.370631 0.9792992 0.3788114 0.9817806 0.3788114 0.9817806 0.3863505 0.977751 0.3888319 0.9695706 0.3666012 0.97176 0.3788114 0.9817806 0.3766219 0.9595499 0.3909085 0.8905338 0.3909085 0.8919881 0.3676396 0.8919881 0.3909085 0.8919881 0.3909085 0.8934424 0.3676396 0.8934424 0.3909085 0.8934424 0.3909085 0.8948968 0.3676396 0.8948968 0.3909085 0.8948968 0.3909085 0.8963511 0.3676396 0.8963511 0.3909085 0.8963511 0.3909085 0.8978053 0.3676396 0.8978053 0.3909085 0.8978053 0.3909085 0.8992596 0.3676396 0.8992596 0.3909085 0.8992596 0.3909085 0.9007139 0.3676396 0.9007139 0.3909085 0.9007139 0.3909085 0.9021683 0.3676396 0.9021683 0.3909085 0.9021683 0.3909085 0.9036226 0.3676396 0.9036226 0.3909085 0.9036226 0.3909085 0.9050769 0.3676396 0.9050769 0.3909085 0.9050769 0.3909085 0.9065311 0.3676396 0.9065311 0.3909085 0.9065311 0.3909085 0.9079855 0.3676396 0.9079855 0.3909085 0.9079855 0.3909085 0.9094398 0.3676396 0.9094398 0.3909085 0.9094398 0.3909085 0.9108941 0.3676396 0.9108941 0.3909085 0.9108941 0.3909085 0.9123485 0.3676396 0.9123485 0.3909085 0.9123485 0.3909085 0.9138028 0.3676396 0.9138028 0.3909085 0.9138028 0.3909085 0.9152571 0.3676396 0.9152571 0.3909085 0.9152571 0.3909085 0.9167113 0.3676396 0.9167113 0.3909085 0.9167113 0.3909085 0.9181656 0.3676396 0.9181656 0.3909085 0.9181656 0.3909085 0.91962 0.3676396 0.91962 0.3909085 0.91962 0.3909085 0.9210743 0.3676396 0.9210743 0.3909085 0.9210743 0.3909085 0.9225286 0.3676396 0.9225286 0.3909085 0.9225286 0.3909085 0.923983 0.3676396 0.923983 0.3909085 0.923983 0.3909085 0.9254373 0.3676396 0.9254373 0.3909085 0.9254373 0.3909085 0.9268915 0.3676396 0.9268915 0.3909085 0.9268915 0.3909085 0.928346 0.3676396 0.928346 0.3909085 0.928346 0.3909085 0.9298002 0.3676396 0.9298002 0.3909085 0.9298002 0.3909085 0.9312545 0.3676396 0.9312545 0.3909085 0.9312545 0.3909085 0.9327088 0.3676396 0.9327088 0.3909085 0.9327088 0.3909085 0.9341632 0.3676396 0.9341632 0.4575448 0.9515531 0.456707 0.953576 0.4554905 0.9553965 0.4554905 0.9553965 0.4539422 0.9569447 0.4575448 0.9515531 0.4539422 0.9569447 0.4521217 0.9581612 0.4575448 0.9515531 0.4521217 0.9581612 0.4500988 0.958999 0.4479514 0.9594261 0.4479514 0.9594261 0.4457618 0.9594261 0.4436144 0.958999 0.4436144 0.958999 0.4415916 0.9581611 0.439771 0.9569447 0.439771 0.9569447 0.4382228 0.9553965 0.4370063 0.953576 0.4370063 0.953576 0.4361684 0.9515531 0.4357413 0.9494056 0.4357413 0.9494056 0.4357413 0.9472162 0.4361684 0.9450687 0.4361684 0.9450687 0.4370063 0.9430459 0.4382228 0.9412252 0.4382228 0.9412252 0.439771 0.9396771 0.4415916 0.9384607 0.4415916 0.9384607 0.4436144 0.9376227 0.4500988 0.9376227 0.4436144 0.9376227 0.4457618 0.9371955 0.4500988 0.9376227 0.4457618 0.9371955 0.4479514 0.9371955 0.4500988 0.9376227 0.4500988 0.9376227 0.4521217 0.9384607 0.4539422 0.9396771 0.4539422 0.9396771 0.4554905 0.9412252 0.456707 0.9430459 0.456707 0.9430459 0.4575448 0.9450687 0.4579721 0.9472162 0.4579721 0.9472162 0.4579719 0.9494056 0.4575448 0.9515531 0.4521217 0.9581612 0.4479514 0.9594261 0.4575448 0.9515531 0.4479514 0.9594261 0.4436144 0.958999 0.4575448 0.9515531 0.4436144 0.958999 0.439771 0.9569447 0.4370063 0.953576 0.4370063 0.953576 0.4357413 0.9494056 0.4436144 0.958999 0.4357413 0.9494056 0.4361684 0.9450687 0.4436144 0.958999 0.4361684 0.9450687 0.4382228 0.9412252 0.4500988 0.9376227 0.4382228 0.9412252 0.4415916 0.9384607 0.4500988 0.9376227 0.4500988 0.9376227 0.4539422 0.9396771 0.456707 0.9430459 0.456707 0.9430459 0.4579721 0.9472162 0.4500988 0.9376227 0.4579721 0.9472162 0.4575448 0.9515531 0.4500988 0.9376227 0.4575448 0.9515531 0.4436144 0.958999 0.4500988 0.9376227 0.3909085 0.9341632 0.3909085 0.9356175 0.3676396 0.9356175 0.3909085 0.9356175 0.3909085 0.9370717 0.3676396 0.9370717 0.389994 0.97176 0.3904212 0.9739076 0.391259 0.9759305 0.391259 0.9759305 0.3924755 0.977751 0.3940238 0.9792992 0.3940238 0.9792992 0.3958442 0.9805157 0.3978672 0.9813535 0.3978672 0.9813535 0.4000146 0.9817806 0.3940238 0.9792992 0.4000146 0.9817806 0.4022041 0.9817806 0.3940238 0.9792992 0.4022041 0.9817806 0.4043515 0.9813535 0.4097432 0.977751 0.4043515 0.9813535 0.4063744 0.9805157 0.4097432 0.977751 0.4063744 0.9805157 0.408195 0.9792992 0.4097432 0.977751 0.4097432 0.977751 0.4109596 0.9759305 0.4122247 0.9695706 0.4109596 0.9759305 0.4117976 0.9739076 0.4122247 0.9695706 0.4117976 0.9739076 0.4122247 0.97176 0.4122247 0.9695706 0.4122247 0.9695706 0.4117976 0.9674231 0.408195 0.9620316 0.4117976 0.9674231 0.4109596 0.9654002 0.408195 0.9620316 0.4109596 0.9654002 0.4097432 0.9635797 0.408195 0.9620316 0.408195 0.9620316 0.4063744 0.9608151 0.4043515 0.9599772 0.4043515 0.9599772 0.4022041 0.9595499 0.408195 0.9620316 0.4022041 0.9595499 0.4000146 0.9595499 0.408195 0.9620316 0.4000146 0.9595499 0.3978672 0.9599772 0.3924755 0.9635797 0.3978672 0.9599772 0.3958442 0.9608151 0.3924755 0.9635797 0.3958442 0.9608151 0.3940238 0.9620316 0.3924755 0.9635797 0.3924755 0.9635797 0.391259 0.9654002 0.389994 0.97176 0.391259 0.9654002 0.3904212 0.9674231 0.389994 0.97176 0.3904212 0.9674231 0.389994 0.9695706 0.389994 0.97176 0.389994 0.97176 0.391259 0.9759305 0.4022041 0.9817806 0.391259 0.9759305 0.3940238 0.9792992 0.4022041 0.9817806 0.4022041 0.9817806 0.4097432 0.977751 0.389994 0.97176 0.4097432 0.977751 0.4122247 0.9695706 0.389994 0.97176 0.4122247 0.9695706 0.408195 0.9620316 0.389994 0.97176 0.408195 0.9620316 0.4000146 0.9595499 0.389994 0.97176 0.4143013 0.8905338 0.4143013 0.8919881 0.3910323 0.8919881 0.4143013 0.8919881 0.4143013 0.8934424 0.3910323 0.8934424 0.4143013 0.8934424 0.4143013 0.8948968 0.3910323 0.8948968 0.4143013 0.8948968 0.4143013 0.8963511 0.3910323 0.8963511 0.4143013 0.8963511 0.4143013 0.8978053 0.3910323 0.8978053 0.4143013 0.8978053 0.4143013 0.8992596 0.3910323 0.8992596 0.4143013 0.8992596 0.4143013 0.9007139 0.3910323 0.9007139 0.4143013 0.9007139 0.4143013 0.9021683 0.3910323 0.9021683 0.4143013 0.9021683 0.4143013 0.9036226 0.3910323 0.9036226 0.4143013 0.9036226 0.4143013 0.9050769 0.3910323 0.9050769 0.4143013 0.9050769 0.4143013 0.9065311 0.3910323 0.9065311 0.4143013 0.9065311 0.4143013 0.9079855 0.3910323 0.9079855 0.4143013 0.9079855 0.4143013 0.9094398 0.3910323 0.9094398 0.4143013 0.9094398 0.4143013 0.9108941 0.3910323 0.9108941 0.4143013 0.9108941 0.4143013 0.9123485 0.3910323 0.9123485 0.4143013 0.9123485 0.4143013 0.9138028 0.3910323 0.9138028 0.4143013 0.9138028 0.4143013 0.9152571 0.3910323 0.9152571 0.4143013 0.9152571 0.4143013 0.9167113 0.3910323 0.9167113 0.4143013 0.9167113 0.4143013 0.9181656 0.3910323 0.9181656 0.4143013 0.9181656 0.4143013 0.91962 0.3910323 0.91962 0.4143013 0.91962 0.4143013 0.9210743 0.3910323 0.9210743 0.4143013 0.9210743 0.4143013 0.9225286 0.3910323 0.9225286 0.4143013 0.9225286 0.4143013 0.923983 0.3910323 0.923983 0.4143013 0.923983 0.4143013 0.9254373 0.3910323 0.9254373 0.4143013 0.9254373 0.4143013 0.9268915 0.3910323 0.9268915 0.4143013 0.9268915 0.4143013 0.928346 0.3910323 0.928346 0.4143013 0.928346 0.4143013 0.9298002 0.3910323 0.9298002 0.4143013 0.9298002 0.4143013 0.9312545 0.3910323 0.9312545 0.4143013 0.9312545 0.4143013 0.9327088 0.3910323 0.9327088 0.4143013 0.9327088 0.4143013 0.9341632 0.3910323 0.9341632 0.4596215 0.8582295 0.4587835 0.8602524 0.457567 0.8620729 0.457567 0.8620729 0.4560189 0.8636212 0.4541983 0.8648377 0.4541983 0.8648377 0.4521755 0.8656756 0.4500281 0.8661027 0.4500281 0.8661027 0.4478385 0.8661027 0.4541983 0.8648377 0.4478385 0.8661027 0.445691 0.8656755 0.4541983 0.8648377 0.445691 0.8656755 0.4436681 0.8648377 0.4390829 0.8602524 0.4436681 0.8648377 0.4418476 0.8636212 0.4390829 0.8602524 0.4418476 0.8636212 0.4402994 0.8620729 0.4390829 0.8602524 0.4390829 0.8602524 0.4382451 0.8582295 0.4382451 0.851745 0.4382451 0.8582295 0.437818 0.8560822 0.4382451 0.851745 0.437818 0.8560822 0.437818 0.8538926 0.4382451 0.851745 0.4382451 0.851745 0.4390829 0.8497223 0.4402994 0.8479018 0.4402994 0.8479018 0.4418476 0.8463534 0.4436681 0.8451371 0.4436681 0.8451371 0.445691 0.8442991 0.4478385 0.843872 0.4478385 0.843872 0.4500281 0.843872 0.4436681 0.8451371 0.4500281 0.843872 0.4521755 0.8442991 0.4436681 0.8451371 0.4521755 0.8442991 0.4541983 0.8451371 0.4560189 0.8463534 0.4560189 0.8463534 0.457567 0.8479018 0.4521755 0.8442991 0.457567 0.8479018 0.4587835 0.8497223 0.4521755 0.8442991 0.4587835 0.8497223 0.4596215 0.851745 0.4596215 0.8582295 0.4596215 0.851745 0.4600486 0.8538926 0.4596215 0.8582295 0.4600486 0.8538926 0.4600486 0.8560822 0.4596215 0.8582295 0.4596215 0.8582295 0.457567 0.8620729 0.4541983 0.8648377 0.4382451 0.851745 0.4402994 0.8479018 0.4521755 0.8442991 0.4402994 0.8479018 0.4436681 0.8451371 0.4521755 0.8442991 0.4596215 0.8582295 0.4541983 0.8648377 0.445691 0.8656755 0.445691 0.8656755 0.4390829 0.8602524 0.4596215 0.8582295 0.4390829 0.8602524 0.4382451 0.851745 0.4596215 0.8582295 0.4521755 0.8442991 0.4587835 0.8497223 0.4596215 0.8582295 0.4143013 0.9341632 0.4143013 0.9356175 0.3910323 0.9356175 0.4143013 0.9356175 0.4143013 0.9370717 0.3910323 0.9370717 0.4133868 0.97176 0.4138139 0.9739076 0.4146519 0.9759305 0.4146519 0.9759305 0.4158683 0.977751 0.4133868 0.97176 0.4158683 0.977751 0.4174165 0.9792992 0.4133868 0.97176 0.4174165 0.9792992 0.419237 0.9805157 0.4212599 0.9813535 0.4212599 0.9813535 0.4234074 0.9817806 0.425597 0.9817806 0.425597 0.9817806 0.4277444 0.9813535 0.4297673 0.9805157 0.4297673 0.9805157 0.4315878 0.9792992 0.425597 0.9817806 0.4315878 0.9792992 0.4331359 0.977751 0.425597 0.9817806 0.4331359 0.977751 0.4343524 0.9759305 0.4351903 0.9739076 0.4351903 0.9739076 0.4356175 0.97176 0.4331359 0.977751 0.4356175 0.97176 0.4356175 0.9695706 0.4331359 0.977751 0.4356175 0.9695706 0.4351903 0.9674231 0.4315878 0.9620316 0.4351903 0.9674231 0.4343524 0.9654002 0.4315878 0.9620316 0.4343524 0.9654002 0.4331359 0.9635797 0.4315878 0.9620316 0.4315878 0.9620316 0.4297671 0.9608151 0.4277444 0.9599772 0.4277444 0.9599772 0.425597 0.9595499 0.4234074 0.9595499 0.4234074 0.9595499 0.4212599 0.9599772 0.419237 0.9608151 0.419237 0.9608151 0.4174165 0.9620316 0.4158683 0.9635797 0.4158683 0.9635797 0.4146519 0.9654002 0.4138139 0.9674231 0.4138139 0.9674231 0.4133868 0.9695706 0.4158683 0.9635797 0.4133868 0.9695706 0.4133868 0.97176 0.4158683 0.9635797 0.4174165 0.9792992 0.4212599 0.9813535 0.4133868 0.97176 0.4212599 0.9813535 0.425597 0.9817806 0.4133868 0.97176 0.4315878 0.9620316 0.4277444 0.9599772 0.4356175 0.9695706 0.4277444 0.9599772 0.4234074 0.9595499 0.4356175 0.9695706 0.4234074 0.9595499 0.419237 0.9608151 0.4158683 0.9635797 0.425597 0.9817806 0.4331359 0.977751 0.4356175 0.9695706 0.4234074 0.9595499 0.4158683 0.9635797 0.4133868 0.97176 0.4133868 0.97176 0.425597 0.9817806 0.4234074 0.9595499 0.4376942 0.843872 0.4376942 0.8453262 0.4144251 0.8453262 0.4376942 0.8453262 0.4376942 0.8467807 0.4144251 0.8467807 0.4376942 0.8467807 0.4376942 0.8482348 0.4144251 0.8482348 0.4376942 0.8482348 0.4376942 0.8496892 0.4144251 0.8496892 0.4376942 0.8496892 0.4376942 0.8511435 0.4144251 0.8511435 0.4376942 0.8511435 0.4376942 0.8525979 0.4144251 0.8525979 0.4376942 0.8525979 0.4376942 0.8540522 0.4144251 0.8540522 0.4376942 0.8540522 0.4376942 0.8555065 0.4144251 0.8555065 0.4376942 0.8555065 0.4376942 0.8569609 0.4144251 0.8569609 0.4376942 0.8569609 0.4376942 0.8584151 0.4144251 0.8584151 0.4376942 0.8584151 0.4376942 0.8598694 0.4144251 0.8598694 0.4376942 0.8598694 0.4376942 0.8613237 0.4144251 0.8613237 0.4376942 0.8613237 0.4376942 0.8627781 0.4144251 0.8627781 0.4376942 0.8627781 0.4376942 0.8642324 0.4144251 0.8642324 0.4376942 0.8642324 0.4376942 0.8656867 0.4144251 0.8656867 0.4376942 0.8656867 0.4376942 0.8671411 0.4144251 0.8671411 0.4376942 0.8671411 0.4376942 0.8685953 0.4144251 0.8685953 0.4376942 0.8685953 0.4376942 0.8700496 0.4144251 0.8700496 0.4376942 0.8700496 0.4376942 0.8715039 0.4144251 0.8715039 0.4376942 0.8715039 0.4376942 0.8729583 0.4144251 0.8729583 0.4376942 0.8729583 0.4376942 0.8744126 0.4144251 0.8744126 0.4376942 0.8744126 0.4376942 0.8758669 0.4144251 0.8758669 0.4376942 0.8758669 0.4376942 0.8773211 0.4144251 0.8773211 0.4376942 0.8773211 0.4376942 0.8787754 0.4144251 0.8787754 0.4376942 0.8787754 0.4376942 0.8802298 0.4144251 0.8802298 0.4376942 0.8802298 0.4376942 0.8816841 0.4144251 0.8816841 0.4376942 0.8816841 0.4376942 0.8831384 0.4144251 0.8831384 0.4376942 0.8831384 0.4376942 0.8845928 0.4144251 0.8845928 0.4376942 0.8845928 0.4376942 0.8860471 0.4144251 0.8860471 0.4376942 0.8860471 0.4376942 0.8875013 0.4144251 0.8875013 0.4596215 0.880584 0.4587835 0.8826069 0.457567 0.8844274 0.457567 0.8844274 0.4560188 0.8859757 0.4596215 0.880584 0.4560188 0.8859757 0.4541983 0.8871921 0.4596215 0.880584 0.4541983 0.8871921 0.4521755 0.8880299 0.4500281 0.8884571 0.4500281 0.8884571 0.4478385 0.8884571 0.445691 0.8880299 0.445691 0.8880299 0.4436681 0.8871921 0.4418476 0.8859757 0.4418476 0.8859757 0.4402994 0.8844274 0.4390829 0.8826069 0.4390829 0.8826069 0.4382451 0.880584 0.437818 0.8784366 0.437818 0.8784366 0.437818 0.876247 0.4382451 0.8740995 0.4382451 0.8740995 0.4390829 0.8720768 0.4402994 0.8702561 0.4402994 0.8702561 0.4418476 0.8687079 0.4436681 0.8674915 0.4436681 0.8674915 0.445691 0.8666536 0.4521755 0.8666536 0.445691 0.8666536 0.4478385 0.8662265 0.4521755 0.8666536 0.4478385 0.8662265 0.4500281 0.8662265 0.4521755 0.8666536 0.4521755 0.8666536 0.4541983 0.8674915 0.4560189 0.8687079 0.4560189 0.8687079 0.457567 0.8702561 0.4587835 0.8720768 0.4587835 0.8720768 0.4596215 0.8740995 0.4600486 0.876247 0.4600486 0.876247 0.4600486 0.8784366 0.4596215 0.880584 0.4541983 0.8871921 0.4500281 0.8884571 0.4596215 0.880584 0.4500281 0.8884571 0.445691 0.8880299 0.4596215 0.880584 0.445691 0.8880299 0.4418476 0.8859757 0.4390829 0.8826069 0.4390829 0.8826069 0.437818 0.8784366 0.445691 0.8880299 0.437818 0.8784366 0.4382451 0.8740995 0.445691 0.8880299 0.4382451 0.8740995 0.4402994 0.8702561 0.4521755 0.8666536 0.4402994 0.8702561 0.4436681 0.8674915 0.4521755 0.8666536 0.4521755 0.8666536 0.4560189 0.8687079 0.4587835 0.8720768 0.4587835 0.8720768 0.4600486 0.876247 0.4521755 0.8666536 0.4600486 0.876247 0.4596215 0.880584 0.4521755 0.8666536 0.4596215 0.880584 0.445691 0.8880299 0.4521755 0.8666536 0.4376942 0.8875013 0.4376942 0.8889556 0.4144251 0.8889556 0.4376942 0.8889556 0.4376942 0.89041 0.4144251 0.89041 0.4357413 0.97176 0.4361684 0.9739076 0.4370063 0.9759305 0.4370063 0.9759305 0.4382228 0.977751 0.439771 0.9792992 0.439771 0.9792992 0.4415916 0.9805157 0.4436144 0.9813535 0.4436144 0.9813535 0.4457618 0.9817806 0.439771 0.9792992 0.4457618 0.9817806 0.4479514 0.9817806 0.439771 0.9792992 0.4479514 0.9817806 0.4500988 0.9813535 0.4554905 0.977751 0.4500988 0.9813535 0.4521217 0.9805155 0.4554905 0.977751 0.4521217 0.9805155 0.4539422 0.9792992 0.4554905 0.977751 0.4554905 0.977751 0.456707 0.9759305 0.4579721 0.9695706 0.456707 0.9759305 0.4575448 0.9739076 0.4579721 0.9695706 0.4575448 0.9739076 0.4579721 0.97176 0.4579721 0.9695706 0.4579721 0.9695706 0.4575448 0.9674231 0.4539422 0.9620316 0.4575448 0.9674231 0.456707 0.9654002 0.4539422 0.9620316 0.456707 0.9654002 0.4554905 0.9635797 0.4539422 0.9620316 0.4539422 0.9620316 0.4521217 0.9608151 0.4500988 0.9599772 0.4500988 0.9599772 0.4479514 0.9595499 0.4539422 0.9620316 0.4479514 0.9595499 0.4457618 0.9595499 0.4539422 0.9620316 0.4457618 0.9595499 0.4436144 0.9599772 0.4382228 0.9635797 0.4436144 0.9599772 0.4415916 0.9608151 0.4382228 0.9635797 0.4415916 0.9608151 0.439771 0.9620316 0.4382228 0.9635797 0.4382228 0.9635797 0.4370063 0.9654002 0.4357413 0.97176 0.4370063 0.9654002 0.4361684 0.9674231 0.4357413 0.97176 0.4361684 0.9674231 0.4357413 0.9695706 0.4357413 0.97176 0.4357413 0.97176 0.4370063 0.9759305 0.4479514 0.9817806 0.4370063 0.9759305 0.439771 0.9792992 0.4479514 0.9817806 0.4479514 0.9817806 0.4554905 0.977751 0.4357413 0.97176 0.4554905 0.977751 0.4579721 0.9695706 0.4357413 0.97176 0.4579721 0.9695706 0.4539422 0.9620316 0.4357413 0.97176 0.4539422 0.9620316 0.4457618 0.9595499 0.4357413 0.97176 0.4376942 0.8905338 0.4376942 0.8919881 0.4144251 0.8919881 0.4376942 0.8919881 0.4376942 0.8934424 0.4144251 0.8934424 0.4376942 0.8905338 0.4376942 0.8905338 0.4376942 0.8919881 0.4376942 0.9225286 0.4376942 0.9225286 0.4376942 0.923983 0.4798992 0.9739076 0.4798992 0.9739076 0.4803264 0.97176 0.4639459 0.9805157 0.4639459 0.9805157 0.4659689 0.9813535 0.4376942 0.928346 0.4376942 0.928346 0.4376942 0.9298002 0.4376942 0.9152571 0.4376942 0.9152571 0.4376942 0.9167113 0.4724533 0.9813535 0.4724533 0.9813535 0.474476 0.9805157 0.4376942 0.9341632 0.4376942 0.9341632 0.4376942 0.9356175 0.4376942 0.9210743 0.4376942 0.9210743 0.4376942 0.9225286 0.3532367 0.6220626 0.3532367 0.6220626 0.3532367 0.5648227 0.4790613 0.9759305 0.4790613 0.9759305 0.4798992 0.9739076 0.4621254 0.9792992 0.4621254 0.9792992 0.4639459 0.9805157 0.4376942 0.9268915 0.4376942 0.9268915 0.4376942 0.928346 0.4376942 0.9138028 0.4376942 0.9138028 0.4376942 0.9152571 0.4376942 0.9138028 0.4376942 0.9152571 0.4144251 0.9152571 0.4376942 0.9152571 0.4376942 0.9167113 0.4144251 0.9167113 0.4376942 0.9167113 0.4376942 0.9181656 0.4144251 0.9181656 0.4376942 0.9181656 0.4376942 0.91962 0.4144251 0.91962 0.4376942 0.91962 0.4376942 0.9210743 0.4144251 0.9210743 0.4376942 0.9210743 0.4376942 0.9225286 0.4144251 0.9225286 0.4376942 0.9225286 0.4376942 0.923983 0.4144251 0.923983 0.4376942 0.923983 0.4376942 0.9254373 0.4144251 0.9254373 0.4376942 0.9254373 0.4376942 0.9268915 0.4144251 0.9268915 0.4376942 0.9268915 0.4376942 0.928346 0.4144251 0.928346 0.4376942 0.928346 0.4376942 0.9298002 0.4144251 0.9298002 0.4376942 0.9298002 0.4376942 0.9312545 0.4144251 0.9312545 0.4376942 0.9312545 0.4376942 0.9327088 0.4144251 0.9327088 0.4376942 0.9327088 0.4376942 0.9341632 0.4144251 0.9341632 0.3532367 0.7187388 0.3532367 0.7187388 0.3532367 0.6220626 0.4376942 0.9341632 0.4376942 0.9356175 0.4144251 0.9356175 0.4376942 0.9356175 0.4376942 0.9370717 0.4144251 0.9370717 0.4580957 0.97176 0.4585229 0.9739076 0.4593607 0.9759305 0.4593607 0.9759305 0.4605772 0.977751 0.4580957 0.97176 0.4605772 0.977751 0.4621254 0.9792992 0.4580957 0.97176 0.4621254 0.9792992 0.4639459 0.9805157 0.4659689 0.9813535 0.4659689 0.9813535 0.4681164 0.9817806 0.4703059 0.9817806 0.4703059 0.9817806 0.4724533 0.9813535 0.474476 0.9805157 0.474476 0.9805157 0.4762967 0.9792992 0.4703059 0.9817806 0.4762967 0.9792992 0.4778449 0.977751 0.4703059 0.9817806 0.4778449 0.977751 0.4790613 0.9759305 0.4798992 0.9739076 0.4798992 0.9739076 0.4803264 0.97176 0.4778449 0.977751 0.4803264 0.97176 0.4803264 0.9695706 0.4778449 0.977751 0.4803264 0.9695706 0.4798992 0.9674231 0.4762967 0.9620316 0.4798992 0.9674231 0.4790613 0.9654002 0.4762967 0.9620316 0.4790613 0.9654002 0.4778449 0.9635797 0.4762967 0.9620316 0.4762967 0.9620316 0.474476 0.9608151 0.4724532 0.9599772 0.4724532 0.9599772 0.4703059 0.9595499 0.4681164 0.9595499 0.4681164 0.9595499 0.4659689 0.9599772 0.4639459 0.9608151 0.4639459 0.9608151 0.4621254 0.9620316 0.4605772 0.9635797 0.4605772 0.9635797 0.4593607 0.9654002 0.4585229 0.9674231 0.4585229 0.9674231 0.4580957 0.9695706 0.4605772 0.9635797 0.4580957 0.9695706 0.4580957 0.97176 0.4605772 0.9635797 0.4621254 0.9792992 0.4659689 0.9813535 0.4580957 0.97176 0.4659689 0.9813535 0.4703059 0.9817806 0.4580957 0.97176 0.4762967 0.9620316 0.4724532 0.9599772 0.4803264 0.9695706 0.4724532 0.9599772 0.4681164 0.9595499 0.4803264 0.9695706 0.4681164 0.9595499 0.4639459 0.9608151 0.4605772 0.9635797 0.4703059 0.9817806 0.4778449 0.977751 0.4803264 0.9695706 0.4681164 0.9595499 0.4605772 0.9635797 0.4580957 0.97176 0.4580957 0.97176 0.4703059 0.9817806 0.4681164 0.9595499 0.2959966 0.5648227 0.2959968 0.4681466 0.3532367 0.4681466 0.4376942 0.8934424 0.4376942 0.8948968 0.4144251 0.8948968 0.4376942 0.8948968 0.4376942 0.8963511 0.4144251 0.8963511 0.4376942 0.8963511 0.4376942 0.8978053 0.4144251 0.8978053 0.4376942 0.8978053 0.4376942 0.8992596 0.4144251 0.8992596 0.4376942 0.8992596 0.4376942 0.9007139 0.4144251 0.9007139 0.4376942 0.9007139 0.4376942 0.9021683 0.4144251 0.9021683 0.4376942 0.9021683 0.4376942 0.9036226 0.4144251 0.9036226 0.4376942 0.9036226 0.4376942 0.9050769 0.4144251 0.9050769 0.4376942 0.9050769 0.4376942 0.9065311 0.4144251 0.9065311 0.4376942 0.9065311 0.4376942 0.9079855 0.4144251 0.9079855 0.4376942 0.9079855 0.4376942 0.9094398 0.4144251 0.9094398 0.4376942 0.9094398 0.4376942 0.9108941 0.4144251 0.9108941 0.4376942 0.9108941 0.4376942 0.9123485 0.4144251 0.9123485 0.4376942 0.9123485 0.4376942 0.9138028 0.4144251 0.9138028 0.4596215 0.9048914 0.4587835 0.9069141 0.457567 0.9087346 0.457567 0.9087346 0.4560188 0.910283 0.4541983 0.9114994 0.4541983 0.9114994 0.4521755 0.9123373 0.4500281 0.9127644 0.4500281 0.9127644 0.4478385 0.9127644 0.4541983 0.9114994 0.4478385 0.9127644 0.445691 0.9123373 0.4541983 0.9114994 0.445691 0.9123373 0.4436681 0.9114994 0.4390829 0.9069141 0.4436681 0.9114994 0.4418476 0.910283 0.4390829 0.9069141 0.4418476 0.910283 0.4402994 0.9087346 0.4390829 0.9069141 0.4390829 0.9069141 0.4382451 0.9048913 0.4382451 0.8984069 0.4382451 0.9048913 0.437818 0.9027439 0.4382451 0.8984069 0.437818 0.9027439 0.437818 0.9005542 0.4382451 0.8984069 0.4382451 0.8984069 0.4390829 0.896384 0.4402994 0.8945635 0.4402994 0.8945635 0.4418476 0.8930152 0.4436681 0.8917988 0.4436681 0.8917988 0.445691 0.8909608 0.4478385 0.8905338 0.4478385 0.8905338 0.4500281 0.8905338 0.4436681 0.8917988 0.4500281 0.8905338 0.4521755 0.8909608 0.4436681 0.8917988 0.4521755 0.8909608 0.4541983 0.8917988 0.4560189 0.8930152 0.4560189 0.8930152 0.457567 0.8945635 0.4521755 0.8909608 0.457567 0.8945635 0.4587835 0.896384 0.4521755 0.8909608 0.4587835 0.896384 0.4596215 0.8984069 0.4596215 0.9048914 0.4596215 0.8984069 0.4600486 0.9005542 0.4596215 0.9048914 0.4600486 0.9005542 0.4600486 0.9027439 0.4596215 0.9048914 0.4596215 0.9048914 0.457567 0.9087346 0.4541983 0.9114994 0.4382451 0.8984069 0.4402994 0.8945635 0.4521755 0.8909608 0.4402994 0.8945635 0.4436681 0.8917988 0.4521755 0.8909608 0.4596215 0.9048914 0.4541983 0.9114994 0.445691 0.9123373 0.445691 0.9123373 0.4390829 0.9069141 0.4596215 0.9048914 0.4390829 0.9069141 0.4382451 0.8984069 0.4596215 0.9048914 0.4521755 0.8909608 0.4587835 0.896384 0.4596215 0.9048914 0.474476 0.9805157 0.474476 0.9805157 0.4762967 0.9792992 0.4376942 0.9167113 0.4376942 0.9167113 0.4376942 0.9181656 0.4376942 0.9298002 0.4376942 0.9298002 0.4376942 0.9312545 0.4659689 0.9813535 0.4659689 0.9813535 0.4681164 0.9817806 0.4803264 0.97176 0.4803264 0.97176 0.4803264 0.9695706 0.4376942 0.923983 0.4376942 0.923983 0.4376942 0.9254373 0.4762967 0.9792992 0.4762967 0.9792992 0.4778449 0.977751 0.4376942 0.8919881 0.4376942 0.8919881 0.4376942 0.8934424 0.4376942 0.9181656 0.4376942 0.9181656 0.4376942 0.91962 0.4376942 0.9312545 0.4376942 0.9312545 0.4376942 0.9327088 0.4681164 0.9817806 0.4681164 0.9817806 0.4703059 0.9817806 0.4803264 0.9695706 0.4803264 0.9695706 0.4798992 0.9674231 0.4376942 0.8934424 0.4376942 0.8934424 0.4144251 0.8934424 0.4376942 0.9254373 0.4376942 0.9254373 0.4376942 0.9268915 0.4605772 0.977751 0.4605772 0.977751 0.4621254 0.9792992 0.4778449 0.977751 0.4778449 0.977751 0.4790613 0.9759305 0.3532367 0.4681466 0.3532367 0.4681466 0.3532367 0.4109067 0.4144251 0.9138028 0.4144251 0.9138028 0.4376942 0.9138028 0.3532367 0.5648227 0.3532367 0.5648227 0.3532367 0.4681466 0.4376942 0.91962 0.4376942 0.91962 0.4376942 0.9210743 0.4376942 0.9327088 0.4376942 0.9327088 0.4376942 0.9341632 0.4703059 0.9817806 0.4703059 0.9817806 0.4724533 0.9813535 - - - - - - - - - - - - - - -

5 0 0 1 0 1 4 0 2 6 1 3 1 1 4 0 1 5 3 2 6 0 2 7 1 2 8 7 3 9 3 3 10 5 3 11 2 4 15 6 4 16 0 4 17 45 35 108 29 35 109 13 35 110 173 35 312 157 35 313 141 35 314 317 106 516 301 106 517 285 106 518 445 106 720 429 106 721 413 106 722 7 3 765 509 3 766 6 3 767 5 3 822 510 3 823 7 3 824 510 134 834 507 134 835 509 134 836 4 3 930 508 3 931 5 3 932 6 3 936 507 3 937 4 3 938 5 0 948 3 0 949 1 0 950 6 1 951 4 1 952 1 1 953 3 2 954 2 2 955 0 2 956 7 3 957 2 3 958 3 3 959 2 4 963 7 4 964 6 4 965 13 157 1056 11 157 1057 9 157 1058 9 3 1059 71 3 1060 69 3 1061 69 3 1062 67 3 1063 61 3 1064 67 3 1065 65 3 1066 61 3 1067 65 158 1068 63 158 1069 61 158 1070 61 159 1071 59 159 1072 57 159 1073 57 160 1074 55 160 1075 53 160 1076 53 158 1077 51 158 1078 49 158 1079 49 3 1080 47 3 1081 53 3 1082 47 3 1083 45 3 1084 53 3 1085 45 161 1086 43 161 1087 41 161 1088 41 3 1089 39 3 1090 37 3 1091 37 3 1092 35 3 1093 29 3 1094 35 3 1095 33 3 1096 29 3 1097 33 162 1098 31 162 1099 29 162 1100 29 163 1101 27 163 1102 25 163 1103 25 164 1104 23 164 1105 21 164 1106 21 165 1107 19 165 1108 17 165 1109 17 3 1110 15 3 1111 21 3 1112 15 3 1113 13 3 1114 21 3 1115 13 3 1116 9 3 1117 61 3 1118 9 3 1119 69 3 1120 61 3 1121 61 3 1122 57 3 1123 45 3 1124 57 166 1125 53 166 1126 45 166 1127 45 3 1128 41 3 1129 29 3 1130 41 3 1131 37 3 1132 29 3 1133 29 3 1134 25 3 1135 13 3 1136 25 167 1137 21 167 1138 13 167 1139 13 168 1140 61 168 1141 45 168 1142 141 157 1596 139 157 1597 137 157 1598 137 3 1599 199 3 1600 197 3 1601 197 3 1602 195 3 1603 189 3 1604 195 3 1605 193 3 1606 189 3 1607 193 158 1608 191 158 1609 189 158 1610 189 159 1611 187 159 1612 185 159 1613 185 160 1614 183 160 1615 181 160 1616 181 158 1617 179 158 1618 177 158 1619 177 3 1620 175 3 1621 181 3 1622 175 3 1623 173 3 1624 181 3 1625 173 161 1626 171 161 1627 169 161 1628 169 3 1629 167 3 1630 165 3 1631 165 3 1632 163 3 1633 157 3 1634 163 3 1635 161 3 1636 157 3 1637 161 162 1638 159 162 1639 157 162 1640 157 163 1641 155 163 1642 153 163 1643 153 164 1644 151 164 1645 149 164 1646 149 165 1647 147 165 1648 145 165 1649 145 3 1650 143 3 1651 149 3 1652 143 3 1653 141 3 1654 149 3 1655 141 3 1656 137 3 1657 189 3 1658 137 3 1659 197 3 1660 189 3 1661 189 3 1662 185 3 1663 173 3 1664 185 166 1665 181 166 1666 173 166 1667 173 3 1668 169 3 1669 157 3 1670 169 3 1671 165 3 1672 157 3 1673 157 3 1674 153 3 1675 141 3 1676 153 167 1677 149 167 1678 141 167 1679 141 168 1680 189 168 1681 173 168 1682 269 247 2136 267 247 2137 265 247 2138 265 248 2139 327 248 2140 269 248 2141 327 3 2142 325 3 2143 269 3 2144 325 249 2145 323 249 2146 321 249 2147 321 250 2148 319 250 2149 317 250 2150 317 251 2151 315 251 2152 313 251 2153 313 251 2154 311 251 2155 309 251 2156 309 250 2157 307 250 2158 305 250 2159 305 252 2160 303 252 2161 301 252 2162 301 253 2163 299 253 2164 297 253 2165 297 3 2166 295 3 2167 293 3 2168 293 254 2169 291 254 2170 285 254 2171 291 3 2172 289 3 2173 285 3 2174 289 255 2175 287 255 2176 285 255 2177 285 256 2178 283 256 2179 281 256 2180 281 257 2181 279 257 2182 277 257 2183 277 255 2184 275 255 2185 273 255 2186 273 258 2187 271 258 2188 269 258 2189 325 3 2190 321 3 2191 269 3 2192 321 259 2193 317 259 2194 269 259 2195 317 3 2196 313 3 2197 309 3 2198 309 3 2199 305 3 2200 317 3 2201 305 3 2202 301 3 2203 317 3 2204 301 3 2205 297 3 2206 285 3 2207 297 3 2208 293 3 2209 285 3 2210 285 3 2211 281 3 2212 277 3 2213 277 3 2214 273 3 2215 285 3 2216 273 3 2217 269 3 2218 285 3 2219 269 3 2220 317 3 2221 285 3 2222 397 247 2676 395 247 2677 393 247 2678 393 248 2679 455 248 2680 397 248 2681 455 3 2682 453 3 2683 397 3 2684 453 249 2685 451 249 2686 449 249 2687 449 250 2688 447 250 2689 445 250 2690 445 251 2691 443 251 2692 441 251 2693 441 251 2694 439 251 2695 437 251 2696 437 250 2697 435 250 2698 433 250 2699 433 252 2700 431 252 2701 429 252 2702 429 253 2703 427 253 2704 425 253 2705 425 3 2706 423 3 2707 421 3 2708 421 254 2709 419 254 2710 413 254 2711 419 3 2712 417 3 2713 413 3 2714 417 255 2715 415 255 2716 413 255 2717 413 256 2718 411 256 2719 409 256 2720 409 257 2721 407 257 2722 405 257 2723 405 255 2724 403 255 2725 401 255 2726 401 258 2727 399 258 2728 397 258 2729 453 3 2730 449 3 2731 397 3 2732 449 259 2733 445 259 2734 397 259 2735 445 3 2736 441 3 2737 437 3 2738 437 3 2739 433 3 2740 445 3 2741 433 3 2742 429 3 2743 445 3 2744 429 3 2745 425 3 2746 413 3 2747 425 3 2748 421 3 2749 413 3 2750 413 3 2751 409 3 2752 405 3 2753 405 3 2754 401 3 2755 413 3 2756 401 3 2757 397 3 2758 413 3 2759 397 3 2760 445 3 2761 413 3 2762 7 3 2889 510 3 2890 509 3 2891 5 3 2946 508 3 2947 510 3 2948 510 134 3042 508 134 3043 507 134 3044 4 3 3222 507 3 3223 508 3 3224 6 3 3228 509 3 3229 507 3 3230

-
- - - - -

506 3 12 512 3 13 457 3 14 9 5 18 10 5 19 8 5 20 11 6 21 12 6 22 10 6 23 13 7 24 14 7 25 12 7 26 15 8 27 16 8 28 14 8 29 17 9 30 18 9 31 16 9 32 19 10 33 20 10 34 18 10 35 21 11 36 22 11 37 20 11 38 23 12 39 24 12 40 22 12 41 25 13 42 26 13 43 24 13 44 27 14 45 28 14 46 26 14 47 29 15 48 30 15 49 28 15 50 31 16 51 32 16 52 30 16 53 33 17 54 34 17 55 32 17 56 35 18 57 36 18 58 34 18 59 37 19 60 38 19 61 36 19 62 39 20 63 40 20 64 38 20 65 41 21 66 42 21 67 40 21 68 43 22 69 44 22 70 42 22 71 45 23 72 46 23 73 44 23 74 47 24 75 48 24 76 46 24 77 49 25 78 50 25 79 48 25 80 51 26 81 52 26 82 50 26 83 53 27 84 54 27 85 52 27 86 55 28 87 56 28 88 54 28 89 57 29 90 58 29 91 56 29 92 59 30 93 60 30 94 58 30 95 61 31 96 62 31 97 60 31 98 63 32 99 64 32 100 62 32 101 65 33 102 66 33 103 64 33 104 67 34 105 68 34 106 66 34 107 69 36 111 70 36 112 68 36 113 71 37 114 8 37 115 70 37 116 38 1 117 54 1 118 70 1 119 73 38 120 74 38 121 72 38 122 75 39 123 76 39 124 74 39 125 77 40 126 78 40 127 76 40 128 79 41 129 80 41 130 78 41 131 81 42 132 82 42 133 80 42 134 83 43 135 84 43 136 82 43 137 85 44 138 86 44 139 84 44 140 87 45 141 88 45 142 86 45 143 89 46 144 90 46 145 88 46 146 91 47 147 92 47 148 90 47 149 93 48 150 94 48 151 92 48 152 95 49 153 96 49 154 94 49 155 97 50 156 98 50 157 96 50 158 99 51 159 100 51 160 98 51 161 101 52 162 102 52 163 100 52 164 103 53 165 104 53 166 102 53 167 105 54 168 106 54 169 104 54 170 107 55 171 108 55 172 106 55 173 109 56 174 110 56 175 108 56 176 111 57 177 112 57 178 110 57 179 113 58 180 114 58 181 112 58 182 115 59 183 116 59 184 114 59 185 117 60 186 118 60 187 116 60 188 119 61 189 120 61 190 118 61 191 121 62 192 122 62 193 120 62 194 123 63 195 124 63 196 122 63 197 125 64 198 126 64 199 124 64 200 127 65 201 128 65 202 126 65 203 129 66 204 130 66 205 128 66 206 131 67 207 132 67 208 130 67 209 125 68 210 109 68 211 93 68 212 133 69 213 134 69 214 132 69 215 135 70 216 72 70 217 134 70 218 86 71 219 102 71 220 118 71 221 137 5 222 138 5 223 136 5 224 139 6 225 140 6 226 138 6 227 141 7 228 142 7 229 140 7 230 143 8 231 144 8 232 142 8 233 145 72 234 146 72 235 144 72 236 147 10 237 148 10 238 146 10 239 149 11 240 150 11 241 148 11 242 151 12 243 152 12 244 150 12 245 153 13 246 154 13 247 152 13 248 155 73 249 156 73 250 154 73 251 157 15 252 158 15 253 156 15 254 159 16 255 160 16 256 158 16 257 161 17 258 162 17 259 160 17 260 163 18 261 164 18 262 162 18 263 165 19 264 166 19 265 164 19 266 167 20 267 168 20 268 166 20 269 169 74 270 170 74 271 168 74 272 171 22 273 172 22 274 170 22 275 173 23 276 174 23 277 172 23 278 175 24 279 176 24 280 174 24 281 177 75 282 178 75 283 176 75 284 179 26 285 180 26 286 178 26 287 181 27 288 182 27 289 180 27 290 183 76 291 184 76 292 182 76 293 185 77 294 186 77 295 184 77 296 187 30 297 188 30 298 186 30 299 189 31 300 190 31 301 188 31 302 191 32 303 192 32 304 190 32 305 193 33 306 194 33 307 192 33 308 195 78 309 196 78 310 194 78 311 197 36 315 198 36 316 196 36 317 199 79 318 136 79 319 198 79 320 166 1 321 182 1 322 198 1 323 201 80 324 202 80 325 200 80 326 203 81 327 204 81 328 202 81 329 205 40 330 206 40 331 204 40 332 207 41 333 208 41 334 206 41 335 209 42 336 210 42 337 208 42 338 211 43 339 212 43 340 210 43 341 213 44 342 214 44 343 212 44 344 215 82 345 216 82 346 214 82 347 217 46 348 218 46 349 216 46 350 219 47 351 220 47 352 218 47 353 221 83 354 222 83 355 220 83 356 223 84 357 224 84 358 222 84 359 225 85 360 226 85 361 224 85 362 227 51 363 228 51 364 226 51 365 229 86 366 230 86 367 228 86 368 231 53 369 232 53 370 230 53 371 233 87 372 234 87 373 232 87 374 235 88 375 236 88 376 234 88 377 237 56 378 238 56 379 236 56 380 239 57 381 240 57 382 238 57 383 241 58 384 242 58 385 240 58 386 243 59 387 244 59 388 242 59 389 245 89 390 246 89 391 244 89 392 247 90 393 248 90 394 246 90 395 249 62 396 250 62 397 248 62 398 251 63 399 252 63 400 250 63 401 253 64 402 254 64 403 252 64 404 255 65 405 256 65 406 254 65 407 257 66 408 258 66 409 256 66 410 259 67 411 260 67 412 258 67 413 253 68 414 237 68 415 221 68 416 261 91 417 262 91 418 260 91 419 263 70 420 200 70 421 262 70 422 214 71 423 230 71 424 246 71 425 265 92 426 266 92 427 264 92 428 267 93 429 268 93 430 266 93 431 269 7 432 270 7 433 268 7 434 271 8 435 272 8 436 270 8 437 273 72 438 274 72 439 272 72 440 275 94 441 276 94 442 274 94 443 277 95 444 278 95 445 276 95 446 279 96 447 280 96 448 278 96 449 281 97 450 282 97 451 280 97 452 283 98 453 284 98 454 282 98 455 285 99 456 286 99 457 284 99 458 287 16 459 288 16 460 286 16 461 289 17 462 290 17 463 288 17 464 291 18 465 292 18 466 290 18 467 293 19 468 294 19 469 292 19 470 295 20 471 296 20 472 294 20 473 297 74 474 298 74 475 296 74 476 299 22 477 300 22 478 298 22 479 301 23 480 302 23 481 300 23 482 303 24 483 304 24 484 302 24 485 305 75 486 306 75 487 304 75 488 307 100 489 308 100 490 306 100 491 309 101 492 310 101 493 308 101 494 311 102 495 312 102 496 310 102 497 313 103 498 314 103 499 312 103 500 315 104 501 316 104 502 314 104 503 317 105 504 318 105 505 316 105 506 319 32 507 320 32 508 318 32 509 321 33 510 322 33 511 320 33 512 323 78 513 324 78 514 322 78 515 325 107 519 326 107 520 324 107 521 327 108 522 264 108 523 326 108 524 310 109 525 318 109 526 326 109 527 329 80 528 330 80 529 328 80 530 331 110 531 332 110 532 330 110 533 333 111 534 334 111 535 332 111 536 335 112 537 336 112 538 334 112 539 337 113 540 338 113 541 336 113 542 339 114 543 340 114 544 338 114 545 341 115 546 342 115 547 340 115 548 343 82 549 344 82 550 342 82 551 345 116 552 346 116 553 344 116 554 347 117 555 348 117 556 346 117 557 349 83 558 350 83 559 348 83 560 351 84 561 352 84 562 350 84 563 353 85 564 354 85 565 352 85 566 355 51 567 356 51 568 354 51 569 357 86 570 358 86 571 356 86 572 359 53 573 360 53 574 358 53 575 361 87 576 362 87 577 360 87 578 363 88 579 364 88 580 362 88 581 365 56 582 366 56 583 364 56 584 367 57 585 368 57 586 366 57 587 369 58 588 370 58 589 368 58 590 371 59 591 372 59 592 370 59 593 373 118 594 374 118 595 372 118 596 375 119 597 376 119 598 374 119 599 377 62 600 378 62 601 376 62 602 379 120 603 380 120 604 378 120 605 381 121 606 382 121 607 380 121 608 383 122 609 384 122 610 382 122 611 385 123 612 386 123 613 384 123 614 387 124 615 388 124 616 386 124 617 365 3 618 349 3 619 333 3 620 389 125 621 390 125 622 388 125 623 391 70 624 328 70 625 390 70 626 342 1 627 358 1 628 374 1 629 393 92 630 394 92 631 392 92 632 395 93 633 396 93 634 394 93 635 397 7 636 398 7 637 396 7 638 399 8 639 400 8 640 398 8 641 401 9 642 402 9 643 400 9 644 403 94 645 404 94 646 402 94 647 405 95 648 406 95 649 404 95 650 407 96 651 408 96 652 406 96 653 409 97 654 410 97 655 408 97 656 411 126 657 412 126 658 410 126 659 413 99 660 414 99 661 412 99 662 415 16 663 416 16 664 414 16 665 417 17 666 418 17 667 416 17 668 419 18 669 420 18 670 418 18 671 421 19 672 422 19 673 420 19 674 423 20 675 424 20 676 422 20 677 425 21 678 426 21 679 424 21 680 427 22 681 428 22 682 426 22 683 429 23 684 430 23 685 428 23 686 431 24 687 432 24 688 430 24 689 433 25 690 434 25 691 432 25 692 435 100 693 436 100 694 434 100 695 437 101 696 438 101 697 436 101 698 439 127 699 440 127 700 438 127 701 441 128 702 442 128 703 440 128 704 443 104 705 444 104 706 442 104 707 445 105 708 446 105 709 444 105 710 447 32 711 448 32 712 446 32 713 449 33 714 450 33 715 448 33 716 451 34 717 452 34 718 450 34 719 453 107 723 454 107 724 452 107 725 455 129 726 392 129 727 454 129 728 438 109 729 446 109 730 454 109 731 457 38 732 458 38 733 456 38 734 459 130 735 460 130 736 458 130 737 457 3 738 511 3 739 459 3 740 488 3 741 549 3 742 490 3 743 472 3 744 537 3 745 473 3 746 463 3 747 519 3 748 464 3 749 496 3 750 553 3 751 498 3 752 478 3 753 544 3 754 480 3 755 467 3 756 527 3 757 468 3 758 504 3 759 557 3 760 506 3 761 486 3 762 548 3 763 488 3 764 471 3 768 535 3 769 472 3 770 462 3 771 517 3 772 463 3 773 494 3 774 552 3 775 496 3 776 476 3 777 543 3 778 478 3 779 476 54 780 477 54 781 475 54 782 478 55 783 479 55 784 477 55 785 480 56 786 481 56 787 479 56 788 482 57 789 483 57 790 481 57 791 484 58 792 485 58 793 483 58 794 486 59 795 487 59 796 485 59 797 488 131 798 489 131 799 487 131 800 490 132 801 491 132 802 489 132 803 492 62 804 493 62 805 491 62 806 494 120 807 495 120 808 493 120 809 496 121 810 497 121 811 495 121 812 498 122 813 499 122 814 497 122 815 500 123 816 501 123 817 499 123 818 502 124 819 503 124 820 501 124 821 504 133 825 505 133 826 503 133 827 506 70 828 456 70 829 505 70 830 466 1 831 474 1 832 489 1 833 513 111 837 515 111 838 514 111 839 516 112 840 517 112 841 515 112 842 518 113 843 519 113 844 517 113 845 520 114 846 521 114 847 519 114 848 522 115 849 523 115 850 521 115 851 524 45 852 525 45 853 523 45 854 526 116 855 527 116 856 525 116 857 528 117 858 529 117 859 527 117 860 530 48 861 531 48 862 529 48 863 532 49 864 533 49 865 531 49 866 534 50 867 535 50 868 533 50 869 536 51 870 537 51 871 535 51 872 538 52 873 539 52 874 537 52 875 540 53 876 541 53 877 539 53 878 544 3 879 530 3 880 513 3 881 468 3 882 529 3 883 469 3 884 480 3 885 545 3 886 482 3 887 498 3 888 554 3 889 500 3 890 464 3 891 521 3 892 465 3 893 473 3 894 539 3 895 474 3 896 490 3 897 550 3 898 492 3 899 469 3 900 531 3 901 470 3 902 459 3 903 513 3 904 461 3 905 482 3 906 546 3 907 484 3 908 500 3 909 555 3 910 502 3 911 465 3 912 523 3 913 466 3 914 474 3 915 541 3 916 475 3 917 461 3 918 514 3 919 460 3 920 492 3 921 551 3 922 494 3 923 460 3 924 515 3 925 462 3 926 470 3 927 533 3 928 471 3 929 475 3 933 542 3 934 476 3 935 484 3 939 547 3 940 486 3 941 502 3 942 556 3 943 504 3 944 466 3 945 525 3 946 467 3 947 506 3 960 557 3 961 512 3 962 9 135 966 11 135 967 10 135 968 11 136 969 13 136 970 12 136 971 13 137 972 15 137 973 14 137 974 15 138 975 17 138 976 16 138 977 17 139 978 19 139 979 18 139 980 19 10 981 21 10 982 20 10 983 21 11 984 23 11 985 22 11 986 23 140 987 25 140 988 24 140 989 25 141 990 27 141 991 26 141 992 27 14 993 29 14 994 28 14 995 29 15 996 31 15 997 30 15 998 31 142 999 33 142 1000 32 142 1001 33 143 1002 35 143 1003 34 143 1004 35 144 1005 37 144 1006 36 144 1007 37 145 1008 39 145 1009 38 145 1010 39 146 1011 41 146 1012 40 146 1013 41 147 1014 43 147 1015 42 147 1016 43 148 1017 45 148 1018 44 148 1019 45 149 1020 47 149 1021 46 149 1022 47 150 1023 49 150 1024 48 150 1025 49 151 1026 51 151 1027 50 151 1028 51 26 1029 53 26 1030 52 26 1031 53 27 1032 55 27 1033 54 27 1034 55 152 1035 57 152 1036 56 152 1037 57 153 1038 59 153 1039 58 153 1040 59 30 1041 61 30 1042 60 30 1043 61 31 1044 63 31 1045 62 31 1046 63 154 1047 65 154 1048 64 154 1049 65 155 1050 67 155 1051 66 155 1052 67 156 1053 69 156 1054 68 156 1055 69 169 1143 71 169 1144 70 169 1145 71 170 1146 9 170 1147 8 170 1148 70 1 1149 8 1 1150 14 1 1151 8 171 1152 10 171 1153 14 171 1154 10 172 1155 12 172 1156 14 172 1157 14 1 1158 16 1 1159 18 1 1160 18 1 1161 20 1 1162 22 1 1163 22 173 1164 24 173 1165 30 173 1166 24 174 1167 26 174 1168 30 174 1169 26 1 1170 28 1 1171 30 1 1172 30 1 1173 32 1 1174 34 1 1175 34 175 1176 36 175 1177 38 175 1178 38 1 1179 40 1 1180 46 1 1181 40 176 1182 42 176 1183 46 176 1184 42 177 1185 44 177 1186 46 177 1187 46 1 1188 48 1 1189 50 1 1190 50 1 1191 52 1 1192 54 1 1193 54 178 1194 56 178 1195 62 178 1196 56 179 1197 58 179 1198 62 179 1199 58 1 1200 60 1 1201 62 1 1202 62 1 1203 64 1 1204 66 1 1205 66 180 1206 68 180 1207 70 180 1208 14 1 1209 18 1 1210 70 1 1211 18 1 1212 22 1 1213 70 1 1214 30 181 1215 34 181 1216 22 181 1217 34 1 1218 38 1 1219 22 1 1220 46 1 1221 50 1 1222 38 1 1223 50 1 1224 54 1 1225 38 1 1226 62 182 1227 66 182 1228 54 182 1229 66 1 1230 70 1 1231 54 1 1232 70 1 1233 22 1 1234 38 1 1235 73 38 1236 75 38 1237 74 38 1238 75 183 1239 77 183 1240 76 183 1241 77 184 1242 79 184 1243 78 184 1244 79 185 1245 81 185 1246 80 185 1247 81 186 1248 83 186 1249 82 186 1250 83 187 1251 85 187 1252 84 187 1253 85 188 1254 87 188 1255 86 188 1256 87 45 1257 89 45 1258 88 45 1259 89 46 1260 91 46 1261 90 46 1262 91 189 1263 93 189 1264 92 189 1265 93 190 1266 95 190 1267 94 190 1268 95 191 1269 97 191 1270 96 191 1271 97 192 1272 99 192 1273 98 192 1274 99 193 1275 101 193 1276 100 193 1277 101 194 1278 103 194 1279 102 194 1280 103 195 1281 105 195 1282 104 195 1283 105 196 1284 107 196 1285 106 196 1286 107 197 1287 109 197 1288 108 197 1289 109 198 1290 111 198 1291 110 198 1292 111 199 1293 113 199 1294 112 199 1295 113 200 1296 115 200 1297 114 200 1298 115 201 1299 117 201 1300 116 201 1301 117 202 1302 119 202 1303 118 202 1304 119 90 1305 121 90 1306 120 90 1307 121 203 1308 123 203 1309 122 203 1310 123 204 1311 125 204 1312 124 204 1313 125 205 1314 127 205 1315 126 205 1316 127 206 1317 129 206 1318 128 206 1319 129 207 1320 131 207 1321 130 207 1322 131 208 1323 133 208 1324 132 208 1325 77 209 1326 75 209 1327 73 209 1328 73 3 1329 135 3 1330 77 3 1331 135 3 1332 133 3 1333 77 3 1334 133 3 1335 131 3 1336 125 3 1337 131 3 1338 129 3 1339 125 3 1340 129 3 1341 127 3 1342 125 3 1343 125 3 1344 123 3 1345 117 3 1346 123 3 1347 121 3 1348 117 3 1349 121 3 1350 119 3 1351 117 3 1352 117 3 1353 115 3 1354 109 3 1355 115 3 1356 113 3 1357 109 3 1358 113 210 1359 111 210 1360 109 210 1361 109 3 1362 107 3 1363 105 3 1364 105 3 1365 103 3 1366 101 3 1367 101 211 1368 99 211 1369 97 211 1370 97 3 1371 95 3 1372 101 3 1373 95 3 1374 93 3 1375 101 3 1376 93 3 1377 91 3 1378 89 3 1379 89 3 1380 87 3 1381 93 3 1382 87 3 1383 85 3 1384 93 3 1385 85 3 1386 83 3 1387 77 3 1388 83 3 1389 81 3 1390 77 3 1391 81 211 1392 79 211 1393 77 211 1394 109 3 1395 105 3 1396 93 3 1397 105 3 1398 101 3 1399 93 3 1400 77 3 1401 133 3 1402 125 3 1403 125 212 1404 117 212 1405 109 212 1406 93 213 1407 85 213 1408 77 213 1409 77 214 1410 125 214 1411 93 214 1412 133 215 1413 135 215 1414 134 215 1415 135 70 1416 73 70 1417 72 70 1418 134 1 1419 72 1 1420 74 1 1421 74 1 1422 76 1 1423 134 1 1424 76 1 1425 78 1 1426 134 1 1427 78 1 1428 80 1 1429 82 1 1430 82 1 1431 84 1 1432 78 1 1433 84 1 1434 86 1 1435 78 1 1436 86 1 1437 88 1 1438 90 1 1439 90 1 1440 92 1 1441 86 1 1442 92 216 1443 94 216 1444 86 216 1445 94 1 1446 96 1 1447 98 1 1448 98 1 1449 100 1 1450 94 1 1451 100 1 1452 102 1 1453 94 1 1454 102 217 1455 104 217 1456 110 217 1457 104 1 1458 106 1 1459 110 1 1460 106 1 1461 108 1 1462 110 1 1463 110 1 1464 112 1 1465 114 1 1466 114 218 1467 116 218 1468 118 218 1469 118 1 1470 120 1 1471 122 1 1472 122 1 1473 124 1 1474 126 1 1475 126 1 1476 128 1 1477 130 1 1478 130 1 1479 132 1 1480 126 1 1481 132 1 1482 134 1 1483 126 1 1484 110 219 1485 114 219 1486 102 219 1487 114 1 1488 118 1 1489 102 1 1490 118 220 1491 122 220 1492 134 220 1493 122 1 1494 126 1 1495 134 1 1496 134 221 1497 78 221 1498 86 221 1499 86 222 1500 94 222 1501 102 222 1502 134 223 1503 86 223 1504 118 223 1505 137 135 1506 139 135 1507 138 135 1508 139 136 1509 141 136 1510 140 136 1511 141 137 1512 143 137 1513 142 137 1514 143 138 1515 145 138 1516 144 138 1517 145 139 1518 147 139 1519 146 139 1520 147 10 1521 149 10 1522 148 10 1523 149 224 1524 151 224 1525 150 224 1526 151 140 1527 153 140 1528 152 140 1529 153 141 1530 155 141 1531 154 141 1532 155 14 1533 157 14 1534 156 14 1535 157 15 1536 159 15 1537 158 15 1538 159 225 1539 161 225 1540 160 225 1541 161 143 1542 163 143 1543 162 143 1544 163 144 1545 165 144 1546 164 144 1547 165 145 1548 167 145 1549 166 145 1550 167 146 1551 169 146 1552 168 146 1553 169 74 1554 171 74 1555 170 74 1556 171 148 1557 173 148 1558 172 148 1559 173 226 1560 175 226 1561 174 226 1562 175 150 1563 177 150 1564 176 150 1565 177 151 1566 179 151 1567 178 151 1568 179 26 1569 181 26 1570 180 26 1571 181 27 1572 183 27 1573 182 27 1574 183 227 1575 185 227 1576 184 227 1577 185 228 1578 187 228 1579 186 228 1580 187 30 1581 189 30 1582 188 30 1583 189 31 1584 191 31 1585 190 31 1586 191 229 1587 193 229 1588 192 229 1589 193 155 1590 195 155 1591 194 155 1592 195 156 1593 197 156 1594 196 156 1595 197 169 1683 199 169 1684 198 169 1685 199 79 1686 137 79 1687 136 79 1688 198 1 1689 136 1 1690 142 1 1691 136 171 1692 138 171 1693 142 171 1694 138 172 1695 140 172 1696 142 172 1697 142 1 1698 144 1 1699 146 1 1700 146 1 1701 148 1 1702 150 1 1703 150 173 1704 152 173 1705 158 173 1706 152 174 1707 154 174 1708 158 174 1709 154 1 1710 156 1 1711 158 1 1712 158 1 1713 160 1 1714 162 1 1715 162 175 1716 164 175 1717 166 175 1718 166 1 1719 168 1 1720 174 1 1721 168 176 1722 170 176 1723 174 176 1724 170 177 1725 172 177 1726 174 177 1727 174 1 1728 176 1 1729 178 1 1730 178 1 1731 180 1 1732 182 1 1733 182 178 1734 184 178 1735 190 178 1736 184 179 1737 186 179 1738 190 179 1739 186 1 1740 188 1 1741 190 1 1742 190 1 1743 192 1 1744 194 1 1745 194 180 1746 196 180 1747 198 180 1748 142 1 1749 146 1 1750 198 1 1751 146 1 1752 150 1 1753 198 1 1754 158 181 1755 162 181 1756 150 181 1757 162 1 1758 166 1 1759 150 1 1760 174 1 1761 178 1 1762 166 1 1763 178 1 1764 182 1 1765 166 1 1766 190 182 1767 194 182 1768 182 182 1769 194 1 1770 198 1 1771 182 1 1772 198 1 1773 150 1 1774 166 1 1775 201 38 1776 203 38 1777 202 38 1778 203 230 1779 205 230 1780 204 230 1781 205 184 1782 207 184 1783 206 184 1784 207 231 1785 209 231 1786 208 231 1787 209 232 1788 211 232 1789 210 232 1790 211 233 1791 213 233 1792 212 233 1793 213 188 1794 215 188 1795 214 188 1796 215 45 1797 217 45 1798 216 45 1799 217 234 1800 219 234 1801 218 234 1802 219 189 1803 221 189 1804 220 189 1805 221 190 1806 223 190 1807 222 190 1808 223 191 1809 225 191 1810 224 191 1811 225 192 1812 227 192 1813 226 192 1814 227 193 1815 229 193 1816 228 193 1817 229 235 1818 231 235 1819 230 235 1820 231 236 1821 233 236 1822 232 236 1823 233 196 1824 235 196 1825 234 196 1826 235 237 1827 237 237 1828 236 237 1829 237 198 1830 239 198 1831 238 198 1832 239 199 1833 241 199 1834 240 199 1835 241 200 1836 243 200 1837 242 200 1838 243 201 1839 245 201 1840 244 201 1841 245 202 1842 247 202 1843 246 202 1844 247 90 1845 249 90 1846 248 90 1847 249 62 1848 251 62 1849 250 62 1850 251 238 1851 253 238 1852 252 238 1853 253 205 1854 255 205 1855 254 205 1856 255 206 1857 257 206 1858 256 206 1859 257 207 1860 259 207 1861 258 207 1862 259 208 1863 261 208 1864 260 208 1865 205 209 1866 203 209 1867 201 209 1868 201 3 1869 263 3 1870 205 3 1871 263 3 1872 261 3 1873 205 3 1874 261 3 1875 259 3 1876 253 3 1877 259 3 1878 257 3 1879 253 3 1880 257 3 1881 255 3 1882 253 3 1883 253 3 1884 251 3 1885 245 3 1886 251 3 1887 249 3 1888 245 3 1889 249 3 1890 247 3 1891 245 3 1892 245 3 1893 243 3 1894 237 3 1895 243 3 1896 241 3 1897 237 3 1898 241 210 1899 239 210 1900 237 210 1901 237 3 1902 235 3 1903 233 3 1904 233 3 1905 231 3 1906 229 3 1907 229 211 1908 227 211 1909 225 211 1910 225 3 1911 223 3 1912 229 3 1913 223 3 1914 221 3 1915 229 3 1916 221 3 1917 219 3 1918 217 3 1919 217 3 1920 215 3 1921 221 3 1922 215 3 1923 213 3 1924 221 3 1925 213 3 1926 211 3 1927 205 3 1928 211 3 1929 209 3 1930 205 3 1931 209 211 1932 207 211 1933 205 211 1934 237 3 1935 233 3 1936 221 3 1937 233 3 1938 229 3 1939 221 3 1940 205 3 1941 261 3 1942 253 3 1943 253 212 1944 245 212 1945 237 212 1946 221 213 1947 213 213 1948 205 213 1949 205 214 1950 253 214 1951 221 214 1952 261 239 1953 263 239 1954 262 239 1955 263 240 1956 201 240 1957 200 240 1958 262 1 1959 200 1 1960 202 1 1961 202 1 1962 204 1 1963 262 1 1964 204 1 1965 206 1 1966 262 1 1967 206 1 1968 208 1 1969 210 1 1970 210 1 1971 212 1 1972 206 1 1973 212 1 1974 214 1 1975 206 1 1976 214 1 1977 216 1 1978 218 1 1979 218 1 1980 220 1 1981 214 1 1982 220 216 1983 222 216 1984 214 216 1985 222 1 1986 224 1 1987 226 1 1988 226 1 1989 228 1 1990 222 1 1991 228 1 1992 230 1 1993 222 1 1994 230 217 1995 232 217 1996 238 217 1997 232 1 1998 234 1 1999 238 1 2000 234 1 2001 236 1 2002 238 1 2003 238 1 2004 240 1 2005 242 1 2006 242 218 2007 244 218 2008 246 218 2009 246 1 2010 248 1 2011 250 1 2012 250 1 2013 252 1 2014 254 1 2015 254 1 2016 256 1 2017 258 1 2018 258 1 2019 260 1 2020 254 1 2021 260 1 2022 262 1 2023 254 1 2024 238 219 2025 242 219 2026 230 219 2027 242 1 2028 246 1 2029 230 1 2030 246 220 2031 250 220 2032 262 220 2033 250 1 2034 254 1 2035 262 1 2036 262 221 2037 206 221 2038 214 221 2039 214 222 2040 222 222 2041 230 222 2042 262 223 2043 214 223 2044 246 223 2045 265 241 2046 267 241 2047 266 241 2048 267 93 2049 269 93 2050 268 93 2051 269 137 2052 271 137 2053 270 137 2054 271 138 2055 273 138 2056 272 138 2057 273 139 2058 275 139 2059 274 139 2060 275 94 2061 277 94 2062 276 94 2063 277 242 2064 279 242 2065 278 242 2066 279 243 2067 281 243 2068 280 243 2069 281 244 2070 283 244 2071 282 244 2072 283 126 2073 285 126 2074 284 126 2075 285 99 2076 287 99 2077 286 99 2078 287 225 2079 289 225 2080 288 225 2081 289 143 2082 291 143 2083 290 143 2084 291 144 2085 293 144 2086 292 144 2087 293 145 2088 295 145 2089 294 145 2090 295 146 2091 297 146 2092 296 146 2093 297 74 2094 299 74 2095 298 74 2096 299 148 2097 301 148 2098 300 148 2099 301 226 2100 303 226 2101 302 226 2102 303 150 2103 305 150 2104 304 150 2105 305 151 2106 307 151 2107 306 151 2108 307 100 2109 309 100 2110 308 100 2111 309 101 2112 311 101 2113 310 101 2114 311 245 2115 313 245 2116 312 245 2117 313 246 2118 315 246 2119 314 246 2120 315 104 2121 317 104 2122 316 104 2123 317 105 2124 319 105 2125 318 105 2126 319 229 2127 321 229 2128 320 229 2129 321 155 2130 323 155 2131 322 155 2132 323 156 2133 325 156 2134 324 156 2135 325 107 2223 327 107 2224 326 107 2225 327 260 2226 265 260 2227 264 260 2228 326 1 2229 264 1 2230 266 1 2231 266 1 2232 268 1 2233 270 1 2234 270 1 2235 272 1 2236 274 1 2237 274 1 2238 276 1 2239 270 1 2240 276 1 2241 278 1 2242 270 1 2243 278 261 2244 280 261 2245 286 261 2246 280 262 2247 282 262 2248 286 262 2249 282 1 2250 284 1 2251 286 1 2252 286 1 2253 288 1 2254 294 1 2255 288 1 2256 290 1 2257 294 1 2258 290 263 2259 292 263 2260 294 263 2261 294 1 2262 296 1 2263 302 1 2264 296 176 2265 298 176 2266 302 176 2267 298 264 2268 300 264 2269 302 264 2270 302 1 2271 304 1 2272 306 1 2273 306 1 2274 308 1 2275 302 1 2276 308 1 2277 310 1 2278 302 1 2279 310 265 2280 312 265 2281 318 265 2282 312 266 2283 314 266 2284 318 266 2285 314 1 2286 316 1 2287 318 1 2288 318 1 2289 320 1 2290 326 1 2291 320 1 2292 322 1 2293 326 1 2294 322 1 2295 324 1 2296 326 1 2297 326 1 2298 266 1 2299 278 1 2300 266 1 2301 270 1 2302 278 1 2303 278 1 2304 286 1 2305 326 1 2306 286 1 2307 294 1 2308 326 1 2309 294 1 2310 302 1 2311 326 1 2312 302 267 2313 310 267 2314 326 267 2315 329 38 2316 331 38 2317 330 38 2318 331 130 2319 333 130 2320 332 130 2321 333 268 2322 335 268 2323 334 268 2324 335 269 2325 337 269 2326 336 269 2327 337 270 2328 339 270 2329 338 270 2330 339 271 2331 341 271 2332 340 271 2333 341 272 2334 343 272 2335 342 272 2336 343 45 2337 345 45 2338 344 45 2339 345 273 2340 347 273 2341 346 273 2342 347 274 2343 349 274 2344 348 274 2345 349 190 2346 351 190 2347 350 190 2348 351 191 2349 353 191 2350 352 191 2351 353 192 2352 355 192 2353 354 192 2354 355 193 2355 357 193 2356 356 193 2357 357 235 2358 359 235 2359 358 235 2360 359 236 2361 361 236 2362 360 236 2363 361 196 2364 363 196 2365 362 196 2366 363 237 2367 365 237 2368 364 237 2369 365 198 2370 367 198 2371 366 198 2372 367 199 2373 369 199 2374 368 199 2375 369 200 2376 371 200 2377 370 200 2378 371 201 2379 373 201 2380 372 201 2381 373 275 2382 375 275 2383 374 275 2384 375 276 2385 377 276 2386 376 276 2387 377 62 2388 379 62 2389 378 62 2390 379 277 2391 381 277 2392 380 277 2393 381 278 2394 383 278 2395 382 278 2396 383 279 2397 385 279 2398 384 279 2399 385 280 2400 387 280 2401 386 280 2402 387 281 2403 389 281 2404 388 281 2405 333 282 2406 331 282 2407 329 282 2408 329 283 2409 391 283 2410 389 283 2411 389 284 2412 387 284 2413 385 284 2414 385 3 2415 383 3 2416 389 3 2417 383 3 2418 381 3 2419 389 3 2420 381 3 2421 379 3 2422 373 3 2423 379 3 2424 377 3 2425 373 3 2426 377 3 2427 375 3 2428 373 3 2429 373 3 2430 371 3 2431 365 3 2432 371 3 2433 369 3 2434 365 3 2435 369 210 2436 367 210 2437 365 210 2438 365 3 2439 363 3 2440 361 3 2441 361 3 2442 359 3 2443 357 3 2444 357 211 2445 355 211 2446 353 211 2447 353 3 2448 351 3 2449 357 3 2450 351 3 2451 349 3 2452 357 3 2453 349 3 2454 347 3 2455 345 3 2456 345 3 2457 343 3 2458 349 3 2459 343 3 2460 341 3 2461 349 3 2462 341 3 2463 339 3 2464 333 3 2465 339 3 2466 337 3 2467 333 3 2468 337 285 2469 335 285 2470 333 285 2471 333 3 2472 329 3 2473 389 3 2474 365 3 2475 361 3 2476 349 3 2477 361 3 2478 357 3 2479 349 3 2480 333 3 2481 389 3 2482 381 3 2483 381 3 2484 373 3 2485 333 3 2486 373 3 2487 365 3 2488 333 3 2489 349 213 2490 341 213 2491 333 213 2492 389 133 2493 391 133 2494 390 133 2495 391 240 2496 329 240 2497 328 240 2498 390 1 2499 328 1 2500 330 1 2501 330 1 2502 332 1 2503 390 1 2504 332 286 2505 334 286 2506 390 286 2507 334 287 2508 336 287 2509 338 287 2510 338 1 2511 340 1 2512 342 1 2513 342 1 2514 344 1 2515 346 1 2516 346 1 2517 348 1 2518 342 1 2519 348 1 2520 350 1 2521 342 1 2522 350 1 2523 352 1 2524 354 1 2525 354 1 2526 356 1 2527 350 1 2528 356 1 2529 358 1 2530 350 1 2531 358 217 2532 360 217 2533 366 217 2534 360 1 2535 362 1 2536 366 1 2537 362 1 2538 364 1 2539 366 1 2540 366 1 2541 368 1 2542 370 1 2543 370 1 2544 372 1 2545 374 1 2546 374 1 2547 376 1 2548 378 1 2549 378 1 2550 380 1 2551 382 1 2552 382 288 2553 384 288 2554 386 288 2555 386 1 2556 388 1 2557 382 1 2558 388 1 2559 390 1 2560 382 1 2561 334 1 2562 338 1 2563 390 1 2564 338 1 2565 342 1 2566 390 1 2567 366 289 2568 370 289 2569 358 289 2570 370 1 2571 374 1 2572 358 1 2573 374 1 2574 378 1 2575 382 1 2576 342 1 2577 350 1 2578 358 1 2579 374 1 2580 382 1 2581 390 1 2582 390 1 2583 342 1 2584 374 1 2585 393 241 2586 395 241 2587 394 241 2588 395 93 2589 397 93 2590 396 93 2591 397 137 2592 399 137 2593 398 137 2594 399 138 2595 401 138 2596 400 138 2597 401 139 2598 403 139 2599 402 139 2600 403 94 2601 405 94 2602 404 94 2603 405 95 2604 407 95 2605 406 95 2606 407 243 2607 409 243 2608 408 243 2609 409 244 2610 411 244 2611 410 244 2612 411 126 2613 413 126 2614 412 126 2615 413 99 2616 415 99 2617 414 99 2618 415 142 2619 417 142 2620 416 142 2621 417 143 2622 419 143 2623 418 143 2624 419 144 2625 421 144 2626 420 144 2627 421 145 2628 423 145 2629 422 145 2630 423 146 2631 425 146 2632 424 146 2633 425 147 2634 427 147 2635 426 147 2636 427 148 2637 429 148 2638 428 148 2639 429 149 2640 431 149 2641 430 149 2642 431 150 2643 433 150 2644 432 150 2645 433 151 2646 435 151 2647 434 151 2648 435 100 2649 437 100 2650 436 100 2651 437 101 2652 439 101 2653 438 101 2654 439 290 2655 441 290 2656 440 290 2657 441 291 2658 443 291 2659 442 291 2660 443 104 2661 445 104 2662 444 104 2663 445 105 2664 447 105 2665 446 105 2666 447 154 2667 449 154 2668 448 154 2669 449 155 2670 451 155 2671 450 155 2672 451 156 2673 453 156 2674 452 156 2675 453 107 2763 455 107 2764 454 107 2765 455 292 2766 393 292 2767 392 292 2768 454 1 2769 392 1 2770 394 1 2771 394 1 2772 396 1 2773 398 1 2774 398 1 2775 400 1 2776 402 1 2777 402 1 2778 404 1 2779 398 1 2780 404 1 2781 406 1 2782 398 1 2783 406 261 2784 408 261 2785 414 261 2786 408 262 2787 410 262 2788 414 262 2789 410 1 2790 412 1 2791 414 1 2792 414 1 2793 416 1 2794 422 1 2795 416 1 2796 418 1 2797 422 1 2798 418 263 2799 420 263 2800 422 263 2801 422 1 2802 424 1 2803 430 1 2804 424 176 2805 426 176 2806 430 176 2807 426 264 2808 428 264 2809 430 264 2810 430 1 2811 432 1 2812 434 1 2813 434 1 2814 436 1 2815 430 1 2816 436 1 2817 438 1 2818 430 1 2819 438 265 2820 440 265 2821 446 265 2822 440 266 2823 442 266 2824 446 266 2825 442 1 2826 444 1 2827 446 1 2828 446 1 2829 448 1 2830 454 1 2831 448 1 2832 450 1 2833 454 1 2834 450 1 2835 452 1 2836 454 1 2837 454 1 2838 394 1 2839 406 1 2840 394 1 2841 398 1 2842 406 1 2843 406 1 2844 414 1 2845 454 1 2846 414 1 2847 422 1 2848 454 1 2849 422 1 2850 430 1 2851 454 1 2852 430 267 2853 438 267 2854 454 267 2855 457 38 2856 459 38 2857 458 38 2858 459 110 2859 461 110 2860 460 110 2861 457 3 2862 512 3 2863 511 3 2864 488 3 2865 548 3 2866 549 3 2867 472 3 2868 535 3 2869 537 3 2870 463 3 2871 517 3 2872 519 3 2873 496 3 2874 552 3 2875 553 3 2876 478 3 2877 543 3 2878 544 3 2879 467 3 2880 525 3 2881 527 3 2882 504 3 2883 556 3 2884 557 3 2885 486 3 2886 547 3 2887 548 3 2888 471 3 2892 533 3 2893 535 3 2894 462 3 2895 515 3 2896 517 3 2897 494 3 2898 551 3 2899 552 3 2900 476 3 2901 542 3 2902 543 3 2903 476 196 2904 478 196 2905 477 196 2906 478 197 2907 480 197 2908 479 197 2909 480 198 2910 482 198 2911 481 198 2912 482 199 2913 484 199 2914 483 199 2915 484 200 2916 486 200 2917 485 200 2918 486 201 2919 488 201 2920 487 201 2921 488 275 2922 490 275 2923 489 275 2924 490 276 2925 492 276 2926 491 276 2927 492 203 2928 494 203 2929 493 203 2930 494 293 2931 496 293 2932 495 293 2933 496 278 2934 498 278 2935 497 278 2936 498 279 2937 500 279 2938 499 279 2939 500 280 2940 502 280 2941 501 280 2942 502 281 2943 504 281 2944 503 281 2945 504 125 2949 506 125 2950 505 125 2951 506 70 2952 457 70 2953 456 70 2954 505 1 2955 456 1 2956 458 1 2957 458 1 2958 460 1 2959 505 1 2960 460 286 2961 462 286 2962 505 286 2963 462 287 2964 463 287 2965 464 287 2966 464 1 2967 465 1 2968 466 1 2969 466 1 2970 467 1 2971 468 1 2972 468 1 2973 469 1 2974 466 1 2975 469 1 2976 470 1 2977 466 1 2978 470 1 2979 471 1 2980 472 1 2981 472 1 2982 473 1 2983 470 1 2984 473 1 2985 474 1 2986 470 1 2987 474 217 2988 475 217 2989 481 217 2990 475 1 2991 477 1 2992 481 1 2993 477 1 2994 479 1 2995 481 1 2996 481 1 2997 483 1 2998 485 1 2999 485 1 3000 487 1 3001 489 1 3002 489 1 3003 491 1 3004 493 1 3005 493 1 3006 495 1 3007 497 1 3008 497 288 3009 499 288 3010 501 288 3011 501 1 3012 503 1 3013 497 1 3014 503 1 3015 505 1 3016 497 1 3017 462 1 3018 464 1 3019 505 1 3020 464 1 3021 466 1 3022 505 1 3023 481 289 3024 485 289 3025 474 289 3026 485 1 3027 489 1 3028 474 1 3029 489 1 3030 493 1 3031 497 1 3032 466 1 3033 470 1 3034 474 1 3035 489 1 3036 497 1 3037 505 1 3038 505 1 3039 466 1 3040 489 1 3041 513 268 3045 516 268 3046 515 268 3047 516 294 3048 518 294 3049 517 294 3050 518 295 3051 520 295 3052 519 295 3053 520 296 3054 522 296 3055 521 296 3056 522 272 3057 524 272 3058 523 272 3059 524 45 3060 526 45 3061 525 45 3062 526 297 3063 528 297 3064 527 297 3065 528 274 3066 530 274 3067 529 274 3068 530 190 3069 532 190 3070 531 190 3071 532 191 3072 534 191 3073 533 191 3074 534 192 3075 536 192 3076 535 192 3077 536 193 3078 538 193 3079 537 193 3080 538 194 3081 540 194 3082 539 194 3083 540 195 3084 542 195 3085 541 195 3086 513 282 3087 511 282 3088 512 282 3089 512 283 3090 557 283 3091 556 283 3092 556 284 3093 555 284 3094 554 284 3095 554 3 3096 553 3 3097 556 3 3098 553 3 3099 552 3 3100 556 3 3101 552 3 3102 551 3 3103 548 3 3104 551 3 3105 550 3 3106 548 3 3107 550 3 3108 549 3 3109 548 3 3110 548 3 3111 547 3 3112 544 3 3113 547 3 3114 546 3 3115 544 3 3116 546 210 3117 545 210 3118 544 210 3119 544 3 3120 543 3 3121 542 3 3122 542 3 3123 540 3 3124 538 3 3125 538 211 3126 536 211 3127 534 211 3128 534 3 3129 532 3 3130 538 3 3131 532 3 3132 530 3 3133 538 3 3134 530 3 3135 528 3 3136 526 3 3137 526 3 3138 524 3 3139 530 3 3140 524 3 3141 522 3 3142 530 3 3143 522 3 3144 520 3 3145 513 3 3146 520 3 3147 518 3 3148 513 3 3149 518 285 3150 516 285 3151 513 285 3152 513 3 3153 512 3 3154 556 3 3155 544 3 3156 542 3 3157 530 3 3158 542 3 3159 538 3 3160 530 3 3161 513 3 3162 556 3 3163 552 3 3164 552 3 3165 548 3 3166 513 3 3167 548 3 3168 544 3 3169 513 3 3170 530 213 3171 522 213 3172 513 213 3173 468 3 3174 527 3 3175 529 3 3176 480 3 3177 544 3 3178 545 3 3179 498 3 3180 553 3 3181 554 3 3182 464 3 3183 519 3 3184 521 3 3185 473 3 3186 537 3 3187 539 3 3188 490 3 3189 549 3 3190 550 3 3191 469 3 3192 529 3 3193 531 3 3194 459 3 3195 511 3 3196 513 3 3197 482 3 3198 545 3 3199 546 3 3200 500 3 3201 554 3 3202 555 3 3203 465 3 3204 521 3 3205 523 3 3206 474 3 3207 539 3 3208 541 3 3209 461 3 3210 513 3 3211 514 3 3212 492 3 3213 550 3 3214 551 3 3215 460 3 3216 514 3 3217 515 3 3218 470 3 3219 531 3 3220 533 3 3221 475 3 3225 541 3 3226 542 3 3227 484 3 3231 546 3 3232 547 3 3233 502 3 3234 555 3 3235 556 3 3236 466 3 3237 523 3 3238 525 3 3239

-
-
-
- - - - -1.474082 0.217336 1.01988e-5 -1.479092 0.2177813 -0.004979968 0.2736381 0.217336 1.01988e-5 0.2786481 0.2177813 -0.004979968 -1.474082 -0.7493964 1.02384e-5 -1.479092 -0.753602 -0.004999756 0.2736381 -0.7493964 1.02384e-5 0.2786481 -0.753602 -0.004999756 -1.474082 -0.8876649 0.7859569 -1.479092 -0.8925992 0.7850893 0.2786481 -0.8934656 0.7900142 0.2736381 -0.8876632 0.7859471 -1.479092 0.3160436 0.0126779 -1.474082 0.3151565 0.0176087 0.2736381 0.3151565 0.0176087 0.2786481 0.3160436 0.0126779 -1.479092 0.1511854 0.9685161 -1.474082 0.146251 0.9676489 0.2786481 0.1453955 0.9725752 0.2736381 0.1462626 0.9676408 -0.9896055 0.217336 1.02384e-5 -0.9893102 0.2177831 -0.004999756 -0.6572885 -0.7493964 1.02384e-5 -0.6572885 -0.753602 -0.004999756 -1.243367 0.3160436 0.0126779 -1.474082 -0.9285135 1.018405 -1.479092 -0.934315 1.022473 -1.474082 0.1054024 1.200097 -1.479092 0.1094697 1.205899 0.2736381 -0.6473677 0.588774 0.2736381 -0.6474025 0.5943585 0.2736381 -0.6468119 0.5999118 0.2736381 -0.6467079 0.5832285 0.2736381 -0.6456031 0.605364 0.2736381 -0.6437915 0.6106467 0.2736381 -0.5716403 0.1735926 0.2736381 -0.5740947 0.178609 0.2736381 -0.575972 0.1838687 0.2736381 -0.5772487 0.1893054 0.2736381 -0.5611571 0.160614 0.2736381 -0.5651306 0.1645382 0.2736381 -0.5469757 0.151826 0.2736381 -0.5520223 0.1542176 0.2736381 -0.5567693 0.1571593 0.2736381 -0.5306876 0.1482149 0.2736381 -0.5362408 0.1488056 0.2736381 -0.525103 0.1482498 0.2736381 -0.541693 0.1500144 0.2736381 -0.5195575 0.1489096 0.2736381 -0.5686397 0.1688826 0.2736381 -0.6350036 0.6248282 0.2736381 -0.6267349 0.6323107 0.2736381 -0.6310793 0.6288016 0.2736381 -0.6220248 0.6353113 0.2736381 -0.6117488 0.639643 0.2736381 -0.6170085 0.6377657 0.2736381 -0.6063121 0.6409196 0.2736381 0.04494291 0.7544856 0.2736381 0.06123101 0.7508745 0.2736381 0.05594843 0.7526862 0.2736381 0.05049616 0.7538949 0.2736381 0.07102465 0.7455412 0.2736381 0.0828951 0.7338179 0.2736381 0.07938599 0.7381623 0.2736381 0.07541251 0.7420865 0.2736381 0.06627762 0.7484829 0.2736381 0.03935837 0.7544507 0.2736381 0.08835005 0.7240915 0.2736381 0.09022736 0.7188318 0.2736381 0.1312638 0.2649348 0.2736381 0.1409902 0.2703898 0.2736381 0.1362801 0.2673892 0.2736381 0.1260042 0.2630575 0.2736381 0.1492589 0.2778724 0.2736381 0.1580469 0.2920538 0.2736381 0.1556552 0.2870073 0.2736381 0.1527135 0.2822602 0.2736381 0.1610672 0.3027887 0.2736381 0.1616579 0.308342 0.2736381 0.161623 0.3139265 0.2736381 0.1598585 0.2973365 0.2736381 0.1609632 0.319472 0.2736381 0.1205675 0.2617809 0.2736381 0.1453346 0.2738989 0.2736381 0.09150397 0.7133951 0.2736381 0.08589565 0.7291079 0.2736381 0.03381288 0.7537909 0.2736381 -0.6413998 0.6156933 0.2736381 -0.6384582 0.6204403 0.2786481 -0.6473677 0.588774 0.2786481 -0.6474025 0.5943585 0.2786481 -0.6468119 0.5999118 0.2786481 -0.6467079 0.5832285 0.2786481 -0.6456031 0.605364 0.2786481 -0.6437915 0.6106467 0.2786481 -0.5716403 0.1735926 0.2786481 -0.5740947 0.178609 0.2786481 -0.575972 0.1838687 0.2786481 -0.5772487 0.1893054 0.2786481 -0.5611571 0.160614 0.2786481 -0.5651306 0.1645382 0.2786481 -0.5469757 0.151826 0.2786481 -0.5520223 0.1542176 0.2786481 -0.5567693 0.1571593 0.2786481 -0.5306876 0.1482149 0.2786481 -0.5362408 0.1488056 0.2786481 -0.525103 0.1482498 0.2786481 -0.541693 0.1500144 0.2786481 -0.5195575 0.1489096 0.2786481 -0.5686397 0.1688826 0.2786481 -0.6413998 0.6156933 0.2786481 -0.6350036 0.6248282 0.2786481 -0.6384582 0.6204403 0.2786481 -0.6310793 0.6288016 0.2786481 -0.6220248 0.6353113 0.2786481 -0.6267349 0.6323107 0.2786481 -0.6117488 0.639643 0.2786481 -0.6170085 0.6377657 0.2786481 -0.6063121 0.6409196 0.2786481 0.05049616 0.7538949 0.2786481 0.04494291 0.7544856 0.2786481 0.03935837 0.7544507 0.2786481 0.06123101 0.7508745 0.2786481 0.07102465 0.7455412 0.2786481 0.07541251 0.7420865 0.2786481 0.06627762 0.7484829 0.2786481 0.05594843 0.7526862 0.2786481 0.08589565 0.7291079 0.2786481 0.0828951 0.7338179 0.2786481 0.09022736 0.7188318 0.2786481 0.08835005 0.7240915 0.2786481 0.1260042 0.2630575 0.2786481 0.1409902 0.2703898 0.2786481 0.1362801 0.2673892 0.2786481 0.1312638 0.2649348 0.2786481 0.1492589 0.2778724 0.2786481 0.1556552 0.2870073 0.2786481 0.1527135 0.2822602 0.2786481 0.1598585 0.2973365 0.2786481 0.1616579 0.308342 0.2786481 0.161623 0.3139265 0.2786481 0.1610672 0.3027887 0.2786481 0.1609632 0.319472 0.2786481 0.1453346 0.2738989 0.2786481 0.1580469 0.2920538 0.2786481 0.1205675 0.2617809 0.2786481 0.09150397 0.7133951 0.2786481 0.03381288 0.7537909 0.2786481 0.07938599 0.7381623 -1.474082 -0.6474026 0.5943585 -1.474082 -0.646708 0.5832285 -1.474082 -0.6473678 0.588774 -1.474082 -0.6468119 0.5999118 -1.474082 -0.6437916 0.6106466 -1.474082 -0.6456032 0.605364 -1.474082 -0.6384583 0.6204403 -1.474082 -0.6413999 0.6156932 -1.474082 -0.6350036 0.6248281 -1.474082 -0.6310794 0.6288015 -1.474082 -0.6220249 0.6353113 -1.474082 -0.6267349 0.6323106 -1.474082 -0.6117489 0.639643 -1.474082 -0.5772488 0.1893053 -1.474082 -0.6063122 0.6409196 -1.474082 -0.6170086 0.6377657 -1.474082 -0.5740948 0.178609 -1.474082 -0.5759721 0.1838686 -1.474082 -0.5716404 0.1735926 -1.474082 -0.5686398 0.1688826 -1.474082 -0.5651307 0.1645381 -1.474082 -0.5611572 0.1606139 -1.474082 -0.5567694 0.1571592 -1.474082 -0.5469758 0.1518259 -1.474082 -0.5416931 0.1500143 -1.474082 -0.5520223 0.1542176 -1.474082 -0.5362409 0.1488056 -1.474082 -0.525103 0.1482498 -1.474082 -0.5306876 0.1482149 -1.474082 0.04494285 0.7544855 -1.474082 0.0504961 0.7538948 -1.474082 0.06123101 0.7508745 -1.474082 0.06627762 0.7484828 -1.474082 0.05594837 0.7526861 -1.474082 0.03935831 0.7544507 -1.474082 -0.5195576 0.1489096 -1.474082 0.07938593 0.7381623 -1.474082 0.07541251 0.7420865 -1.474082 0.08835005 0.7240914 -1.474082 0.08589565 0.7291078 -1.474082 0.08289504 0.7338178 -1.474082 0.1312638 0.2649348 -1.474082 0.1362801 0.2673891 -1.474082 0.1260042 0.2630575 -1.474082 0.0902273 0.7188318 -1.474082 0.1453346 0.2738988 -1.474082 0.1556552 0.2870072 -1.474082 0.1527135 0.2822602 -1.474082 0.1492589 0.2778723 -1.474082 0.1598585 0.2973364 -1.474082 0.1616578 0.3083419 -1.474082 0.161623 0.3139265 -1.474082 0.1580469 0.2920538 -1.474082 0.1610671 0.3027887 -1.474082 0.1609632 0.319472 -1.474082 0.1205674 0.2617809 -1.474082 0.1409902 0.2703897 -1.474082 0.09150397 0.7133951 -1.474082 0.03381282 0.7537909 -1.474082 0.07102465 0.7455412 -1.479092 -0.6473678 0.588774 -1.479092 -0.6474026 0.5943585 -1.479092 -0.6468119 0.5999118 -1.479092 -0.646708 0.5832285 -1.479092 -0.6456032 0.605364 -1.479092 -0.5740948 0.178609 -1.479092 -0.5716404 0.1735926 -1.479092 -0.5759721 0.1838686 -1.479092 -0.5686398 0.1688826 -1.479092 -0.5772488 0.1893053 -1.479092 -0.5611572 0.1606139 -1.479092 -0.5651307 0.1645381 -1.479092 -0.5469758 0.1518259 -1.479092 -0.5520223 0.1542176 -1.479092 -0.5567694 0.1571592 -1.479092 -0.5306876 0.1482149 -1.479092 -0.5362409 0.1488056 -1.479092 -0.525103 0.1482498 -1.479092 -0.5416931 0.1500143 -1.479092 -0.5195576 0.1489096 -1.479092 -0.6437916 0.6106466 -1.479092 -0.6384583 0.6204403 -1.479092 -0.6413999 0.6156932 -1.479092 -0.6350036 0.6248281 -1.479092 -0.6267349 0.6323106 -1.479092 -0.6310794 0.6288015 -1.479092 -0.6117489 0.639643 -1.479092 -0.6170086 0.6377657 -1.479092 -0.6220249 0.6353113 -1.479092 -0.6063122 0.6409196 -1.479092 0.04494285 0.7544855 -1.479092 0.03935831 0.7544507 -1.479092 0.06123101 0.7508745 -1.479092 0.05594837 0.7526861 -1.479092 0.07541251 0.7420865 -1.479092 0.07102465 0.7455412 -1.479092 0.06627762 0.7484828 -1.479092 0.0504961 0.7538948 -1.479092 0.08289504 0.7338178 -1.479092 0.0902273 0.7188318 -1.479092 0.08835005 0.7240914 -1.479092 0.08589565 0.7291078 -1.479092 0.1260042 0.2630575 -1.479092 0.1409902 0.2703897 -1.479092 0.1362801 0.2673891 -1.479092 0.1312638 0.2649348 -1.479092 0.1492589 0.2778723 -1.479092 0.1556552 0.2870072 -1.479092 0.1527135 0.2822602 -1.479092 0.1598585 0.2973364 -1.479092 0.1616578 0.3083419 -1.479092 0.161623 0.3139265 -1.479092 0.1610671 0.3027887 -1.479092 0.1609632 0.319472 -1.479092 0.1453346 0.2738988 -1.479092 0.1580469 0.2920538 -1.479092 0.1205674 0.2617809 -1.479092 0.09150397 0.7133951 -1.479092 0.07938593 0.7381623 -1.479092 0.03381282 0.7537909 -0.9893867 0.2108088 1.02223e-5 -0.6572885 -0.6806749 1.02384e-5 -0.09790301 0.2108088 -0.004988074 -0.9893867 -0.6806749 1.02356e-5 -0.9893867 -0.6806749 -0.004998266 -0.9893867 0.2108088 -0.00499171 -0.6572885 -0.6806749 -0.004999756 -0.09790301 0.2108088 1.02149e-5 -0.09790301 -0.6806749 1.02384e-5 -0.09790301 -0.6806749 -0.004999756 -0.2793233 0.148347 0.9730939 -0.2793233 0.1486856 0.9711045 -0.2793233 0.1462568 0.9676398 -0.6624633 0.1503307 0.97338 -0.6624633 0.1462838 0.9676446 -0.6624633 0.1462528 0.9676392 -0.6624633 -0.7834702 0.1936928 -0.6618477 -0.782115 0.1859893 -0.6572907 -0.7796531 0.1719955 -0.6600161 -0.7807931 0.1784757 -0.6624633 -0.8876632 0.7859472 -0.6624633 -0.8934547 0.7899536 -0.6624633 -0.7884041 0.1928228 -0.6618477 -0.7870488 0.1851194 -0.6600161 -0.785727 0.1776057 -0.6570135 -0.784471 0.1704666 -0.6561933 -0.7842391 0.1691482 -0.2793233 -0.8876632 0.7859471 -0.2793233 -0.8934655 0.7900142 -0.3231408 -0.7749385 0.1451971 -0.3318233 -0.7748069 0.1444489 -0.3147222 -0.7753294 0.1474188 -0.3068232 -0.7759676 0.1510463 -0.293521 -0.7779016 0.1620395 -0.288522 -0.7791386 0.1690709 -0.2812374 -0.7819659 0.1851417 -0.2793233 -0.7834702 0.1936927 -0.2848386 -0.7805072 0.1768504 -0.2996839 -0.7768338 0.1559699 -0.6570135 -0.7795372 0.1713365 -0.6418525 -0.7764615 0.1538537 -0.6478186 -0.7773444 0.1588722 -0.6529141 -0.7783781 0.164748 -0.6279141 -0.775231 0.1468592 -0.620285 -0.7749136 0.1450553 -0.6124632 -0.7748069 0.144449 -0.6351628 -0.7757512 0.1498163 -0.6529141 -0.7833119 0.163878 -0.6418525 -0.7813954 0.1529838 -0.6478186 -0.7822782 0.1580022 -0.6279141 -0.7801648 0.1459892 -0.620285 -0.7798475 0.1441853 -0.6124632 -0.7797408 0.1435791 -0.6351628 -0.7806851 0.1489463 -0.3231408 -0.7798725 0.1443272 -0.3318233 -0.7797409 0.143579 -0.3147222 -0.7802633 0.1465488 -0.3068232 -0.7809015 0.1501764 -0.293521 -0.7828355 0.1611695 -0.288522 -0.7840725 0.1682009 -0.2812374 -0.7868998 0.1842717 -0.2793233 -0.7884041 0.1928227 -0.2848386 -0.7854411 0.1759804 -0.2996839 -0.7817677 0.1550999 -0.6624633 -0.9285135 1.018405 -0.6624633 0.1054024 1.200097 -0.6624633 0.1094697 1.205899 -0.6624633 -0.934315 1.022473 -0.09810417 0.3160436 0.0126779 -0.09770447 0.217782 -0.004987597 -0.989402 -0.753602 -0.004999756 -0.9806979 0.3160436 0.0126779 -0.09802776 0.217336 1.02109e-5 -0.9840301 0.1462522 0.9676424 -0.9840728 0.1506104 0.9717882 -0.09696644 -0.753602 -0.004999756 - - - - - - - - - - 0 0.9842009 0.1770556 -7.56295e-6 0.8188235 -0.5740454 -0.001982748 0.9845606 0.1750332 0.007200002 0.9854246 0.1699605 -7.63306e-5 0.817075 -0.5765314 0 0.9848789 0.1732448 -1 0 0 -1 -3.35565e-6 0 -1 8.86688e-6 0 1 6.82895e-6 0 1 -1.90693e-6 0 0 0 1 -5.21093e-7 -0.9848783 -0.1732481 1 1.08179e-5 0 1 0 0 0 0 1 0 6.11854e-7 1 0 0.1730797 -0.9849079 3.20038e-7 -0.1730797 0.9849079 2.0698e-6 0.9848709 0.1732902 -6.92424e-7 -0.984874 -0.1732721 0 0.1730796 -0.9849079 0 -0.1730798 0.9849079 0 -0.9849079 -0.1730797 0 0.9849079 0.1730796 0 0.9849079 0.1730794 0 0.9762947 -0.2164458 0 0.5267472 0.8500221 0 -0.9999805 -0.006241142 0 0.3361608 -0.9418047 0 0.7857148 -0.6185891 0 0.9848078 0.1736482 0 0.8433955 0.5372933 0 -0.9929957 -0.1181505 0 0.4394978 -0.8982437 0 0.1736475 -0.984808 0 -0.9762973 0.2164339 0 0.2164474 0.9762944 0 0.9999806 0.006224572 0 -0.9943909 0.1057685 0 -0.6283518 0.7779294 0 -0.7857067 0.6185993 0 0.618614 0.7856951 0 -0.8500197 0.5267509 0 -0.228592 0.9735224 0 0.9036552 -0.4282609 0 -0.4394861 0.8982495 0 0.8982503 0.4394845 0 -0.5372973 0.8433929 0 0.1181504 -0.9929957 0 0.6283457 -0.7779343 0 -0.1057696 -0.9943907 0 -0.3243939 -0.9459221 0 -0.9459229 0.324392 0 0.2286005 -0.9735203 0 -0.7026826 -0.7115036 0 0.9735217 0.228595 0 -0.777929 -0.6283522 0 -0.9735203 -0.2286008 0 -0.9036552 0.4282607 0 -0.2164376 -0.9762965 0 -0.8433932 -0.5372971 0 -0.9418079 -0.3361519 0 -0.3361556 0.9418066 0 0.3243806 0.9459267 0 -0.6186045 -0.7857027 0 0.9929957 0.1181505 0 -0.984808 -0.1736471 0 -0.006238162 0.9999806 0 0.006233036 -0.9999806 0 0.7026868 0.7114994 0 0.9459229 -0.324392 0 0.9943892 -0.1057841 0 -0.8982462 -0.4394928 0 0.4282575 0.9036567 0 0.9418043 0.3361619 0 0.8500314 -0.5267322 0 -0.1181516 0.9929956 0 -0.4282507 -0.90366 0 0.7114952 -0.702691 0 0.7779425 0.6283356 0 0.1057644 0.9943913 0 0.5373038 -0.8433889 0 -0.1736475 0.984808 0 -0.7114993 0.7026869 0 -0.5267442 -0.8500239 0 0.5267471 0.8500221 0 -0.9999806 -0.00623697 0 0.3361498 -0.9418087 0 0.7856989 -0.6186093 0 0.9848079 0.1736482 0 0.8433887 0.5373041 0 -0.992995 -0.1181574 0 0.4394943 -0.8982455 0 0.1736471 -0.984808 0 -0.9762982 0.21643 0 0.2164449 0.9762948 0 0.9999806 0.00622487 0 -0.994391 0.1057668 0 -0.6283619 0.7779212 0 -0.7856969 0.6186119 0 0.6185989 0.7857069 0 -0.8500137 0.5267605 0 -0.2285907 0.9735226 0 0.9036617 -0.4282473 0 -0.4394943 0.8982455 0 0.8982486 0.4394877 0 -0.537289 0.8433983 0 0.1181491 -0.9929959 0 0.6283619 -0.7779212 0 -0.1057713 -0.9943905 0 -0.3244009 -0.9459197 0 -0.9459179 0.3244062 0 0.2285963 -0.9735214 0 -0.702674 -0.711512 0 0.9735203 0.2286005 0 -0.7779405 -0.6283381 0 -0.9735169 -0.2286153 0 -0.9036539 0.4282636 0 -0.2164405 -0.9762959 0 -0.8433867 -0.537307 0 -0.9418067 -0.3361551 0 -0.3361524 0.9418076 0 0.3243746 0.9459288 0 -0.6186084 -0.7856995 0 0.9929968 0.1181409 0 -0.9848079 -0.1736482 0 -0.00623846 0.9999806 0 0.006232976 -0.9999806 0 0.7026826 0.7115036 0 0.9459218 -0.324395 0 0.994392 -0.1057573 0 -0.8982486 -0.4394877 0 0.4282674 0.9036521 0 0.9418067 0.3361551 0 0.8500175 -0.5267545 0 -0.1181494 0.9929959 0 -0.4282562 -0.9036574 0 0.7114955 -0.7026908 0 0.1057679 0.9943909 0 0.5372965 -0.8433934 0 -0.1736471 0.984808 0 -0.7114871 0.7026992 0 -0.5267415 -0.8500256 1 2.08583e-7 0 -1 0 0 0.006710708 0.1796821 -0.9837018 0 1 0 -0.0871582 -0.1729847 0.9810605 0.9723701 -0.0405395 0.2298978 0.6494487 -0.1320277 0.748856 -0.2588211 -0.1677237 0.951252 0.2334451 -0.1688478 0.957598 0.8526487 -0.0907309 0.5145465 0.7604106 -0.1127797 0.6395751 1.67666e-7 -0.1736512 0.9848072 0.07846277 -0.1731097 0.9817722 -0.9765493 -0.0373947 0.212022 -0.8191587 -0.09959536 0.5648539 0.9969174 -0.01362347 0.0772674 -0.573582 -0.1422404 0.8067041 0.3826912 -0.1604264 0.9098411 -0.9194119 -0.0682953 0.3873212 0.5225033 -0.1480697 0.8396819 -0.7071037 -0.1227891 0.6963672 1 7.01623e-7 0 -0.4225974 -0.1573779 0.892549 0.9238793 -0.06645822 0.3768692 -0.9063107 -0.07338362 0.4161922 -4.04146e-5 0.1769624 -0.9842177 0 -1 0 -4.47752e-6 0 -1 2.03978e-5 0.1768685 -0.9842345 0 0 -1 1.35904e-5 0.1770625 -0.9841997 4.13793e-6 -0.001146674 -0.9999994 -4.04001e-5 -0.001146197 -0.9999994 0 0.9842017 0.1770511 -0.01345872 -0.1272905 0.9917743 0 -0.1272917 0.9918654 0 -0.1770638 0.9841994 0.02170991 -0.1770222 0.9839674 0 -0.1272917 0.9918653 0 -0.1272915 0.9918655 0 -0.1272915 0.9918654 0.005370557 0.985809 0.167785 0.005370914 0.985809 0.1677855 -0.002055943 0.9845606 0.1750323 0.7071168 0.6961796 0.1237734 -1.05371e-5 0.1723451 -0.9850367 0.004185438 0.6892518 -0.7245098 -1.27199e-5 0.9848757 0.1732628 0 0.9848751 0.1732661 0 0.9848752 0.1732652 2.87918e-7 0.9848718 0.1732849 0 0.9848752 0.1732653 -1 -3.58593e-7 0 -1 4.19113e-5 0 -1 -1.61883e-6 0 -1 2.48318e-6 0 -1 9.01126e-7 0 -1 2.103e-5 0 -1 -5.33284e-6 0 -1 2.12217e-7 0 -1 -4.84437e-5 0 -1 4.37417e-5 0 -1 -3.56303e-5 0 -1 1.76267e-5 0 -1 -1.61299e-6 0 -1 1.72646e-6 0 -1 -3.04251e-7 0 -1 -7.90834e-7 0 -1 0 0 -1 0 0 -1 -1.5184e-6 0 -1 0 0 -1 -3.34734e-6 0 -1 4.5211e-7 0 -1 -5.78928e-7 0 -1 3.94083e-6 0 -1 -3.23559e-6 0 -1 2.56138e-6 0 -1 3.79837e-7 0 -1 -3.55119e-6 0 -1 4.4676e-6 0 -1 -1.41901e-6 0 -1 -1.02424e-6 0 -1 -6.34494e-6 0 -1 1.35983e-5 0 -1 5.97666e-7 0 -1 -7.62368e-7 0 -1 -1.06977e-6 0 -1 -5.74502e-7 0 -1 2.50427e-6 0 -1 0 0 -1 7.30078e-6 0 -1 -1.45497e-5 0 -1 -3.74328e-7 0 -1 -7.33171e-6 0 -1 -5.64911e-7 0 1 -7.31562e-7 0 1 3.52742e-7 0 1 -6.28536e-7 0 1 6.41011e-6 0 1 -2.15138e-6 0 1 -2.51856e-6 0 1 5.98902e-6 0 1 -9.87409e-6 0 1 1.36688e-5 0 1 3.08809e-7 0 1 -8.95685e-6 0 1 -2.83263e-6 0 1 -2.18654e-6 0 1 -3.15858e-6 0 1 3.89472e-6 0 1 1.91021e-6 0 1 -5.2428e-6 0 1 1.9763e-6 0 1 -4.34594e-6 0 1 -5.86448e-6 0 1 1.78186e-7 0 1 2.24021e-6 0 1 -2.34848e-6 0 1 0 0 1 3.2797e-6 0 1 -1.79606e-7 0 1 -4.53576e-6 0 1 2.55422e-6 0 1 9.42617e-7 0 1 -1.92228e-6 0 1 -1.55799e-6 0 1 -4.59593e-6 0 1 4.44753e-6 0 1 3.44626e-6 0 0 0 1 0 -2.46819e-6 1 0 0 1 0 0 1 0 -0.9848753 -0.1732652 0 -0.9848752 -0.1732653 -1.43056e-5 -0.9848691 -0.1733002 -8.42841e-7 -0.9849079 -0.1730796 1.51073e-7 -0.9848753 -0.1732653 -1.42337e-6 -0.9848789 -0.1732442 0 -0.9849084 -0.1730771 3.04956e-7 -0.9848753 -0.1732647 1.42841e-7 -0.984872 -0.1732835 1 2.16453e-5 0 1 2.16493e-5 0 1 -4.66623e-6 0 1 1.09512e-5 0 1 -2.19944e-5 0 1 2.27042e-5 0 1 -2.9423e-5 0 1 3.56906e-5 0 1 -4.41955e-5 0 1 5.58772e-6 0 1 3.56489e-5 0 1 6.11299e-6 0 1 3.33941e-7 0 1 5.98689e-6 0 1 -3.03901e-6 0 1 -3.85361e-5 0 1 3.83312e-5 0 1 -2.83984e-5 0 1 -3.86993e-5 0 1 6.59664e-6 0 1 -3.63745e-6 0 1 3.14416e-6 0 1 3.50874e-6 0 1 1.15673e-5 0 1 3.41849e-6 0 1 7.99613e-6 0 1 5.01086e-7 0 1 -7.38832e-7 0 1 -8.11091e-6 0 1 -4.11456e-6 0 1 -3.70364e-6 0 1 -4.2941e-7 0 1 1.47242e-6 0 1 1.5491e-5 0 1 -2.51128e-5 0 1 2.59666e-5 0 1 2.18767e-5 0 1 -2.17983e-5 0 1 -2.89969e-6 0 1 6.77314e-6 0 1 7.80822e-6 0 -1 -1.22073e-6 0 -1 6.99692e-5 0 -1 -1.91107e-5 0 -1 5.35432e-6 0 -1 -4.60522e-5 0 -1 1.03573e-5 0 -1 -5.79537e-6 0 -1 -3.48437e-6 0 -1 2.11412e-7 0 -1 6.51333e-5 0 -1 -7.70174e-6 0 -1 4.12764e-6 0 -1 8.49302e-6 0 -1 1.44565e-6 0 -1 1.6399e-7 0 -1 -2.30698e-5 0 -1 -1.17734e-6 0 -1 5.94592e-6 0 -1 1.52432e-5 0 0 0 1 0 0 1 0 6.12316e-7 1 0 0 1 0 -2.46442e-6 1 2.05363e-7 0.1730797 -0.9849079 -2.01978e-7 -0.1730797 0.9849079 0 0.9848753 0.1732652 2.25387e-7 0.9848908 0.173177 5.69909e-6 0.9848745 0.1732699 0 0.9848753 0.1732653 7.1953e-7 0.9848777 0.1732512 -2.61746e-6 0.984875 0.1732668 2.07346e-6 0.9848762 0.1732601 -5.22409e-7 0.984875 0.1732671 9.17964e-7 0.9848713 0.1732881 -1.70699e-6 0.9848749 0.1732677 -2.61406e-7 0.9848755 0.1732635 -9.55873e-7 0.984878 0.1732501 5.16346e-7 0.9848749 0.1732675 1.91164e-6 0.9848752 0.1732658 -3.86499e-6 0.9848741 0.1732714 -2.33024e-7 0.9848752 0.1732656 2.78061e-7 0.9848791 0.1732434 0 0.9848754 0.1732645 0 0.9848752 0.1732652 -1.83652e-6 0.9848752 0.1732658 1.35159e-5 -0.9848757 -0.1732625 0 -0.9848753 -0.173265 0 -0.9848754 -0.1732645 1.40801e-6 -0.9848733 -0.1732761 0 -0.9848753 -0.1732652 -2.20214e-7 -0.9848753 -0.173265 -7.76252e-6 -0.984875 -0.1732666 -1.79845e-6 -0.9848762 -0.1732603 -2.12981e-6 -0.9848731 -0.1732774 1.24543e-6 -0.9848767 -0.1732571 1.63912e-6 -0.984875 -0.1732664 3.8822e-7 -0.9848749 -0.1732674 -2.37051e-6 -0.9848769 -0.1732558 2.48715e-6 -0.9848753 -0.1732649 -1.90315e-6 -0.9848752 -0.1732657 3.85614e-6 -0.9848755 -0.1732639 -1.448e-6 -0.9848768 -0.1732566 6.42592e-7 -0.9848732 -0.1732771 -2.47473e-7 -0.9848753 -0.1732649 1.95479e-6 -0.9848784 -0.1732472 0 0.1730796 -0.9849079 0 -0.1730798 0.9849079 0 -0.9849079 -0.1730797 0 -0.9849079 -0.1730796 0 0.9849079 0.1730796 0 0.9849079 0.1730796 0 0.9849079 0.1730797 0 0.9762978 -0.2164317 0 0.5267442 0.8500239 0 -0.9999806 -0.00623703 0 0.3361451 -0.9418103 0 0.7856985 -0.6186096 0 0.984808 0.1736472 0 0.8433856 0.5373089 0 0.4394912 -0.8982469 0 0.1736487 -0.9848077 0 0.2164438 0.9762951 0 0.9999805 0.006241202 0 -0.9943904 0.1057726 0 -0.6283513 0.7779298 0 0.6186004 0.7857059 0 -0.8500239 0.5267442 0 -0.228595 0.9735217 0 0.8982437 0.4394979 0 -0.5373003 0.8433911 0 0.1181505 -0.9929957 0 -0.1057709 -0.9943906 0 -0.3243976 -0.9459208 0 0.2285912 -0.9735226 0 0.973518 0.2286107 0 -0.7779333 -0.6283469 0 -0.9735207 -0.2285989 0 -0.2164361 -0.9762969 0 -0.8433945 -0.5372948 0 -0.9418069 -0.3361545 0 0.3243894 0.9459236 0 -0.618606 -0.7857014 0 -0.9848078 -0.1736484 0 -0.006238281 0.9999806 0 0.006232976 -0.9999806 0 0.7026742 0.7115117 0 0.9943909 -0.1057677 0 -0.8982477 -0.4394896 0 0.4282704 0.9036507 0 0.9418053 0.3361593 0 0.8500217 -0.526748 0 -0.1181535 0.9929954 0 -0.4282541 -0.9036585 0 0.7114995 -0.7026867 0 0.777923 0.6283598 0 0.1057655 0.9943912 0 0.5372992 -0.8433918 0 -0.1736487 0.9848077 0 -0.7114952 0.702691 0 -0.5267481 -0.8500215 0 0.9762982 -0.21643 0 0.5267397 0.8500268 0 -0.9999806 -0.006237387 0 0.3361445 -0.9418105 0 0.7857116 -0.6185931 0 0.9848079 0.1736479 0 0.8433907 0.5373008 0 -0.9929963 -0.1181455 0 0.1736471 -0.984808 0 -0.9762951 0.216444 0 0.2164414 0.9762957 0 0.9999805 0.0062415 0 -0.9943907 0.1057696 0 -0.6283438 0.7779358 0 -0.7857116 0.6185931 0 0.6186034 0.7857035 0 -0.8500249 0.5267426 0 -0.2285987 0.9735208 0 0.903649 -0.4282737 0 -0.4394809 0.898252 0 0.8982422 0.4395009 0 -0.5373108 0.8433843 0 0.1181533 -0.9929955 0 0.6283538 -0.7779277 0 -0.105767 -0.994391 0 -0.9459227 0.3243922 0 -0.7026899 -0.7114964 0 0.9735167 0.2286162 0 -0.7779273 -0.6283544 0 -0.9735209 -0.2285985 0 -0.9036555 0.4282602 0 -0.216433 -0.9762976 0 -0.8433964 -0.537292 0 -0.9418105 -0.3361445 0 0.3243848 0.9459253 0 0.9929959 0.1181496 0 -0.9848079 -0.1736482 0 -0.006238102 0.9999806 0 0.006232976 -0.9999806 0 0.702674 0.711512 0 0.9459202 -0.3243997 0 0.994391 -0.1057668 0 -0.8982478 -0.4394894 0 0.4282667 0.9036524 0 0.8500268 -0.5267397 0 -0.1181554 0.9929952 0 -0.4282418 -0.9036643 0 0.7115036 -0.7026826 0 0.7779294 0.6283519 0 0.1057621 0.9943915 0 0.537289 -0.8433983 0 -0.1736471 0.984808 0 -0.7115036 0.7026826 1 -1.64373e-7 0 -1.12859e-5 0.6892319 -0.7245408 -0.08715772 -0.1729847 0.9810606 0.9723693 -0.04053622 0.2299018 0.6494559 -0.1320508 0.7488456 -0.2588228 -0.1677335 0.9512498 0.2334407 -0.1688537 0.957598 0.8526381 -0.0907343 0.5145634 0.8526469 -0.09070247 0.5145545 0.7603959 -0.112773 0.6395939 1.65594e-7 -0.173644 0.9848085 -1 -2.21349e-7 0 -1 -7.23549e-6 0 0.07846266 -0.1731137 0.9817715 -0.9765499 -0.0373739 0.2120226 -0.8191522 -0.0996055 0.5648615 0.9969174 -0.01362049 0.07726866 -0.5735924 -0.1422415 0.8066964 0.3826755 -0.1604321 0.9098467 -0.9194182 -0.068295 0.3873062 0.5225001 -0.1480528 0.8396869 -0.7071055 -0.1227901 0.6963651 1 1.49648e-5 0 1 -2.3622e-6 0 1 -2.5197e-5 0 1 2.08689e-5 0 1 -1.97843e-5 0 1 5.31239e-7 0 -0.4226064 -0.1573795 0.8925445 0.9238747 -0.06644731 0.3768824 0.9238817 -0.06645625 0.3768639 -0.9063067 -0.07339233 0.4161992 0 0.1768683 -0.9842346 0 0.1770638 -0.9841994 0 2.03755e-5 -1 0 0.1769442 -0.984221 2.12793e-5 1.31082e-5 -1 2.03899e-5 6.11223e-5 -1 3.94559e-6 2.03732e-5 -1 0 0.1769442 -0.9842209 1.35891e-5 6.13162e-5 -1 -2.39783e-5 7.30394e-6 -1 0 2.03755e-5 -1 0 2.03732e-5 -1 - - - - - - - - - - 0.8144246 0.9832577 0.7333412 0.9670422 0.7336204 0.9665908 0.981158 0.9082872 0.9632149 0.8570863 0.9635183 0.8570276 0.9142314 0.9817867 0.981158 0.9082872 0.9817329 0.9084089 0.6766925 0.8927361 0.7336204 0.9665908 0.7333412 0.9670422 0.6615117 0.8536715 0.6534397 0.8344755 0.6539292 0.8347179 0.8208814 0.8856445 0.8210781 0.8862837 0.7698203 0.9022399 0.1601298 0.3173595 0.1606493 0.3168823 0.1920673 0.338983 0.9086689 0.8734209 0.9135509 0.8888647 0.9131584 0.8889433 0.9276995 0.949799 0.9282227 0.9498755 0.9140335 0.9813115 0.6844192 0.2529656 0.6512128 0.2903282 0.6509062 0.289507 0.5004894 0.330456 0.5282862 0.3151882 0.5286183 0.3158802 0.8206426 0.9023172 0.8204795 0.9073001 0.7951825 0.9067766 0.2692312 0.2232967 0.3319807 0.2621161 0.3318286 0.2636325 0.7336204 0.9665908 0.7219669 0.937798 0.722405 0.9378422 0.7473767 0.8839331 0.7470774 0.8838632 0.7529727 0.8688679 0.04490453 0.2911104 0.04453307 0.2918578 0.008181571 0.2617684 0.8631129 0.9094895 0.8206426 0.9023172 0.8843328 0.9057126 0.8804847 0.9713259 0.8270514 0.9733139 0.8732222 0.9710156 0.9632149 0.8570863 0.9086689 0.8734209 0.8856092 0.8332486 0.6281018 0.3944575 0.4365528 0.3769267 0.5004894 0.330456 0.8489315 0.890781 0.8496351 0.890707 0.8843328 0.9057126 0.401956 0.2557986 0.4004096 0.2550646 0.4433817 0.2251373 0.6880185 0.8704311 0.7913666 0.7970162 0.7451852 0.8560523 0.09564483 0.404841 0.2867114 0.4380289 0.09434968 0.5149184 0.6615117 0.8536715 0.6539314 0.834717 0.658658 0.8068557 0.0545926 0.4552482 0.09564483 0.404841 0.09434968 0.5149184 0.7529727 0.8688679 0.7913666 0.7970162 0.8017322 0.8268812 0.9117215 0.8896787 0.9122476 0.8897275 0.9119445 0.8899517 0.8972221 0.9094889 0.8975955 0.9098473 0.8972534 0.909891 0.9312095 0.9491473 0.9313463 0.9484902 0.931633 0.9488391 0.9151513 0.8889935 0.9153966 0.8894621 0.9150462 0.8893282 0.9131584 0.8889433 0.913599 0.8892037 0.9132443 0.8892753 0.8981258 0.9069538 0.9111493 0.8907686 0.8983586 0.9071247 0.8973832 0.9082965 0.8978326 0.9080528 0.8977127 0.9083956 0.931633 0.9488391 0.9316985 0.9481518 0.9320235 0.9484888 0.9147548 0.8888944 0.9150462 0.8893282 0.9146876 0.8892351 0.9159118 0.8893178 0.9554474 0.9158514 0.9157375 0.8896365 0.9302806 0.9496127 0.9305601 0.9490118 0.9307575 0.949406 0.8974411 0.9106757 0.8979064 0.9109035 0.8975957 0.9110495 0.9111468 0.8902614 0.9116627 0.890206 0.9114008 0.8904836 0.9307575 0.949406 0.9309669 0.9487757 0.9312095 0.9491473 0.9271675 0.9496498 0.9277938 0.949346 0.9276995 0.949799 0.9282227 0.9498755 0.9287428 0.9494475 0.9287478 0.9498964 0.8972327 0.9090862 0.8975675 0.9094813 0.8972221 0.9094889 0.9287478 0.9498964 0.9292151 0.9494172 0.9292699 0.9498595 0.9253795 0.9484837 0.9260324 0.9485024 0.9257536 0.9488486 0.9124076 0.8892278 0.9129001 0.8893867 0.912571 0.8895366 0.9261868 0.9491693 0.9268652 0.9490203 0.9266614 0.949438 0.8975198 0.9079233 0.8979849 0.9077253 0.8978326 0.9080528 0.9266614 0.949438 0.9273212 0.9492099 0.9271675 0.9496498 0.9556968 0.9155468 0.9557726 0.9161452 0.9554474 0.9158514 0.9139505 0.88883 0.9143245 0.8891834 0.9139603 0.8891729 0.9563893 0.9162108 0.9563217 0.9168324 0.9560659 0.9164719 0.9569172 0.9170401 0.956704 0.9176362 0.9565356 0.9172223 0.9297829 0.9497646 0.9301292 0.9491981 0.9302806 0.9496127 0.9155386 0.8891358 0.9157375 0.8896365 0.9153966 0.8894621 0.9573361 0.9189664 0.9568824 0.9194064 0.9569141 0.9189592 0.8978965 0.907245 0.8983586 0.9071247 0.8981632 0.9074153 0.9572108 0.9199461 0.9568824 0.9194064 0.9572969 0.9194599 0.9563274 0.9217127 0.9562572 0.9210773 0.9566197 0.921313 0.9292699 0.9498595 0.9296791 0.9493337 0.9297829 0.9497646 0.9566771 0.9166083 0.9565356 0.9172223 0.9563217 0.9168324 0.9570671 0.9204223 0.9567998 0.919846 0.9572108 0.9199461 0.9566197 0.921313 0.9564858 0.9206869 0.9568688 0.9208801 0.9257536 0.9488486 0.9264337 0.948782 0.9261868 0.9491693 0.8973266 0.9102879 0.897766 0.9105627 0.8974411 0.9106757 0.9573168 0.9184695 0.9569141 0.9189592 0.9568946 0.9185111 0.910916 0.8905769 0.9114008 0.8904836 0.9111493 0.8907686 0.9320235 0.9484888 0.9559856 0.9214432 0.9563274 0.9217127 0.8977885 0.9114053 0.8982937 0.9115315 0.8980163 0.9117391 0.9560593 0.9158544 0.9560659 0.9164719 0.9557726 0.9161452 0.8972839 0.9086859 0.8975785 0.9091149 0.8972327 0.9090862 0.9120535 0.889434 0.912571 0.8895366 0.9122476 0.8897275 0.9114175 0.8899571 0.9119445 0.8899517 0.9116627 0.890206 0.9568688 0.9208801 0.956667 0.9202747 0.9570671 0.9204223 0.8972534 0.909891 0.897662 0.9102092 0.8973266 0.9102879 0.8976923 0.9075707 0.8981632 0.9074153 0.8979849 0.9077253 0.9127764 0.8890647 0.9132443 0.8892753 0.9129001 0.8893867 0.8980163 0.9117391 0.898546 0.9118154 0.8982692 0.912044 0.9571056 0.9174989 0.9568243 0.918068 0.956704 0.9176362 0.9135509 0.8888647 0.9139603 0.8891729 0.913599 0.8892037 0.8972839 0.9086859 0.8977127 0.9083956 0.8976295 0.9087516 0.8975957 0.9110495 0.8980824 0.9112277 0.8977885 0.9114053 0.914353 0.8888398 0.9146876 0.8892351 0.9143245 0.8891834 0.9253795 0.9484837 0.898546 0.9118154 0.9256636 0.9481966 0.9276995 0.949799 0.9282675 0.949424 0.9282227 0.9498755 0.9572395 0.9179778 0.9568946 0.9185111 0.9568243 0.918068 0.7481969 0.8843272 0.7482625 0.8847054 0.7480477 0.8845388 0.758993 0.9039866 0.7586627 0.9042307 0.7587229 0.9039461 0.7203593 0.9371479 0.7202717 0.9365931 0.7205784 0.9368418 0.7455473 0.884004 0.7459166 0.8841753 0.7456463 0.8842683 0.7470774 0.8838632 0.7473023 0.8841856 0.7470307 0.8841232 0.7489702 0.8851911 0.758258 0.9020243 0.7487696 0.8853156 0.758897 0.9027303 0.7587076 0.903087 0.7586387 0.902809 0.720015 0.9368742 0.719996 0.9363044 0.7202717 0.9365931 0.7458473 0.8839116 0.7461926 0.8841155 0.7459166 0.8841753 0.7453793 0.8843972 0.7006751 0.9025083 0.7452577 0.8841221 0.7211256 0.9375656 0.7209115 0.937051 0.7212665 0.9372192 0.7586935 0.90491 0.7582864 0.9050368 0.7584443 0.904779 0.7486414 0.8847237 0.7486249 0.8850954 0.7484558 0.8848919 0.7207308 0.9373791 0.7205784 0.9368418 0.7209115 0.937051 0.7237785 0.9376698 0.7232354 0.9373896 0.723654 0.9372794 0.722851 0.9378385 0.7224197 0.9374612 0.7228199 0.9374493 0.7590218 0.9036687 0.7587229 0.9039461 0.7587502 0.9036585 0.722405 0.9378422 0.7220249 0.9374258 0.7224197 0.9374612 0.7253959 0.9366716 0.7248038 0.9366722 0.725137 0.9363867 0.7476655 0.8840347 0.747814 0.8843951 0.7475644 0.8842768 0.7246567 0.9372669 0.7240597 0.9371212 0.7244449 0.9369177 0.7587873 0.9024342 0.7586387 0.902809 0.7585394 0.9025397 0.7242303 0.9374949 0.723654 0.9372794 0.7240597 0.9371212 0.7003173 0.9027553 0.700861 0.9028145 0.7005494 0.9030467 0.7464622 0.8838215 0.746753 0.8840901 0.7464725 0.8840874 0.6996952 0.9033807 0.7002576 0.9033159 0.6999941 0.9036175 0.6992293 0.904137 0.6997647 0.9039472 0.6995738 0.9043004 0.721539 0.9377057 0.7212665 0.9372192 0.7216391 0.9373446 0.7452577 0.8841221 0.7456463 0.8842683 0.7453793 0.8843972 0.6988621 0.905857 0.6992563 0.905453 0.6992403 0.9058512 0.7584823 0.9018914 0.7584115 0.9022797 0.758258 0.9020243 0.6988952 0.9062972 0.6992403 0.9058512 0.6992703 0.9062479 0.6995148 0.9079512 0.699638 0.9073818 0.6998571 0.9077303 0.7219669 0.937798 0.7216391 0.9373446 0.7220249 0.9374258 0.6994407 0.9037455 0.6999941 0.9036175 0.6997647 0.9039472 0.6989781 0.906731 0.6992703 0.9062479 0.6993463 0.9066382 0.6992902 0.9075626 0.6994686 0.9070174 0.699638 0.9073818 0.7250492 0.9369898 0.7244449 0.9369177 0.7248038 0.9366722 0.7588284 0.9046105 0.7584443 0.904779 0.7585698 0.9045093 0.6988794 0.9054152 0.6993178 0.9050583 0.6992563 0.905453 0.7488215 0.884952 0.7487696 0.8853156 0.7486249 0.8850954 0.7197008 0.9365606 0.6998571 0.9077303 0.719996 0.9363044 0.7583235 0.9054699 0.7578778 0.905509 0.7580966 0.9052792 0.699989 0.9030486 0.7005494 0.9030467 0.7002576 0.9033159 0.7590152 0.903351 0.7587502 0.9036585 0.758745 0.9033712 0.7479401 0.8841668 0.7480477 0.8845388 0.747814 0.8843951 0.7484319 0.8845139 0.7484558 0.8848919 0.7482625 0.8847054 0.6991101 0.9071541 0.6993463 0.9066382 0.6994686 0.9070174 0.7589284 0.9043017 0.7585698 0.9045093 0.7586627 0.9042307 0.7586469 0.9021527 0.7585394 0.9025397 0.7584115 0.9022797 0.7473767 0.8839331 0.7475644 0.8842768 0.7473023 0.8841856 0.7580934 0.9057248 0.7576303 0.9057236 0.7578778 0.905509 0.699064 0.9045496 0.6995738 0.9043004 0.6994242 0.9046724 0.7467713 0.8838258 0.7470307 0.8841232 0.746753 0.8840901 0.7589733 0.9030371 0.758745 0.9033712 0.7587076 0.903087 0.7585245 0.9051975 0.7580966 0.9052792 0.7582864 0.9050368 0.7461532 0.8838502 0.7464725 0.8840874 0.7461926 0.8841155 0.7578453 0.9059553 0.725137 0.9363867 0.7576303 0.9057236 0.7233069 0.9377867 0.7228199 0.9374493 0.7232354 0.9373896 0.6989469 0.9049776 0.6994242 0.9046724 0.6993178 0.9050583 0.7838017 0.9661539 0.7951825 0.9067766 0.7955474 0.9071758 0.8631129 0.9094895 0.8735573 0.9705377 0.8627287 0.9098702 0.6610493 0.8535416 0.6769561 0.8922903 0.6766925 0.8927361 0.820461 0.9078074 0.7955474 0.9071758 0.8204795 0.9073001 0.8489009 0.8903851 0.8482088 0.890825 0.8482071 0.8904128 0.8210781 0.8862837 0.8212972 0.8855296 0.8214814 0.8861495 0.822586 0.8885926 0.8223941 0.8878224 0.8228539 0.8882614 0.8495655 0.890317 0.8489315 0.890781 0.8489009 0.8903851 0.8244565 0.8895012 0.8239458 0.8888988 0.8245538 0.889087 0.8213143 0.8869313 0.8217098 0.8867626 0.8217603 0.8868799 0.8220782 0.8881083 0.8220065 0.8873179 0.8223941 0.8878224 0.8482088 0.890825 0.8251839 0.8891966 0.8482071 0.8904128 0.8856092 0.8332486 0.8528541 0.8873486 0.8853808 0.832731 0.825132 0.88961 0.8245538 0.889087 0.8251839 0.8891966 0.8528541 0.8873486 0.8528711 0.8881674 0.85253 0.8879653 0.851759 0.8890734 0.8515428 0.8898204 0.851299 0.8895217 0.8208814 0.8856445 0.821152 0.8848704 0.8212972 0.8855296 0.8507741 0.8898853 0.8503234 0.8905199 0.8501926 0.8901529 0.8237912 0.8892955 0.823375 0.8886228 0.8239458 0.8888988 0.85253 0.8879653 0.8524698 0.8887773 0.8521551 0.8885557 0.8231619 0.8889913 0.8228539 0.8882614 0.823375 0.8886228 0.851299 0.8895217 0.8509646 0.8902213 0.8507741 0.8898853 0.6581624 0.8063405 0.79183 0.7963298 0.7913666 0.7970162 0.8501926 0.8901529 0.8496351 0.890707 0.8495655 0.890317 0.8212924 0.8868725 0.8214814 0.8861495 0.8217098 0.8867626 0.8521551 0.8885557 0.8520465 0.8893316 0.851759 0.8890734 0.1713902 0.03509753 0.21771 0.0150693 0.2679117 0.03438824 0.7991394 0.9672784 0.8652717 0.9709582 0.8613291 0.9703543 0.3334052 0.2241951 0.2690851 0.2092068 0.3335518 0.2099398 0.4437994 0.03414064 0.5180054 0.01453781 0.5179812 0.03422337 0.5172361 0.2255963 0.4433817 0.2251373 0.4432952 0.2108101 0.2695215 0.01469802 0.4437994 0.03414064 0.2679117 0.03438824 0.2679117 0.03438824 0.4437604 0.03551566 0.2679027 0.03576338 0.1713902 0.03509753 0.2679117 0.03438824 0.2679027 0.03576338 0.9140335 0.9813115 0.9142314 0.9817867 0.8827549 0.9822506 0.9140335 0.9813115 0.8827549 0.9822506 0.8804847 0.9713259 0.8827549 0.9822506 0.8400148 0.9828805 0.8804847 0.9713259 0.8804847 0.9713259 0.9090774 0.9699652 0.9140335 0.9813115 0.7336204 0.9665908 0.7390483 0.9570456 0.8144246 0.9832577 0.7390483 0.9570456 0.8153287 0.9744266 0.8144246 0.9832577 0.8153287 0.9744266 0.8804847 0.9713259 0.8400148 0.9828805 0.8400148 0.9828805 0.8144246 0.9832577 0.8153287 0.9744266 0.9635183 0.8570276 0.963638 0.8568787 0.981158 0.9082872 0.963638 0.8568787 0.9817329 0.9084089 0.981158 0.9082872 0.9142314 0.9817867 0.9140335 0.9813115 0.981158 0.9082872 0.6766925 0.8927361 0.6769561 0.8922903 0.7336204 0.9665908 0.6539292 0.8347179 0.6539314 0.834717 0.6615117 0.8536715 0.6615117 0.8536715 0.6610493 0.8535416 0.6534397 0.8344755 0.8210781 0.8862837 0.8212924 0.8868725 0.8206426 0.9023172 0.8206426 0.9023172 0.7698203 0.9022399 0.8210781 0.8862837 0.7698203 0.9022399 0.7529727 0.8688679 0.8207169 0.884998 0.8208814 0.8856445 0.7698203 0.9022399 0.8207169 0.884998 0.7529727 0.8688679 0.8017322 0.8268812 0.8207169 0.884998 0.1512694 0.2556579 0.1506835 0.2551221 0.174475 0.2267131 0.174475 0.2267131 0.1920673 0.338983 0.1623916 0.3116757 0.1920673 0.338983 0.1895545 0.3639723 0.1569454 0.3187288 0.174475 0.2267131 0.1526194 0.2576101 0.1522436 0.2569097 0.1895545 0.3639723 0.09564483 0.404841 0.1569454 0.3187288 0.09564483 0.404841 0.07647401 0.3841392 0.08166462 0.3502521 0.08023703 0.3508628 0.07647401 0.3841392 0.07948112 0.3510431 0.07647401 0.3841392 0.07793235 0.3511424 0.07870972 0.3511366 0.07647401 0.3841392 0.07870972 0.3511366 0.07948112 0.3510431 0.1517916 0.2562562 0.1512694 0.2556579 0.174475 0.2267131 0.1522436 0.2569097 0.1517916 0.2562562 0.174475 0.2267131 0.07647401 0.3841392 0.08023703 0.3508628 0.0809679 0.3505981 0.07647401 0.3841392 0.0809679 0.3505981 0.08166462 0.3502521 0.1526194 0.2576101 0.174475 0.2267131 0.1529145 0.2583488 0.1529145 0.2583488 0.174475 0.2267131 0.1623916 0.3116757 0.09564483 0.404841 0.08166462 0.3502521 0.1569454 0.3187288 0.1623916 0.3116757 0.1920673 0.338983 0.1624397 0.312387 0.1624397 0.312387 0.1920673 0.338983 0.1624084 0.3130981 0.1569454 0.3187288 0.1576337 0.3186031 0.1920673 0.338983 0.1624084 0.3130981 0.1920673 0.338983 0.1622982 0.3138003 0.1622982 0.3138003 0.1920673 0.338983 0.1621105 0.3144848 0.1576337 0.3186031 0.1583048 0.3184005 0.1920673 0.338983 0.1583048 0.3184005 0.15895 0.3181233 0.1920673 0.338983 0.1621105 0.3144848 0.1920673 0.338983 0.1618478 0.3151431 0.1618478 0.3151431 0.1920673 0.338983 0.1615138 0.3157674 0.15895 0.3181233 0.1595609 0.3177748 0.1920673 0.338983 0.1595609 0.3177748 0.1601298 0.3173595 0.1920673 0.338983 0.1615138 0.3157674 0.1920673 0.338983 0.1611126 0.3163494 0.1611126 0.3163494 0.1920673 0.338983 0.1606493 0.3168823 0.8973832 0.9082965 0.8972839 0.9086859 0.8843328 0.9057126 0.981158 0.9082872 0.9571056 0.9174989 0.9569172 0.9170401 0.981158 0.9082872 0.9569172 0.9170401 0.9566771 0.9166083 0.8975198 0.9079233 0.8973832 0.9082965 0.8843328 0.9057126 0.8976923 0.9075707 0.8975198 0.9079233 0.8843328 0.9057126 0.981158 0.9082872 0.9566771 0.9166083 0.9563893 0.9162108 0.981158 0.9082872 0.9563893 0.9162108 0.9560593 0.9158544 0.8976923 0.9075707 0.8843328 0.9057126 0.8978965 0.907245 0.8843328 0.9057126 0.9086689 0.8734209 0.910916 0.8905769 0.8978965 0.907245 0.8843328 0.9057126 0.8981258 0.9069538 0.8981258 0.9069538 0.8843328 0.9057126 0.910916 0.8905769 0.9086689 0.8734209 0.981158 0.9082872 0.9159118 0.8893178 0.981158 0.9082872 0.9560593 0.9158544 0.9556968 0.9155468 0.981158 0.9082872 0.9556968 0.9155468 0.9159118 0.8893178 0.9086689 0.8734209 0.9159118 0.8893178 0.9155386 0.8891358 0.9111468 0.8902614 0.910916 0.8905769 0.9086689 0.8734209 0.9114175 0.8899571 0.9111468 0.8902614 0.9086689 0.8734209 0.9086689 0.8734209 0.9155386 0.8891358 0.9151513 0.8889935 0.9086689 0.8734209 0.9151513 0.8889935 0.9147548 0.8888944 0.9117215 0.8896787 0.9114175 0.8899571 0.9086689 0.8734209 0.9120535 0.889434 0.9117215 0.8896787 0.9086689 0.8734209 0.9086689 0.8734209 0.9147548 0.8888944 0.914353 0.8888398 0.9086689 0.8734209 0.914353 0.8888398 0.9139505 0.88883 0.9124076 0.8892278 0.9120535 0.889434 0.9086689 0.8734209 0.9127764 0.8890647 0.9124076 0.8892278 0.9086689 0.8734209 0.9086689 0.8734209 0.9139505 0.88883 0.9135509 0.8888647 0.9131584 0.8889433 0.9127764 0.8890647 0.9086689 0.8734209 0.9572395 0.9179778 0.9571056 0.9174989 0.981158 0.9082872 0.981158 0.9082872 0.9140335 0.9813115 0.9320235 0.9484888 0.9140335 0.9813115 0.9090774 0.9699652 0.9276995 0.949799 0.981158 0.9082872 0.9320235 0.9484888 0.9563274 0.9217127 0.8843328 0.9057126 0.8972839 0.9086859 0.8972327 0.9090862 0.8843328 0.9057126 0.8972327 0.9090862 0.8972221 0.9094889 0.9573168 0.9184695 0.9572395 0.9179778 0.981158 0.9082872 0.9573361 0.9189664 0.9573168 0.9184695 0.981158 0.9082872 0.8843328 0.9057126 0.8972221 0.9094889 0.8972534 0.909891 0.8843328 0.9057126 0.8972534 0.909891 0.8973266 0.9102879 0.9572969 0.9194599 0.9573361 0.9189664 0.981158 0.9082872 0.9572108 0.9199461 0.9572969 0.9194599 0.981158 0.9082872 0.8843328 0.9057126 0.8973266 0.9102879 0.8974411 0.9106757 0.8843328 0.9057126 0.8974411 0.9106757 0.8975957 0.9110495 0.9570671 0.9204223 0.9572108 0.9199461 0.981158 0.9082872 0.9568688 0.9208801 0.9570671 0.9204223 0.981158 0.9082872 0.9090774 0.9699652 0.8843328 0.9057126 0.8982692 0.912044 0.8843328 0.9057126 0.8975957 0.9110495 0.8977885 0.9114053 0.8843328 0.9057126 0.8977885 0.9114053 0.8980163 0.9117391 0.9566197 0.921313 0.9568688 0.9208801 0.981158 0.9082872 0.9563274 0.9217127 0.9566197 0.921313 0.981158 0.9082872 0.8843328 0.9057126 0.8980163 0.9117391 0.8982692 0.912044 0.9320235 0.9484888 0.9140335 0.9813115 0.931633 0.9488391 0.931633 0.9488391 0.9140335 0.9813115 0.9312095 0.9491473 0.9090774 0.9699652 0.8982692 0.912044 0.9253795 0.9484837 0.9090774 0.9699652 0.9253795 0.9484837 0.9257536 0.9488486 0.9312095 0.9491473 0.9140335 0.9813115 0.9307575 0.949406 0.9307575 0.949406 0.9140335 0.9813115 0.9302806 0.9496127 0.9090774 0.9699652 0.9257536 0.9488486 0.9261868 0.9491693 0.9090774 0.9699652 0.9261868 0.9491693 0.9266614 0.949438 0.9302806 0.9496127 0.9140335 0.9813115 0.9297829 0.9497646 0.9297829 0.9497646 0.9140335 0.9813115 0.9292699 0.9498595 0.9090774 0.9699652 0.9266614 0.949438 0.9271675 0.9496498 0.9090774 0.9699652 0.9271675 0.9496498 0.9276995 0.949799 0.9292699 0.9498595 0.9140335 0.9813115 0.9287478 0.9498964 0.9287478 0.9498964 0.9140335 0.9813115 0.9282227 0.9498755 0.5432537 0.2547456 0.5425713 0.2552505 0.5172361 0.2255963 0.5172361 0.2255963 0.6695529 0.2470815 0.5497625 0.2538697 0.6695529 0.2470815 0.6844192 0.2529656 0.6494675 0.2873191 0.5172361 0.2255963 0.5489441 0.2536548 0.5481054 0.2535318 0.6281018 0.3944575 0.6223689 0.3578878 0.6232107 0.3576832 0.6281018 0.3944575 0.6232107 0.3576832 0.6240243 0.3573852 0.5439884 0.2543201 0.5432537 0.2547456 0.5172361 0.2255963 0.544766 0.2539795 0.5439884 0.2543201 0.5172361 0.2255963 0.6281018 0.3944575 0.6240243 0.3573852 0.6247997 0.3569977 0.6281018 0.3944575 0.6247997 0.3569977 0.6255269 0.3565254 0.545577 0.2537278 0.544766 0.2539795 0.5172361 0.2255963 0.546411 0.2535682 0.545577 0.2537278 0.5172361 0.2255963 0.6281018 0.3944575 0.6255269 0.3565254 0.6261971 0.3559738 0.6281018 0.3944575 0.6261971 0.3559738 0.6268016 0.3553501 0.5472574 0.2535027 0.546411 0.2535682 0.5172361 0.2255963 0.5481054 0.2535318 0.5472574 0.2535027 0.5172361 0.2255963 0.6281018 0.3944575 0.6268016 0.3553501 0.6273328 0.3546617 0.6281018 0.3944575 0.6273328 0.3546617 0.6277841 0.3539167 0.5489441 0.2536548 0.5172361 0.2255963 0.5497625 0.2538697 0.5497625 0.2538697 0.6695529 0.2470815 0.6465912 0.2853708 0.6844192 0.2529656 0.6281018 0.3944575 0.6510297 0.2954903 0.6281018 0.3944575 0.6277841 0.3539167 0.6281498 0.3531237 0.6281018 0.3944575 0.6281498 0.3531237 0.6510297 0.2954903 0.6465912 0.2853708 0.6695529 0.2470815 0.6473874 0.2857324 0.6473874 0.2857324 0.6695529 0.2470815 0.6481383 0.2861815 0.6844192 0.2529656 0.6510297 0.2954903 0.6513022 0.2946566 0.6481383 0.2861815 0.6695529 0.2470815 0.6488346 0.2867127 0.6488346 0.2867127 0.6695529 0.2470815 0.6494675 0.2873191 0.6844192 0.2529656 0.6513022 0.2946566 0.6514796 0.2937976 0.6844192 0.2529656 0.6514796 0.2937976 0.6515598 0.2929244 0.6844192 0.2529656 0.6515598 0.2929244 0.6515417 0.2920477 0.6844192 0.2529656 0.6515417 0.2920477 0.6514255 0.2911787 0.650028 0.2879929 0.6494675 0.2873191 0.6844192 0.2529656 0.6505096 0.2887253 0.650028 0.2879929 0.6844192 0.2529656 0.6844192 0.2529656 0.6514255 0.2911787 0.6512128 0.2903282 0.6509062 0.289507 0.6505096 0.2887253 0.6844192 0.2529656 0.6215098 0.3579965 0.6223689 0.3578878 0.6281018 0.3944575 0.5172361 0.2255963 0.5425713 0.2552505 0.5419496 0.2558287 0.5172361 0.2255963 0.5419496 0.2558287 0.5413967 0.2564728 0.6206439 0.3580081 0.6215098 0.3579965 0.6281018 0.3944575 0.619782 0.3579223 0.6206439 0.3580081 0.6281018 0.3944575 0.5004894 0.330456 0.5172361 0.2255963 0.5279994 0.3106058 0.5172361 0.2255963 0.5413967 0.2564728 0.5409196 0.257175 0.5172361 0.2255963 0.5409196 0.257175 0.540524 0.2579264 0.619782 0.3579223 0.6281018 0.3944575 0.6189353 0.3577402 0.6281018 0.3944575 0.5004894 0.330456 0.5327929 0.3192167 0.6189353 0.3577402 0.6281018 0.3944575 0.6181141 0.3574641 0.6181141 0.3574641 0.6281018 0.3944575 0.5327929 0.3192167 0.5172361 0.2255963 0.540524 0.2579264 0.5402153 0.2587176 0.5172361 0.2255963 0.5402153 0.2587176 0.5279994 0.3106058 0.5004894 0.330456 0.5279994 0.3106058 0.527838 0.3113796 0.5320363 0.3189417 0.5327929 0.3192167 0.5004894 0.330456 0.5313227 0.3185911 0.5320363 0.3189417 0.5004894 0.330456 0.5004894 0.330456 0.527838 0.3113796 0.5277608 0.3121607 0.5004894 0.330456 0.5277608 0.3121607 0.527768 0.3129405 0.530659 0.3181692 0.5313227 0.3185911 0.5004894 0.330456 0.5300511 0.3176817 0.530659 0.3181692 0.5004894 0.330456 0.5004894 0.330456 0.527768 0.3129405 0.527859 0.3137105 0.5004894 0.330456 0.527859 0.3137105 0.5280326 0.3144624 0.5295051 0.3171336 0.5300511 0.3176817 0.5004894 0.330456 0.529026 0.3165311 0.5295051 0.3171336 0.5004894 0.330456 0.5004894 0.330456 0.5280326 0.3144624 0.5282862 0.3151882 0.5286183 0.3158802 0.529026 0.3165311 0.5004894 0.330456 0.7951825 0.9067766 0.8153742 0.9738952 0.7390483 0.9570456 0.8153742 0.9738952 0.8153287 0.9744266 0.7390483 0.9570456 0.7390483 0.9570456 0.7698203 0.9022399 0.7951825 0.9067766 0.7698203 0.9022399 0.8206426 0.9023172 0.7951825 0.9067766 0.1920673 0.338983 0.174475 0.2267131 0.2692312 0.2232967 0.2692312 0.2232967 0.3334052 0.2241951 0.3329814 0.2592467 0.3334052 0.2241951 0.3331465 0.2589855 0.3329814 0.2592467 0.1895545 0.3639723 0.1920673 0.338983 0.3123614 0.3904872 0.1920673 0.338983 0.2692312 0.2232967 0.3318286 0.2636325 0.3323682 0.260642 0.2692312 0.2232967 0.3329814 0.2592467 0.3123614 0.3904872 0.2867114 0.4380289 0.1895545 0.3639723 0.3318286 0.2636325 0.3123614 0.3904872 0.1920673 0.338983 0.2692312 0.2232967 0.3323682 0.260642 0.3319807 0.2621161 0.7590218 0.9036687 0.7590152 0.903351 0.7698203 0.9022399 0.7698203 0.9022399 0.7390483 0.9570456 0.7578453 0.9059553 0.7390483 0.9570456 0.7336204 0.9665908 0.7233069 0.9377867 0.7698203 0.9022399 0.7580934 0.9057248 0.7583235 0.9054699 0.6769561 0.8922903 0.6992293 0.904137 0.699064 0.9045496 0.6769561 0.8922903 0.699064 0.9045496 0.6989469 0.9049776 0.758993 0.9039866 0.7590218 0.9036687 0.7698203 0.9022399 0.7589284 0.9043017 0.758993 0.9039866 0.7698203 0.9022399 0.6769561 0.8922903 0.6989469 0.9049776 0.6988794 0.9054152 0.6769561 0.8922903 0.6988794 0.9054152 0.6988621 0.905857 0.7588284 0.9046105 0.7589284 0.9043017 0.7698203 0.9022399 0.7586935 0.90491 0.7588284 0.9046105 0.7698203 0.9022399 0.6769561 0.8922903 0.6988621 0.905857 0.6988952 0.9062972 0.6769561 0.8922903 0.6988952 0.9062972 0.6989781 0.906731 0.7585245 0.9051975 0.7586935 0.90491 0.7698203 0.9022399 0.7583235 0.9054699 0.7585245 0.9051975 0.7698203 0.9022399 0.6769561 0.8922903 0.6989781 0.906731 0.6991101 0.9071541 0.6769561 0.8922903 0.6991101 0.9071541 0.6992902 0.9075626 0.7580934 0.9057248 0.7698203 0.9022399 0.7578453 0.9059553 0.7578453 0.9059553 0.7390483 0.9570456 0.7253959 0.9366716 0.7336204 0.9665908 0.6769561 0.8922903 0.7197008 0.9365606 0.6769561 0.8922903 0.6992902 0.9075626 0.6995148 0.9079512 0.6769561 0.8922903 0.6995148 0.9079512 0.7197008 0.9365606 0.7253959 0.9366716 0.7390483 0.9570456 0.7250492 0.9369898 0.7250492 0.9369898 0.7390483 0.9570456 0.7246567 0.9372669 0.7336204 0.9665908 0.7197008 0.9365606 0.720015 0.9368742 0.7246567 0.9372669 0.7390483 0.9570456 0.7242303 0.9374949 0.7242303 0.9374949 0.7390483 0.9570456 0.7237785 0.9376698 0.7336204 0.9665908 0.720015 0.9368742 0.7203593 0.9371479 0.7336204 0.9665908 0.7203593 0.9371479 0.7207308 0.9373791 0.7237785 0.9376698 0.7390483 0.9570456 0.7233069 0.9377867 0.7336204 0.9665908 0.7207308 0.9373791 0.7211256 0.9375656 0.7336204 0.9665908 0.7211256 0.9375656 0.721539 0.9377057 0.722851 0.9378385 0.7233069 0.9377867 0.7336204 0.9665908 0.7336204 0.9665908 0.721539 0.9377057 0.7219669 0.937798 0.722405 0.9378422 0.722851 0.9378385 0.7336204 0.9665908 0.6994407 0.9037455 0.6992293 0.904137 0.6769561 0.8922903 0.6769561 0.8922903 0.6880185 0.8704311 0.7006751 0.9025083 0.6880185 0.8704311 0.7451852 0.8560523 0.7452577 0.8841221 0.6769561 0.8922903 0.6996952 0.9033807 0.6994407 0.9037455 0.7451852 0.8560523 0.7529727 0.8688679 0.7452577 0.8841221 0.7529727 0.8688679 0.7698203 0.9022399 0.7489702 0.8851911 0.7584823 0.9018914 0.7698203 0.9022399 0.7586469 0.9021527 0.7698203 0.9022399 0.7590152 0.903351 0.7589733 0.9030371 0.7698203 0.9022399 0.7589733 0.9030371 0.758897 0.9027303 0.6996952 0.9033807 0.6769561 0.8922903 0.699989 0.9030486 0.699989 0.9030486 0.6769561 0.8922903 0.7003173 0.9027553 0.7698203 0.9022399 0.758897 0.9027303 0.7587873 0.9024342 0.7698203 0.9022399 0.7587873 0.9024342 0.7586469 0.9021527 0.7003173 0.9027553 0.6769561 0.8922903 0.7006751 0.9025083 0.7006751 0.9025083 0.6880185 0.8704311 0.7452577 0.8841221 0.7698203 0.9022399 0.7584823 0.9018914 0.7489702 0.8851911 0.7529727 0.8688679 0.7489702 0.8851911 0.7488215 0.884952 0.7529727 0.8688679 0.7488215 0.884952 0.7486414 0.8847237 0.7455473 0.884004 0.7452577 0.8841221 0.7529727 0.8688679 0.7458473 0.8839116 0.7455473 0.884004 0.7529727 0.8688679 0.7529727 0.8688679 0.7486414 0.8847237 0.7484319 0.8845139 0.7529727 0.8688679 0.7484319 0.8845139 0.7481969 0.8843272 0.7461532 0.8838502 0.7458473 0.8839116 0.7529727 0.8688679 0.7464622 0.8838215 0.7461532 0.8838502 0.7529727 0.8688679 0.7529727 0.8688679 0.7481969 0.8843272 0.7479401 0.8841668 0.7529727 0.8688679 0.7479401 0.8841668 0.7476655 0.8840347 0.7467713 0.8838258 0.7464622 0.8838215 0.7529727 0.8688679 0.7470774 0.8838632 0.7467713 0.8838258 0.7529727 0.8688679 0.7529727 0.8688679 0.7476655 0.8840347 0.7473767 0.8839331 0.07715892 0.3510601 0.07793235 0.3511424 0.07647401 0.3841392 0.07647401 0.3841392 0.008181571 0.2617684 0.04481691 0.298317 0.008181571 0.2617684 0.0219565 0.2540714 0.04535734 0.2904094 0.04446303 0.2975589 0.008181571 0.2617684 0.0441966 0.2967662 0.174475 0.2267131 0.1506835 0.2551221 0.1500412 0.2546555 0.174475 0.2267131 0.1500412 0.2546555 0.1493508 0.2542639 0.07639896 0.3508906 0.07715892 0.3510601 0.07647401 0.3841392 0.07566201 0.3506362 0.07639896 0.3508906 0.07647401 0.3841392 0.174475 0.2267131 0.1493508 0.2542639 0.1486207 0.2539522 0.174475 0.2267131 0.1486207 0.2539522 0.1478603 0.253724 0.07495743 0.3502994 0.07566201 0.3506362 0.07647401 0.3841392 0.07429397 0.3498843 0.07495743 0.3502994 0.07647401 0.3841392 0.174475 0.2267131 0.1478603 0.253724 0.1470791 0.2535824 0.174475 0.2267131 0.1470791 0.2535824 0.146287 0.253529 0.07367998 0.3493954 0.07429397 0.3498843 0.07647401 0.3841392 0.07312321 0.3488379 0.07367998 0.3493954 0.07647401 0.3841392 0.0219565 0.2540714 0.174475 0.2267131 0.1439479 0.2538963 0.174475 0.2267131 0.146287 0.253529 0.1454943 0.2535641 0.174475 0.2267131 0.1454943 0.2535641 0.1447111 0.2536873 0.07263046 0.3482171 0.07312321 0.3488379 0.07647401 0.3841392 0.07220751 0.3475378 0.07263046 0.3482171 0.07647401 0.3841392 0.174475 0.2267131 0.1447111 0.2536873 0.1439479 0.2538963 0.04481691 0.298317 0.07220751 0.3475378 0.07647401 0.3841392 0.04446303 0.2975589 0.04481691 0.298317 0.008181571 0.2617684 0.0219565 0.2540714 0.1439479 0.2538963 0.04785549 0.2882441 0.0219565 0.2540714 0.04785549 0.2882441 0.04714494 0.2886738 0.0441966 0.2967662 0.008181571 0.2617684 0.04402071 0.2959491 0.04402071 0.2959491 0.008181571 0.2617684 0.04393744 0.2951177 0.0219565 0.2540714 0.04714494 0.2886738 0.04648602 0.2891818 0.0219565 0.2540714 0.04648602 0.2891818 0.0458877 0.2897629 0.04393744 0.2951177 0.008181571 0.2617684 0.04394787 0.2942824 0.04394787 0.2942824 0.008181571 0.2617684 0.0440517 0.2934538 0.0219565 0.2540714 0.0458877 0.2897629 0.04535734 0.2904094 0.04535734 0.2904094 0.04490453 0.2911104 0.008181571 0.2617684 0.0440517 0.2934538 0.008181571 0.2617684 0.04424756 0.2926422 0.04424756 0.2926422 0.008181571 0.2617684 0.04453307 0.2918578 0.8631129 0.9094895 0.8204795 0.9073001 0.8206426 0.9023172 0.8843328 0.9057126 0.9090774 0.9699652 0.8631129 0.9094895 0.9090774 0.9699652 0.8804847 0.9713259 0.8739594 0.9709789 0.9090774 0.9699652 0.8739594 0.9709789 0.8631129 0.9094895 0.8804847 0.9713259 0.8153287 0.9744266 0.8270514 0.9733139 0.9632149 0.8570863 0.981158 0.9082872 0.9086689 0.8734209 0.6281018 0.3944575 0.5793785 0.4700611 0.4365528 0.3769267 0.8531991 0.8875417 0.8856092 0.8332486 0.9086689 0.8734209 0.8206426 0.9023172 0.8212924 0.8868725 0.8213143 0.8869313 0.8206426 0.9023172 0.8213143 0.8869313 0.8216513 0.8875509 0.8531991 0.8875417 0.9086689 0.8734209 0.8843328 0.9057126 0.8528711 0.8881674 0.8531991 0.8875417 0.8843328 0.9057126 0.8206426 0.9023172 0.8216513 0.8875509 0.8220782 0.8881083 0.8206426 0.9023172 0.8220782 0.8881083 0.822586 0.8885926 0.8524698 0.8887773 0.8528711 0.8881674 0.8843328 0.9057126 0.8520465 0.8893316 0.8524698 0.8887773 0.8843328 0.9057126 0.8206426 0.9023172 0.822586 0.8885926 0.8231619 0.8889913 0.8206426 0.9023172 0.8231619 0.8889913 0.8237912 0.8892955 0.8515428 0.8898204 0.8520465 0.8893316 0.8843328 0.9057126 0.8509646 0.8902213 0.8515428 0.8898204 0.8843328 0.9057126 0.8206426 0.9023172 0.8237912 0.8892955 0.8244565 0.8895012 0.8206426 0.9023172 0.8244565 0.8895012 0.825132 0.88961 0.8503234 0.8905199 0.8509646 0.8902213 0.8843328 0.9057126 0.8496351 0.890707 0.8503234 0.8905199 0.8843328 0.9057126 0.8843328 0.9057126 0.8206426 0.9023172 0.8489315 0.890781 0.8206426 0.9023172 0.825132 0.88961 0.8482088 0.890825 0.8206426 0.9023172 0.8482088 0.890825 0.8489315 0.890781 0.3338061 0.257941 0.3331465 0.2589855 0.3334052 0.2241951 0.3334052 0.2241951 0.4433817 0.2251373 0.3970552 0.2544493 0.4433817 0.2251373 0.5172361 0.2255963 0.4072988 0.2643404 0.3970552 0.2544493 0.4433817 0.2251373 0.3987593 0.2546102 0.5172361 0.2255963 0.5004894 0.330456 0.4072988 0.2643404 0.5004894 0.330456 0.4365528 0.3769267 0.4072988 0.2643404 0.3348249 0.2567802 0.3338061 0.257941 0.3334052 0.2241951 0.3360128 0.2557929 0.3348249 0.2567802 0.3334052 0.2241951 0.4072988 0.2643404 0.4069345 0.2626325 0.4433817 0.2251373 0.4069345 0.2626325 0.4062386 0.2609741 0.4433817 0.2251373 0.3373403 0.2550035 0.3360128 0.2557929 0.3334052 0.2241951 0.3387749 0.2544316 0.3373403 0.2550035 0.3334052 0.2241951 0.4062386 0.2609741 0.4055258 0.2594178 0.4433817 0.2251373 0.4055258 0.2594178 0.4045535 0.2580088 0.4433817 0.2251373 0.340281 0.254091 0.3387749 0.2544316 0.3334052 0.2241951 0.3418218 0.2539903 0.340281 0.254091 0.3334052 0.2241951 0.4045535 0.2580088 0.4033514 0.2567901 0.4433817 0.2251373 0.4033514 0.2567901 0.401956 0.2557986 0.4433817 0.2251373 0.3418218 0.2539903 0.3334052 0.2241951 0.3970552 0.2544493 0.3987593 0.2546102 0.4433817 0.2251373 0.4004096 0.2550646 0.6880185 0.8704311 0.658658 0.8068557 0.7913666 0.7970162 0.09564483 0.404841 0.1895545 0.3639723 0.2867114 0.4380289 0.658658 0.8068557 0.6880185 0.8704311 0.6615117 0.8536715 0.6880185 0.8704311 0.6769561 0.8922903 0.6615117 0.8536715 0.09434968 0.5149184 0.05207228 0.512856 0.0545926 0.4552482 0.0545926 0.4552482 0.07647401 0.3841392 0.09564483 0.404841 0.7529727 0.8688679 0.7451852 0.8560523 0.7913666 0.7970162 0.9117215 0.8896787 0.9120535 0.889434 0.9122476 0.8897275 0.8972221 0.9094889 0.8975675 0.9094813 0.8975955 0.9098473 0.9312095 0.9491473 0.9309669 0.9487757 0.9313463 0.9484902 0.9151513 0.8889935 0.9155386 0.8891358 0.9153966 0.8894621 0.9131584 0.8889433 0.9135509 0.8888647 0.913599 0.8892037 0.8981258 0.9069538 0.910916 0.8905769 0.9111493 0.8907686 0.8973832 0.9082965 0.8975198 0.9079233 0.8978326 0.9080528 0.931633 0.9488391 0.9313463 0.9484902 0.9316985 0.9481518 0.9147548 0.8888944 0.9151513 0.8889935 0.9150462 0.8893282 0.9159118 0.8893178 0.9556968 0.9155468 0.9554474 0.9158514 0.9302806 0.9496127 0.9301292 0.9491981 0.9305601 0.9490118 0.8974411 0.9106757 0.897766 0.9105627 0.8979064 0.9109035 0.9111468 0.8902614 0.9114175 0.8899571 0.9116627 0.890206 0.9307575 0.949406 0.9305601 0.9490118 0.9309669 0.9487757 0.9271675 0.9496498 0.9273212 0.9492099 0.9277938 0.949346 0.9282227 0.9498755 0.9282675 0.949424 0.9287428 0.9494475 0.8972327 0.9090862 0.8975785 0.9091149 0.8975675 0.9094813 0.9287478 0.9498964 0.9287428 0.9494475 0.9292151 0.9494172 0.9253795 0.9484837 0.9256636 0.9481966 0.9260324 0.9485024 0.9124076 0.8892278 0.9127764 0.8890647 0.9129001 0.8893867 0.9261868 0.9491693 0.9264337 0.948782 0.9268652 0.9490203 0.8975198 0.9079233 0.8976923 0.9075707 0.8979849 0.9077253 0.9266614 0.949438 0.9268652 0.9490203 0.9273212 0.9492099 0.9556968 0.9155468 0.9560593 0.9158544 0.9557726 0.9161452 0.9139505 0.88883 0.914353 0.8888398 0.9143245 0.8891834 0.9563893 0.9162108 0.9566771 0.9166083 0.9563217 0.9168324 0.9569172 0.9170401 0.9571056 0.9174989 0.956704 0.9176362 0.9297829 0.9497646 0.9296791 0.9493337 0.9301292 0.9491981 0.9155386 0.8891358 0.9159118 0.8893178 0.9157375 0.8896365 0.9573361 0.9189664 0.9572969 0.9194599 0.9568824 0.9194064 0.8978965 0.907245 0.8981258 0.9069538 0.8983586 0.9071247 0.9572108 0.9199461 0.9567998 0.919846 0.9568824 0.9194064 0.9563274 0.9217127 0.9559856 0.9214432 0.9562572 0.9210773 0.9292699 0.9498595 0.9292151 0.9494172 0.9296791 0.9493337 0.9566771 0.9166083 0.9569172 0.9170401 0.9565356 0.9172223 0.9570671 0.9204223 0.956667 0.9202747 0.9567998 0.919846 0.9566197 0.921313 0.9562572 0.9210773 0.9564858 0.9206869 0.9257536 0.9488486 0.9260324 0.9485024 0.9264337 0.948782 0.8973266 0.9102879 0.897662 0.9102092 0.897766 0.9105627 0.9573168 0.9184695 0.9573361 0.9189664 0.9569141 0.9189592 0.910916 0.8905769 0.9111468 0.8902614 0.9114008 0.8904836 0.9320235 0.9484888 0.9316985 0.9481518 0.9559856 0.9214432 0.8977885 0.9114053 0.8980824 0.9112277 0.8982937 0.9115315 0.9560593 0.9158544 0.9563893 0.9162108 0.9560659 0.9164719 0.8972839 0.9086859 0.8976295 0.9087516 0.8975785 0.9091149 0.9120535 0.889434 0.9124076 0.8892278 0.912571 0.8895366 0.9114175 0.8899571 0.9117215 0.8896787 0.9119445 0.8899517 0.9568688 0.9208801 0.9564858 0.9206869 0.956667 0.9202747 0.8972534 0.909891 0.8975955 0.9098473 0.897662 0.9102092 0.8976923 0.9075707 0.8978965 0.907245 0.8981632 0.9074153 0.9127764 0.8890647 0.9131584 0.8889433 0.9132443 0.8892753 0.8980163 0.9117391 0.8982937 0.9115315 0.898546 0.9118154 0.9571056 0.9174989 0.9572395 0.9179778 0.9568243 0.918068 0.9135509 0.8888647 0.9139505 0.88883 0.9139603 0.8891729 0.8972839 0.9086859 0.8973832 0.9082965 0.8977127 0.9083956 0.8975957 0.9110495 0.8979064 0.9109035 0.8980824 0.9112277 0.914353 0.8888398 0.9147548 0.8888944 0.9146876 0.8892351 0.9253795 0.9484837 0.8982692 0.912044 0.898546 0.9118154 0.9276995 0.949799 0.9277938 0.949346 0.9282675 0.949424 0.9572395 0.9179778 0.9573168 0.9184695 0.9568946 0.9185111 0.7481969 0.8843272 0.7484319 0.8845139 0.7482625 0.8847054 0.758993 0.9039866 0.7589284 0.9043017 0.7586627 0.9042307 0.7203593 0.9371479 0.720015 0.9368742 0.7202717 0.9365931 0.7455473 0.884004 0.7458473 0.8839116 0.7459166 0.8841753 0.7470774 0.8838632 0.7473767 0.8839331 0.7473023 0.8841856 0.7489702 0.8851911 0.7584823 0.9018914 0.758258 0.9020243 0.758897 0.9027303 0.7589733 0.9030371 0.7587076 0.903087 0.720015 0.9368742 0.7197008 0.9365606 0.719996 0.9363044 0.7458473 0.8839116 0.7461532 0.8838502 0.7461926 0.8841155 0.7453793 0.8843972 0.700861 0.9028145 0.7006751 0.9025083 0.7211256 0.9375656 0.7207308 0.9373791 0.7209115 0.937051 0.7586935 0.90491 0.7585245 0.9051975 0.7582864 0.9050368 0.7486414 0.8847237 0.7488215 0.884952 0.7486249 0.8850954 0.7207308 0.9373791 0.7203593 0.9371479 0.7205784 0.9368418 0.7237785 0.9376698 0.7233069 0.9377867 0.7232354 0.9373896 0.722851 0.9378385 0.722405 0.9378422 0.7224197 0.9374612 0.7590218 0.9036687 0.758993 0.9039866 0.7587229 0.9039461 0.722405 0.9378422 0.7219669 0.937798 0.7220249 0.9374258 0.7253959 0.9366716 0.7250492 0.9369898 0.7248038 0.9366722 0.7476655 0.8840347 0.7479401 0.8841668 0.747814 0.8843951 0.7246567 0.9372669 0.7242303 0.9374949 0.7240597 0.9371212 0.7587873 0.9024342 0.758897 0.9027303 0.7586387 0.902809 0.7242303 0.9374949 0.7237785 0.9376698 0.723654 0.9372794 0.7003173 0.9027553 0.7006751 0.9025083 0.700861 0.9028145 0.7464622 0.8838215 0.7467713 0.8838258 0.746753 0.8840901 0.6996952 0.9033807 0.699989 0.9030486 0.7002576 0.9033159 0.6992293 0.904137 0.6994407 0.9037455 0.6997647 0.9039472 0.721539 0.9377057 0.7211256 0.9375656 0.7212665 0.9372192 0.7452577 0.8841221 0.7455473 0.884004 0.7456463 0.8842683 0.6988621 0.905857 0.6988794 0.9054152 0.6992563 0.905453 0.7584823 0.9018914 0.7586469 0.9021527 0.7584115 0.9022797 0.6988952 0.9062972 0.6988621 0.905857 0.6992403 0.9058512 0.6995148 0.9079512 0.6992902 0.9075626 0.699638 0.9073818 0.7219669 0.937798 0.721539 0.9377057 0.7216391 0.9373446 0.6994407 0.9037455 0.6996952 0.9033807 0.6999941 0.9036175 0.6989781 0.906731 0.6988952 0.9062972 0.6992703 0.9062479 0.6992902 0.9075626 0.6991101 0.9071541 0.6994686 0.9070174 0.7250492 0.9369898 0.7246567 0.9372669 0.7244449 0.9369177 0.7588284 0.9046105 0.7586935 0.90491 0.7584443 0.904779 0.6988794 0.9054152 0.6989469 0.9049776 0.6993178 0.9050583 0.7488215 0.884952 0.7489702 0.8851911 0.7487696 0.8853156 0.7197008 0.9365606 0.6995148 0.9079512 0.6998571 0.9077303 0.7583235 0.9054699 0.7580934 0.9057248 0.7578778 0.905509 0.699989 0.9030486 0.7003173 0.9027553 0.7005494 0.9030467 0.7590152 0.903351 0.7590218 0.9036687 0.7587502 0.9036585 0.7479401 0.8841668 0.7481969 0.8843272 0.7480477 0.8845388 0.7484319 0.8845139 0.7486414 0.8847237 0.7484558 0.8848919 0.6991101 0.9071541 0.6989781 0.906731 0.6993463 0.9066382 0.7589284 0.9043017 0.7588284 0.9046105 0.7585698 0.9045093 0.7586469 0.9021527 0.7587873 0.9024342 0.7585394 0.9025397 0.7473767 0.8839331 0.7476655 0.8840347 0.7475644 0.8842768 0.7580934 0.9057248 0.7578453 0.9059553 0.7576303 0.9057236 0.699064 0.9045496 0.6992293 0.904137 0.6995738 0.9043004 0.7467713 0.8838258 0.7470774 0.8838632 0.7470307 0.8841232 0.7589733 0.9030371 0.7590152 0.903351 0.758745 0.9033712 0.7585245 0.9051975 0.7583235 0.9054699 0.7580966 0.9052792 0.7461532 0.8838502 0.7464622 0.8838215 0.7464725 0.8840874 0.7578453 0.9059553 0.7253959 0.9366716 0.725137 0.9363867 0.7233069 0.9377867 0.722851 0.9378385 0.7228199 0.9374493 0.6989469 0.9049776 0.699064 0.9045496 0.6994242 0.9046724 0.7838017 0.9661539 0.783411 0.9665004 0.7951825 0.9067766 0.8631129 0.9094895 0.8739594 0.9709789 0.8735573 0.9705377 0.6610493 0.8535416 0.6615117 0.8536715 0.6769561 0.8922903 0.7955474 0.9071758 0.7951825 0.9067766 0.8204795 0.9073001 0.8204795 0.9073001 0.8631129 0.9094895 0.8567802 0.9095799 0.8567802 0.9095799 0.820461 0.9078074 0.8204795 0.9073001 0.8489009 0.8903851 0.8489315 0.890781 0.8482088 0.890825 0.8210781 0.8862837 0.8208814 0.8856445 0.8212972 0.8855296 0.822586 0.8885926 0.8220782 0.8881083 0.8223941 0.8878224 0.8495655 0.890317 0.8496351 0.890707 0.8489315 0.890781 0.8244565 0.8895012 0.8237912 0.8892955 0.8239458 0.8888988 0.8217603 0.8868799 0.8220065 0.8873179 0.8216513 0.8875509 0.8216513 0.8875509 0.8213143 0.8869313 0.8217603 0.8868799 0.8220782 0.8881083 0.8216513 0.8875509 0.8220065 0.8873179 0.8482088 0.890825 0.825132 0.88961 0.8251839 0.8891966 0.8853808 0.832731 0.963638 0.8568787 0.8856092 0.8332486 0.963638 0.8568787 0.9635183 0.8570276 0.9632149 0.8570863 0.8856092 0.8332486 0.963638 0.8568787 0.9632149 0.8570863 0.8856092 0.8332486 0.8531991 0.8875417 0.8528541 0.8873486 0.825132 0.88961 0.8244565 0.8895012 0.8245538 0.889087 0.8528541 0.8873486 0.8531991 0.8875417 0.8528711 0.8881674 0.851759 0.8890734 0.8520465 0.8893316 0.8515428 0.8898204 0.8208814 0.8856445 0.8207169 0.884998 0.821152 0.8848704 0.8507741 0.8898853 0.8509646 0.8902213 0.8503234 0.8905199 0.8237912 0.8892955 0.8231619 0.8889913 0.823375 0.8886228 0.85253 0.8879653 0.8528711 0.8881674 0.8524698 0.8887773 0.8231619 0.8889913 0.822586 0.8885926 0.8228539 0.8882614 0.851299 0.8895217 0.8515428 0.8898204 0.8509646 0.8902213 0.658658 0.8068557 0.6539314 0.834717 0.6534397 0.8344755 0.6539314 0.834717 0.6539292 0.8347179 0.6534397 0.8344755 0.6534397 0.8344755 0.6581624 0.8063405 0.658658 0.8068557 0.79183 0.7963298 0.8020621 0.8262268 0.7913666 0.7970162 0.8020621 0.8262268 0.821152 0.8848704 0.8017322 0.8268812 0.7913666 0.7970162 0.8020621 0.8262268 0.8017322 0.8268812 0.821152 0.8848704 0.8207169 0.884998 0.8017322 0.8268812 0.7913666 0.7970162 0.658658 0.8068557 0.6581624 0.8063405 0.8501926 0.8901529 0.8503234 0.8905199 0.8496351 0.890707 0.8217098 0.8867626 0.8213143 0.8869313 0.8212924 0.8868725 0.8212924 0.8868725 0.8210781 0.8862837 0.8214814 0.8861495 0.8521551 0.8885557 0.8524698 0.8887773 0.8520465 0.8893316 0.1712428 0.01541733 0.21771 0.0150693 0.1713902 0.03509753 0.21771 0.0150693 0.2695215 0.01469802 0.2679117 0.03438824 0.7991394 0.9672784 0.8254557 0.9729788 0.8652717 0.9709582 0.3334052 0.2241951 0.2692312 0.2232967 0.2690851 0.2092068 0.3335518 0.2099398 0.4432952 0.2108101 0.3334052 0.2241951 0.4432952 0.2108101 0.4433817 0.2251373 0.3334052 0.2241951 0.4437994 0.03414064 0.4437184 0.01445209 0.5180054 0.01453781 0.4432952 0.2108101 0.4437604 0.03551566 0.5179812 0.03422337 0.4437604 0.03551566 0.4437994 0.03414064 0.5179812 0.03422337 0.5179812 0.03422337 0.5172361 0.2255963 0.4432952 0.2108101 0.2695215 0.01469802 0.4437184 0.01445209 0.4437994 0.03414064 0.2679117 0.03438824 0.4437994 0.03414064 0.4437604 0.03551566 0.2679027 0.03576338 0.2690851 0.2092068 0.1713902 0.03509753 0.2690851 0.2092068 0.2692312 0.2232967 0.174475 0.2267131 0.1713902 0.03509753 0.2690851 0.2092068 0.174475 0.2267131 - - - - - - - - - - - - - - -

24 0 0 12 0 1 13 0 2 19 1 3 281 1 4 280 1 5 15 2 6 19 2 7 18 2 8 16 3 9 13 3 10 12 3 11 342 4 12 282 4 13 283 4 14 286 5 15 288 5 16 4 5 17 234 6 18 232 6 19 9 6 20 11 7 21 50 7 22 88 7 23 83 8 24 73 8 25 14 8 26 15 9 27 136 9 28 137 9 29 10 10 30 110 10 31 112 10 32 22 11 33 270 11 34 272 11 35 339 12 36 292 12 37 291 12 38 13 13 39 195 13 40 196 13 41 155 14 42 157 14 43 8 14 44 263 6 45 255 6 46 12 6 47 277 15 48 22 15 49 6 15 50 341 16 51 269 16 52 276 16 53 281 17 54 11 17 55 296 17 56 18 18 57 297 18 58 10 18 59 298 19 60 300 19 61 6 19 62 326 20 63 325 20 64 344 20 65 27 21 66 333 21 67 25 21 68 28 22 69 336 22 70 335 22 71 342 23 72 284 23 73 334 23 74 343 24 75 28 24 76 335 24 77 8 25 78 333 25 79 289 25 80 154 26 261 211 26 262 213 26 263 171 86 264 222 86 265 223 86 266 199 87 267 260 87 268 259 87 269 161 88 270 236 88 271 235 88 272 157 89 273 230 89 274 232 89 275 150 90 276 218 90 277 212 90 278 167 91 279 217 91 280 215 91 281 200 92 282 262 92 283 260 92 284 164 93 285 237 93 286 236 93 287 238 94 288 207 94 289 163 94 290 198 95 291 261 95 292 258 95 293 173 96 294 225 96 295 227 96 296 149 97 297 209 97 298 210 97 299 202 98 300 259 98 301 261 98 302 205 99 303 263 99 304 252 99 305 197 100 306 257 100 307 255 100 308 170 101 309 223 101 310 219 101 311 196 102 312 256 102 313 257 102 314 204 103 315 251 103 316 265 103 317 156 104 318 229 104 319 231 104 320 190 105 321 253 105 322 254 105 323 165 106 324 215 106 325 214 106 326 191 107 327 252 107 328 253 107 329 183 108 330 268 108 331 240 108 332 160 109 333 234 109 334 233 109 335 179 110 336 239 110 337 246 110 338 180 111 339 242 111 340 241 111 341 201 112 342 258 112 343 264 112 344 163 113 345 235 113 346 238 113 347 185 114 348 243 114 349 267 114 350 162 115 351 216 115 352 218 115 353 189 116 354 267 116 355 247 116 356 206 117 357 248 117 358 266 117 359 195 118 360 264 118 361 256 118 362 182 119 363 246 119 364 242 119 365 188 120 366 247 120 367 250 120 368 193 121 369 249 121 370 248 121 371 192 122 372 254 122 373 251 122 374 172 123 375 227 123 376 221 123 377 186 124 378 244 124 379 243 124 380 151 125 381 212 125 382 209 125 383 203 126 384 266 126 385 262 126 386 177 127 387 226 127 388 224 127 389 178 128 390 240 128 391 239 128 392 169 129 393 219 129 394 220 129 395 153 130 396 213 130 397 229 130 398 152 131 399 210 131 400 211 131 401 187 132 402 250 132 403 249 132 404 174 133 405 221 133 406 222 133 407 166 134 408 214 134 409 216 134 410 155 135 411 231 135 412 230 135 413 176 136 414 228 136 415 226 136 416 181 137 417 241 137 418 245 137 419 158 138 420 232 138 421 234 138 422 168 80 423 220 80 424 217 80 425 175 139 426 224 139 427 225 139 428 159 140 429 233 140 430 237 140 431 184 141 432 265 141 433 228 141 434 194 142 435 255 142 436 263 142 437 208 143 438 245 143 439 244 143 440 274 144 441 272 144 442 273 144 443 277 145 444 271 145 445 278 145 446 343 146 447 17 146 448 16 146 449 275 147 450 273 147 451 270 147 452 1 169 519 24 169 520 21 169 521 269 170 522 271 170 523 276 170 524 338 172 528 15 172 529 3 172 530 7 173 531 344 173 532 278 173 533 21 175 537 271 175 538 274 175 539 1 176 540 21 176 541 274 176 542 14 177 543 15 177 544 337 177 545 14 178 546 337 178 547 341 178 548 337 179 549 340 179 550 341 179 551 341 180 552 2 180 553 14 180 554 13 181 555 0 181 556 24 181 557 0 182 558 20 182 559 24 182 560 20 183 561 341 183 562 340 183 563 340 184 564 24 184 565 20 184 566 280 185 567 279 185 568 19 185 569 279 186 570 18 186 571 19 186 572 15 187 573 14 187 574 19 187 575 16 188 576 17 188 577 13 188 578 283 189 579 284 189 580 342 189 581 342 190 582 343 190 583 282 190 584 288 191 585 287 191 586 22 191 587 22 192 588 4 192 589 288 192 590 4 193 591 8 193 592 285 193 593 286 194 594 4 194 595 285 194 596 8 195 597 289 195 598 285 195 599 217 6 600 220 6 601 5 6 602 5 196 603 9 196 604 212 196 605 9 6 606 26 6 607 238 6 608 5 197 609 216 197 610 214 197 611 26 6 612 28 6 613 238 6 614 28 198 615 16 198 616 268 198 617 239 6 618 16 6 619 246 6 620 16 199 621 241 199 622 242 199 623 16 200 624 242 200 625 246 200 626 215 6 627 217 6 628 5 6 629 214 6 630 215 6 631 5 6 632 16 201 633 239 201 634 240 201 635 16 202 636 240 202 637 268 202 638 216 6 639 5 6 640 218 6 641 218 6 642 5 6 643 212 6 644 28 203 645 268 203 646 238 203 647 212 204 648 9 204 649 209 204 650 209 205 651 9 205 652 210 205 653 238 6 654 235 6 655 9 6 656 210 6 657 9 6 658 211 6 659 211 6 660 9 6 661 213 6 662 235 6 663 236 6 664 9 6 665 236 6 666 237 6 667 9 6 668 213 6 669 9 6 670 229 6 671 229 206 672 9 206 673 231 206 674 237 6 675 233 6 676 9 6 677 233 6 678 234 6 679 9 6 680 231 207 681 9 207 682 230 207 683 230 6 684 9 6 685 232 6 686 49 6 687 40 6 688 6 6 689 19 208 690 58 208 691 59 208 692 19 209 693 59 209 694 60 209 695 35 6 696 49 6 697 6 6 698 36 6 699 35 6 700 6 6 701 19 210 702 60 210 703 57 210 704 19 211 705 57 211 706 66 211 707 36 6 708 6 6 709 37 6 710 6 212 711 11 212 712 32 212 713 37 6 714 6 6 715 38 6 716 38 6 717 6 6 718 32 6 719 11 213 720 19 213 721 56 213 722 19 214 723 66 214 724 86 214 725 19 215 726 86 215 727 56 215 728 11 216 729 56 216 730 54 216 731 29 6 732 32 6 733 11 6 734 30 6 735 29 6 736 11 6 737 11 217 738 54 217 739 55 217 740 11 218 741 55 218 742 53 218 743 31 6 744 30 6 745 11 6 746 33 6 747 31 6 748 11 6 749 11 219 750 53 219 751 51 219 752 11 220 753 51 220 754 52 220 755 34 6 756 33 6 757 11 6 758 87 6 759 34 6 760 11 6 761 11 221 762 52 221 763 50 221 764 88 6 765 87 6 766 11 6 767 65 6 768 58 6 769 19 6 770 19 6 771 14 6 772 81 6 773 14 6 774 2 6 775 83 6 776 19 222 777 81 222 778 84 222 779 6 223 780 40 223 781 39 223 782 6 224 783 39 224 784 43 224 785 61 6 786 65 6 787 19 6 788 64 6 789 61 6 790 19 6 791 6 225 792 43 225 793 42 225 794 6 226 795 42 226 796 41 226 797 63 227 798 64 227 799 19 227 800 62 228 801 63 228 802 19 228 803 6 229 804 41 229 805 47 229 806 6 230 807 47 230 808 45 230 809 85 6 810 62 6 811 19 6 812 67 6 813 85 6 814 19 6 815 2 6 816 6 6 817 48 6 818 6 231 819 45 231 820 44 231 821 6 232 822 44 232 823 46 232 824 68 6 825 67 6 826 19 6 827 84 6 828 68 6 829 19 6 830 6 233 831 46 233 832 48 233 833 81 6 834 14 6 835 79 6 836 79 6 837 14 6 838 78 6 839 2 234 840 48 234 841 82 234 842 2 235 843 82 235 844 72 235 845 78 236 846 14 236 847 77 236 848 77 6 849 14 6 850 80 6 851 2 237 852 72 237 853 69 237 854 2 238 855 69 238 856 71 238 857 80 6 858 14 6 859 74 6 860 74 6 861 14 6 862 75 6 863 2 6 864 71 6 865 70 6 866 2 239 867 70 239 868 83 239 869 75 6 870 14 6 871 76 6 872 76 6 873 14 6 874 73 6 875 99 14 876 100 14 877 7 14 878 7 14 879 3 14 880 108 14 881 3 14 882 15 14 883 132 14 884 7 240 885 106 240 886 104 240 887 18 241 888 122 241 889 125 241 890 18 242 891 125 242 892 123 242 893 103 14 894 99 14 895 7 14 896 102 14 897 103 14 898 7 14 899 18 243 900 123 243 901 124 243 902 18 244 903 124 244 904 148 244 905 101 14 906 102 14 907 7 14 908 107 14 909 101 14 910 7 14 911 18 245 912 148 245 913 128 245 914 18 246 915 128 246 916 127 246 917 105 14 918 107 14 919 7 14 920 104 14 921 105 14 922 7 14 923 18 247 924 127 247 925 130 247 926 18 248 927 130 248 928 129 248 929 106 14 930 7 14 931 108 14 932 108 14 933 3 14 934 145 14 935 15 249 936 18 249 937 142 249 938 18 250 939 129 250 940 146 250 941 18 14 942 146 14 943 142 14 944 145 14 945 3 14 946 131 14 947 131 14 948 3 14 949 134 14 950 15 251 951 142 251 952 140 251 953 134 14 954 3 14 955 133 14 956 133 14 957 3 14 958 132 14 959 15 252 960 140 252 961 139 252 962 15 253 963 139 253 964 141 253 965 15 254 966 141 254 967 138 254 968 15 255 969 138 255 970 144 255 971 143 14 972 132 14 973 15 14 974 135 14 975 143 14 976 15 14 977 15 256 978 144 256 979 136 256 980 137 14 981 135 14 982 15 14 983 126 14 984 122 14 985 18 14 986 7 257 987 100 257 988 109 257 989 7 258 990 109 258 991 95 258 992 119 14 993 126 14 994 18 14 995 120 259 996 119 259 997 18 259 998 10 260 999 7 260 1000 92 260 1001 7 261 1002 95 261 1003 96 261 1004 7 262 1005 96 262 1006 97 262 1007 120 14 1008 18 14 1009 121 14 1010 18 263 1011 10 263 1012 118 263 1013 121 14 1014 18 14 1015 147 14 1016 147 14 1017 18 14 1018 118 14 1019 7 264 1020 97 264 1021 98 264 1022 7 265 1023 98 265 1024 92 265 1025 10 266 1026 92 266 1027 89 266 1028 116 14 1029 118 14 1030 10 14 1031 117 14 1032 116 14 1033 10 14 1034 10 267 1035 89 267 1036 90 267 1037 10 268 1038 90 268 1039 91 268 1040 114 14 1041 117 14 1042 10 14 1043 115 14 1044 114 14 1045 10 14 1046 10 269 1047 91 269 1048 93 269 1049 10 270 1050 93 270 1051 94 270 1052 113 271 1053 115 271 1054 10 271 1055 111 272 1056 113 272 1057 10 272 1058 10 273 1059 94 273 1060 110 273 1061 112 14 1062 111 14 1063 10 14 1064 272 274 1065 269 274 1066 0 274 1067 269 275 1068 20 275 1069 0 275 1070 0 276 1071 4 276 1072 272 276 1073 4 277 1074 22 277 1075 272 277 1076 9 278 1077 5 278 1078 339 278 1079 339 279 1080 23 279 1081 294 279 1082 23 280 1083 295 280 1084 294 280 1085 26 281 1086 9 281 1087 290 281 1088 9 282 1089 339 282 1090 291 282 1091 293 283 1092 339 283 1093 294 283 1094 290 284 1095 336 284 1096 26 284 1097 291 285 1098 290 285 1099 9 285 1100 339 286 1101 293 286 1102 292 286 1103 170 287 1104 169 287 1105 4 287 1106 4 14 1107 0 14 1108 184 14 1109 0 14 1110 13 14 1111 194 14 1112 4 288 1113 176 288 1114 177 288 1115 17 289 1116 180 289 1117 181 289 1118 17 290 1119 181 290 1120 208 290 1121 171 291 1122 170 291 1123 4 291 1124 174 292 1125 171 292 1126 4 292 1127 17 293 1128 208 293 1129 186 293 1130 17 294 1131 186 294 1132 185 294 1133 172 14 1134 174 14 1135 4 14 1136 173 14 1137 172 14 1138 4 14 1139 17 295 1140 185 295 1141 189 295 1142 17 296 1143 189 296 1144 188 296 1145 175 14 1146 173 14 1147 4 14 1148 177 14 1149 175 14 1150 4 14 1151 17 297 1152 188 297 1153 187 297 1154 17 298 1155 187 298 1156 193 298 1157 176 14 1158 4 14 1159 184 14 1160 184 299 1161 0 299 1162 204 299 1163 13 14 1164 17 14 1165 203 14 1166 17 300 1167 193 300 1168 206 300 1169 17 301 1170 206 301 1171 203 301 1172 204 302 1173 0 302 1174 192 302 1175 192 303 1176 0 303 1177 190 303 1178 13 304 1179 203 304 1180 200 304 1181 190 305 1182 0 305 1183 191 305 1184 191 14 1185 0 14 1186 205 14 1187 13 306 1188 200 306 1189 199 306 1190 13 307 1191 199 307 1192 202 307 1193 205 14 1194 0 14 1195 194 14 1196 13 308 1197 202 308 1198 198 308 1199 13 309 1200 198 309 1201 201 309 1202 197 14 1203 194 14 1204 13 14 1205 13 310 1206 201 310 1207 195 310 1208 196 14 1209 197 14 1210 13 14 1211 182 14 1212 180 14 1213 17 14 1214 17 311 1215 27 311 1216 207 311 1217 27 14 1218 25 14 1219 163 14 1220 17 312 1221 179 312 1222 182 312 1223 25 313 1224 8 313 1225 163 313 1226 8 314 1227 4 314 1228 150 314 1229 162 14 1230 4 14 1231 166 14 1232 4 315 1233 169 315 1234 168 315 1235 4 316 1236 168 316 1237 167 316 1238 179 14 1239 17 14 1240 178 14 1241 178 14 1242 17 14 1243 183 14 1244 4 14 1245 167 14 1246 165 14 1247 4 317 1248 165 317 1249 166 317 1250 183 14 1251 17 14 1252 207 14 1253 207 318 1254 27 318 1255 163 318 1256 4 319 1257 162 319 1258 150 319 1259 8 320 1260 150 320 1261 151 320 1262 8 321 1263 151 321 1264 149 321 1265 161 322 1266 163 322 1267 8 322 1268 164 14 1269 161 14 1270 8 14 1271 8 323 1272 149 323 1273 152 323 1274 8 324 1275 152 324 1276 154 324 1277 159 14 1278 164 14 1279 8 14 1280 160 14 1281 159 14 1282 8 14 1283 8 325 1284 154 325 1285 153 325 1286 8 326 1287 153 326 1288 156 326 1289 158 14 1290 160 14 1291 8 14 1292 157 14 1293 158 14 1294 8 14 1295 8 327 1296 156 327 1297 155 327 1298 245 6 1299 241 6 1300 16 6 1301 16 328 1302 12 328 1303 262 328 1304 12 6 1305 1 6 1306 252 6 1307 260 329 1308 12 329 1309 259 329 1310 5 330 1311 220 330 1312 219 330 1313 5 331 1314 219 331 1315 223 331 1316 244 332 1317 245 332 1318 16 332 1319 243 6 1320 244 6 1321 16 6 1322 5 333 1323 223 333 1324 222 333 1325 5 334 1326 222 334 1327 221 334 1328 267 6 1329 243 6 1330 16 6 1331 247 6 1332 267 6 1333 16 6 1334 5 335 1335 221 335 1336 227 335 1337 5 336 1338 227 336 1339 225 336 1340 250 6 1341 247 6 1342 16 6 1343 249 337 1344 250 337 1345 16 337 1346 1 6 1347 5 6 1348 228 6 1349 5 338 1350 225 338 1351 224 338 1352 5 339 1353 224 339 1354 226 339 1355 248 6 1356 249 6 1357 16 6 1358 266 6 1359 248 6 1360 16 6 1361 5 340 1362 226 340 1363 228 340 1364 262 341 1365 266 341 1366 16 341 1367 260 6 1368 262 6 1369 12 6 1370 1 342 1371 228 342 1372 265 342 1373 1 343 1374 265 343 1375 251 343 1376 259 6 1377 12 6 1378 261 6 1379 261 6 1380 12 6 1381 258 6 1382 1 344 1383 251 344 1384 254 344 1385 1 345 1386 254 345 1387 253 345 1388 258 6 1389 12 6 1390 264 6 1391 264 6 1392 12 6 1393 256 6 1394 1 346 1395 253 346 1396 252 346 1397 252 6 1398 263 6 1399 12 6 1400 256 6 1401 12 6 1402 257 6 1403 257 6 1404 12 6 1405 255 6 1406 277 347 1407 270 347 1408 22 347 1409 6 348 1410 2 348 1411 277 348 1412 2 349 1413 341 349 1414 276 349 1415 2 350 1416 276 350 1417 277 350 1418 341 351 1419 20 351 1420 269 351 1421 281 352 1422 19 352 1423 11 352 1424 18 353 1425 279 353 1426 297 353 1427 305 354 1428 296 354 1429 11 354 1430 22 355 1431 287 355 1432 308 355 1433 22 356 1434 308 356 1435 311 356 1436 305 357 1437 11 357 1438 6 357 1439 304 358 1440 305 358 1441 6 358 1442 22 359 1443 311 359 1444 310 359 1445 22 360 1446 310 360 1447 309 360 1448 306 361 1449 304 361 1450 6 361 1451 303 362 1452 306 362 1453 6 362 1454 22 363 1455 309 363 1456 315 363 1457 22 364 1458 315 364 1459 312 364 1460 302 365 1461 303 365 1462 6 365 1463 307 366 1464 302 366 1465 6 366 1466 22 367 1467 312 367 1468 313 367 1469 22 368 1470 313 368 1471 314 368 1472 301 369 1473 307 369 1474 6 369 1475 300 370 1476 301 370 1477 6 370 1478 6 371 1479 22 371 1480 298 371 1481 22 372 1482 314 372 1483 299 372 1484 22 373 1485 299 373 1486 298 373 1487 316 374 1488 295 374 1489 23 374 1490 23 375 1491 344 375 1492 324 375 1493 344 376 1494 7 376 1495 330 376 1496 324 377 1497 344 377 1498 323 377 1499 7 378 1500 10 378 1501 330 378 1502 10 379 1503 297 379 1504 330 379 1505 318 380 1506 316 380 1507 23 380 1508 317 381 1509 318 381 1510 23 381 1511 330 382 1512 329 382 1513 344 382 1514 329 383 1515 331 383 1516 344 383 1517 322 384 1518 317 384 1519 23 384 1520 319 385 1521 322 385 1522 23 385 1523 331 386 1524 328 386 1525 344 386 1526 328 387 1527 327 387 1528 344 387 1529 320 388 1530 319 388 1531 23 388 1532 321 389 1533 320 389 1534 23 389 1535 327 390 1536 332 390 1537 344 390 1538 332 391 1539 326 391 1540 344 391 1541 321 392 1542 23 392 1543 324 392 1544 323 393 1545 344 393 1546 325 393 1547 27 394 1548 334 394 1549 333 394 1550 28 395 1551 26 395 1552 336 395 1553 334 396 1554 27 396 1555 342 396 1556 27 397 1557 17 397 1558 342 397 1559 335 398 1560 282 398 1561 343 398 1562 343 399 1563 16 399 1564 28 399 1565 8 400 1566 25 400 1567 333 400 1568 154 449 1749 152 449 1750 211 449 1751 171 450 1752 174 450 1753 222 450 1754 199 451 1755 200 451 1756 260 451 1757 161 452 1758 164 452 1759 236 452 1760 157 453 1761 155 453 1762 230 453 1763 150 454 1764 162 454 1765 218 454 1766 167 455 1767 168 455 1768 217 455 1769 200 456 1770 203 456 1771 262 456 1772 164 93 1773 159 93 1774 237 93 1775 238 457 1776 268 457 1777 207 457 1778 198 458 1779 202 458 1780 261 458 1781 173 459 1782 175 459 1783 225 459 1784 149 460 1785 151 460 1786 209 460 1787 202 461 1788 199 461 1789 259 461 1790 205 462 1791 194 462 1792 263 462 1793 197 463 1794 196 463 1795 257 463 1796 170 464 1797 171 464 1798 223 464 1799 196 465 1800 195 465 1801 256 465 1802 204 466 1803 192 466 1804 251 466 1805 156 467 1806 153 467 1807 229 467 1808 190 468 1809 191 468 1810 253 468 1811 165 469 1812 167 469 1813 215 469 1814 191 470 1815 205 470 1816 252 470 1817 183 471 1818 207 471 1819 268 471 1820 160 472 1821 158 472 1822 234 472 1823 179 473 1824 178 473 1825 239 473 1826 180 111 1827 182 111 1828 242 111 1829 201 474 1830 198 474 1831 258 474 1832 163 54 1833 161 54 1834 235 54 1835 185 475 1836 186 475 1837 243 475 1838 162 476 1839 166 476 1840 216 476 1841 189 477 1842 185 477 1843 267 477 1844 206 478 1845 193 478 1846 248 478 1847 195 479 1848 201 479 1849 264 479 1850 182 480 1851 179 480 1852 246 480 1853 188 481 1854 189 481 1855 247 481 1856 193 482 1857 187 482 1858 249 482 1859 192 122 1860 190 122 1861 254 122 1862 172 483 1863 173 483 1864 227 483 1865 186 124 1866 208 124 1867 244 124 1868 151 484 1869 150 484 1870 212 484 1871 203 485 1872 206 485 1873 266 485 1874 177 486 1875 176 486 1876 226 486 1877 178 487 1878 183 487 1879 240 487 1880 169 488 1881 170 488 1882 219 488 1883 153 489 1884 154 489 1885 213 489 1886 152 490 1887 149 490 1888 210 490 1889 187 491 1890 188 491 1891 250 491 1892 174 492 1893 172 492 1894 221 492 1895 166 438 1896 165 438 1897 214 438 1898 155 493 1899 156 493 1900 231 493 1901 176 494 1902 184 494 1903 228 494 1904 181 495 1905 180 495 1906 241 495 1907 158 496 1908 157 496 1909 232 496 1910 168 497 1911 169 497 1912 220 497 1913 175 498 1914 177 498 1915 224 498 1916 159 499 1917 160 499 1918 233 499 1919 184 500 1920 204 500 1921 265 500 1922 194 501 1923 197 501 1924 255 501 1925 208 143 1926 181 143 1927 245 143 1928 274 502 1929 269 502 1930 272 502 1931 277 6 1932 276 6 1933 271 6 1934 343 503 1935 342 503 1936 17 503 1937 273 147 1938 272 147 1939 270 147 1940 270 147 1941 277 147 1942 278 147 1943 278 147 1944 275 147 1945 270 147 1946 12 534 2049 24 534 2050 1 534 2051 24 535 2052 340 535 2053 21 535 2054 269 170 2055 274 170 2056 271 170 2057 338 537 2067 337 537 2068 15 537 2069 278 538 2070 271 538 2071 3 538 2072 271 539 2073 338 539 2074 3 539 2075 3 540 2076 7 540 2077 278 540 2078 21 542 2082 338 542 2083 271 542 2084 274 543 2085 273 543 2086 1 543 2087 273 544 2088 339 544 2089 5 544 2090 1 545 2091 273 545 2092 5 545 2093

-
- - - - -

23 171 525 273 171 526 275 171 527 340 174 534 338 174 535 21 174 536 23 536 2058 339 536 2059 273 536 2060 275 173 2061 278 173 2062 23 173 2063 278 173 2064 344 173 2065 23 173 2066 340 541 2079 337 541 2080 338 541 2081

-
-
-
- - - - -0.04859954 0.7272743 0.823 0.05140036 0.7272743 0.823 0.05140036 0.7272743 0.684 -0.04859954 0.7272743 0.684 -0.04859954 0.6102742 0.684 -0.04859954 0.6102742 0.823 0.05140036 0.6102742 0.684 0.05140036 0.6102742 0.823 -0.04809957 0.3322743 1.920057 -0.0390892 0.339264 1.920057 -0.0390892 0.425264 1.920057 0.04691076 0.339264 1.920057 0.05590039 0.3322743 1.920057 0.04691076 0.425264 1.920057 0.05590039 0.5572742 1.920057 -0.04809957 0.5572742 1.920057 -0.04809957 0.3322743 1.785057 -0.125 0.3302742 1.828173 0.125 0.3302742 1.828173 -0.1160995 0.5572742 1.785057 0.1239004 0.5572742 1.785057 0.1264004 0.5982744 1.828173 0.1239004 0.4472743 1.785057 -0.04166346 0.7270793 0.718064 -0.04166346 0.7270793 0.8040639 0.05590039 0.4472743 1.785057 0.05590039 0.3322743 1.785057 -0.04809957 0.4472743 1.785057 -0.1160995 0.4472743 1.785057 -0.1235995 0.5982744 1.828173 -0.1160995 0.4472743 1.805057 -0.04809957 0.4472743 1.805057 0.1239004 0.4472743 1.805057 0.05590039 0.4472743 1.805057 -0.04809957 0.5572742 1.805057 -0.1160995 0.5572742 1.805057 0.05590039 0.5572742 1.805057 0.1239004 0.5572742 1.805057 -0.1385996 0.3832742 0.731 -0.1385996 -0.2117256 0.731 0.1414004 -0.2117256 0.731 0.1414004 0.3832742 0.731 0.1594004 0.5882744 0.721 0.2314004 0.5882744 0.681 0.2314004 0.5882744 0.651 -0.1565995 0.5882744 0.721 -0.1235995 0.5882744 0.8711729 -0.2285996 0.5882744 0.651 -0.2285996 0.5882744 0.681 -0.1235995 0.5882744 1.808173 0.1264004 0.5882744 1.808173 0.1264004 0.5882744 0.8711729 -0.2285996 -0.2117256 0.681 -0.2285996 -0.2117256 0.651 0.2314004 -0.2117256 0.651 0.2314004 -0.2117256 0.681 -0.1565995 0.3832742 0.721 0.1594004 0.3832742 0.721 0.125 0.3782743 0.951173 0.1264004 0.3782743 0.890173 0.1264004 0.3832742 0.8711729 0.1264004 0.3832742 0.890173 0.1264004 0.5982744 1.808173 -0.1235995 0.5982744 1.808173 -0.1235995 0.3782743 0.890173 -0.1235995 0.3782743 0.951173 -0.1235995 0.3832742 0.890173 -0.1235995 0.3832742 0.8711729 -0.125 0.3302742 0.951173 0.125 0.3302742 0.951173 -0.0390892 0.339264 2.085057 0.04691076 0.339264 2.085057 -0.0390892 0.425264 2.085057 0.04691076 0.425264 2.085057 0.1621006 0.4455419 0.795 0.1621006 -0.1494579 0.795 -0.1578993 -0.1494579 0.795 -0.1578993 0.4455419 0.795 -0.1565995 0.4455419 0.795 0.1621006 0.4455419 0.845 0.1621006 -0.198458 0.845 0.1621006 -0.1494579 0.7705 0.1621006 -0.198458 0.7705 -0.1578993 -0.1494579 0.7705 -0.1578993 -0.198458 0.7705 -0.1578993 -0.198458 0.845 -0.1578993 0.4455419 0.845 0.04433643 0.7270793 0.8040639 0.04433643 0.7270793 0.718064 -0.04166346 0.8530792 0.8040639 0.04433643 0.8530792 0.8040639 -0.04166346 0.8530792 0.718064 0.04433643 0.8530792 0.718064 - - - - - - - - - - 0 0 1 0 0 -1 0 1 8.84168e-7 0 -1 0 -1 0 0 -0.4856434 0 0.8741571 0 1 -7.16403e-6 1 0 0 0 1 0 0.4856413 0 0.8741583 -0.999985 0.005326807 -0.001305222 0.999983 -0.0052253 0.00261265 0 1 1.35333e-6 -1 1.27561e-7 0 0 1 -5.32185e-6 -0.4856438 0 0.8741569 -0.4856437 0 0.8741569 -0.4856416 0 0.8741581 0 1 4.65662e-6 1 0 0 0 -1 0 0.4856436 0 0.8741569 0.4856433 0 0.874157 0.4856434 0 0.8741571 -1 0 0 -0.9995747 0.02916258 0 -0.999983 0.00522536 -0.00261265 0 1 -9.25538e-7 0 1 2.02095e-6 0.9997367 0 0.02295124 0.9997304 0.002143442 0.02312701 0.9999778 -0.006668508 0 0.9999852 -0.005451023 -2.98345e-4 1 2.55121e-7 0 - - - - - - - - - - 0.6288605 0.9097533 0.6282742 0.9071835 0.6229379 0.9097533 0.8381606 0.664284 0.8365315 0.6235561 0.8381606 0.6235561 0.5539344 0.5972073 0.602482 0.5955782 0.6054144 0.5972073 0.6288605 0.8020199 0.6227855 0.7959449 0.6288605 0.7959449 0.4724853 0.7832508 0.4709771 0.7835606 0.4715764 0.7826516 0.6227855 0.8028768 0.6288605 0.8089518 0.6227855 0.8089518 0.4715764 0.7826516 0.4734486 0.7878549 0.4724853 0.7832508 0.5422049 0.7723369 0.6171441 0.642008 0.6171441 0.7723369 0.5238993 0.6754048 0.5238993 0.642008 0.5373175 0.642008 0.5568668 0.5955782 0.602482 0.498646 0.602482 0.5955782 0.63892 0.6642839 0.6467398 0.6237843 0.6467398 0.664512 0.6288605 0.8583313 0.6227855 0.8644063 0.6227855 0.8583313 0.6288605 0.8652632 0.6227855 0.8713383 0.6227855 0.8652632 0.4709771 0.7835606 0.4725396 0.7872557 0.4715764 0.7826516 0.6288605 0.7890124 0.6227855 0.7950884 0.6227855 0.7890124 0.6232472 0.9229907 0.6288605 0.9229907 0.6272168 0.9190225 0.4734486 0.7878549 0.4709771 0.7929179 0.4724853 0.7832508 0.4740478 0.7869458 0.4725396 0.7872557 0.4731386 0.7863467 0.6277573 0.9126703 0.6241869 0.9126703 0.6230837 0.9160671 0.6389201 0.5811803 0.6488576 0.5406805 0.6488577 0.5814084 0.5539344 0.5972073 0.6054144 0.6306042 0.5539344 0.6306043 0.6527675 0.5814084 0.6861643 0.5406805 0.6861643 0.5814084 0.6288605 0.8158838 0.6227855 0.8098087 0.6288605 0.8098087 0.6171441 0.7723369 0.6220314 0.642008 0.6220314 0.7723369 0.4704062 0.7647963 0.4445917 0.7647963 0.4445917 0.7603068 0.4740478 0.7869458 0.4709771 0.7835606 0.471886 0.7841598 0.8365315 0.6235561 0.8332733 0.664284 0.8332733 0.6235561 0.6288605 0.8436114 0.6227855 0.837536 0.6288605 0.837536 0.6288605 0.8929901 0.6227855 0.8990651 0.6227855 0.8929901 0.602482 0.7853699 0.5568668 0.7853699 0.5422049 0.7723369 0.6288605 0.8505429 0.6227855 0.8444679 0.6288605 0.8444679 0.6354496 0.6754048 0.6388041 0.6754048 0.6388041 0.7723369 0.5373175 0.7723369 0.5422048 0.642008 0.5422049 0.7723369 0.6488576 0.5406805 0.6496722 0.5814084 0.6488577 0.5814084 0.6496722 0.5814084 0.6527674 0.5406805 0.6527675 0.5814084 0.7478262 0.7697057 0.7398436 0.7175741 0.7478262 0.7175741 0.7358522 0.7175741 0.7398436 0.7697057 0.7358522 0.7697057 0.6467398 0.6237843 0.789613 0.6645121 0.6467398 0.664512 0.8388122 0.5406803 0.6991971 0.5064691 0.8420705 0.4986486 0.4709771 0.7537969 0.4902818 0.7344923 0.4902818 0.7537969 0.6054144 0.6306042 0.6171441 0.6371206 0.6171441 0.642008 0.8388123 0.5814082 0.8420705 0.579779 0.8420705 0.6234399 0.6288605 0.9025522 0.6273419 0.8999215 0.6243045 0.8999215 0.6288605 0.8791267 0.6227855 0.8852017 0.6227855 0.8791267 0.6288605 0.8721952 0.6227855 0.8782702 0.6227855 0.8721952 0.6288605 0.8574749 0.6227855 0.8513998 0.6288605 0.8513998 0.7478262 0.7175741 0.7599632 0.7697057 0.7478262 0.7697057 0.6755751 0.6727735 0.7274949 0.6646279 0.7277067 0.6727735 0.6674295 0.7697057 0.6755751 0.6727735 0.6755751 0.7776883 0.7277066 0.7776885 0.6755751 0.6727735 0.7277067 0.6727735 0.7277066 0.7776885 0.7358522 0.7697057 0.7398436 0.7776885 0.7358522 0.7175741 0.63892 0.7694939 0.63892 0.7175741 0.789613 0.6237843 0.8332733 0.664284 0.789613 0.6645121 0.6861643 0.5406805 0.8388123 0.5814082 0.6861643 0.5814084 0.4198996 0.8034058 0.4198996 0.749532 0.4445917 0.7647963 0.6227855 0.8228157 0.6288605 0.8167406 0.6288605 0.8228157 0.6227855 0.8297476 0.6288605 0.8236725 0.6288605 0.8297476 0.6227855 0.8366795 0.6288605 0.830604 0.6288605 0.8366795 0.6288605 0.8860582 0.6227855 0.8921332 0.6227855 0.8860582 0.4902818 0.7537969 0.4709771 0.7820808 0.4709771 0.7537969 0.6229379 0.9097533 0.6245808 0.9118139 0.6288605 0.9097533 0.6245808 0.9118139 0.6272181 0.9118139 0.6288605 0.9097533 0.6282742 0.9071835 0.6258994 0.9060398 0.6235252 0.9071835 0.6282742 0.9071835 0.6235252 0.9071835 0.6229379 0.9097533 0.8381606 0.664284 0.8365316 0.664284 0.8365315 0.6235561 0.5539344 0.5972073 0.5568668 0.5955782 0.602482 0.5955782 0.6288605 0.8020199 0.6227855 0.8020199 0.6227855 0.7959449 0.4724853 0.7832508 0.471886 0.7841598 0.4709771 0.7835606 0.6227855 0.8028768 0.6288605 0.8028768 0.6288605 0.8089518 0.4715764 0.7826516 0.4725396 0.7872557 0.4734486 0.7878549 0.5422049 0.7723369 0.5422048 0.642008 0.6171441 0.642008 0.5373175 0.642008 0.5373175 0.7723369 0.5238993 0.6754048 0.5373175 0.7723369 0.5205448 0.7723369 0.5238993 0.6754048 0.5205448 0.7723369 0.5205448 0.6754048 0.5238993 0.6754048 0.5568668 0.5955782 0.5568668 0.498646 0.602482 0.498646 0.63892 0.6642839 0.63892 0.6237843 0.6467398 0.6237843 0.6288605 0.8583313 0.6288605 0.8644064 0.6227855 0.8644063 0.6288605 0.8652632 0.6288605 0.8713383 0.6227855 0.8713383 0.4709771 0.7835606 0.4712408 0.7937272 0.4725396 0.7872557 0.6288605 0.7890124 0.6288605 0.7950884 0.6227855 0.7950884 0.6272168 0.9190225 0.6248909 0.9190225 0.6232472 0.9229907 0.6248909 0.9190225 0.6232472 0.9206662 0.6232472 0.9229907 0.6232472 0.9229907 0.624891 0.9246354 0.6272168 0.9246354 0.6288605 0.9229907 0.6288605 0.9206662 0.6272168 0.9190225 0.6232472 0.9229907 0.6272168 0.9246354 0.6288605 0.9229907 0.4734486 0.7878549 0.4740478 0.7869458 0.4709771 0.7929179 0.4740478 0.7869458 0.4734486 0.7878549 0.4725396 0.7872557 0.6259717 0.9181656 0.6288605 0.9160671 0.6230837 0.9160671 0.6288605 0.9160671 0.6277573 0.9126703 0.6230837 0.9160671 0.6389201 0.5811803 0.63892 0.5406806 0.6488576 0.5406805 0.5539344 0.5972073 0.6054144 0.5972073 0.6054144 0.6306042 0.6527675 0.5814084 0.6527674 0.5406805 0.6861643 0.5406805 0.6288605 0.8158838 0.6227855 0.8158838 0.6227855 0.8098087 0.6171441 0.7723369 0.6171441 0.642008 0.6220314 0.642008 0.4198996 0.7603068 0.4198996 0.7344923 0.4445917 0.7603068 0.4198996 0.7344923 0.4704062 0.7344923 0.4445917 0.7603068 0.4704062 0.7344923 0.4704062 0.7647963 0.4445917 0.7603068 0.4740478 0.7869458 0.4712408 0.7937272 0.4709771 0.7835606 0.8365315 0.6235561 0.8365316 0.664284 0.8332733 0.664284 0.6288605 0.8436114 0.6227855 0.8436114 0.6227855 0.837536 0.6288605 0.8929901 0.6288605 0.8990651 0.6227855 0.8990651 0.5422049 0.7772244 0.5422049 0.7723369 0.5568668 0.7853699 0.5422049 0.7723369 0.6171441 0.7723369 0.602482 0.7853699 0.6171441 0.7723369 0.6171441 0.7772244 0.602482 0.7853699 0.6288605 0.8505429 0.6227855 0.8505429 0.6227855 0.8444679 0.6388041 0.7723369 0.6220314 0.7723369 0.6354496 0.6754048 0.6220314 0.7723369 0.6220314 0.642008 0.6354496 0.6754048 0.6220314 0.642008 0.6354496 0.642008 0.6354496 0.6754048 0.5373175 0.7723369 0.5373175 0.642008 0.5422048 0.642008 0.6488576 0.5406805 0.6496722 0.5406805 0.6496722 0.5814084 0.6496722 0.5814084 0.6496722 0.5406805 0.6527674 0.5406805 0.7478262 0.7697057 0.7398436 0.7697057 0.7398436 0.7175741 0.7358522 0.7175741 0.7398436 0.7175741 0.7398436 0.7697057 0.6467398 0.6237843 0.789613 0.6237843 0.789613 0.6645121 0.8388122 0.5406803 0.6861643 0.5406805 0.6991971 0.5064691 0.6861643 0.5406805 0.6861642 0.5072837 0.6892596 0.5072837 0.6892596 0.5072837 0.6892596 0.5064691 0.6991971 0.5064691 0.6861643 0.5406805 0.6892596 0.5072837 0.6991971 0.5064691 0.8420704 0.5423094 0.8388122 0.5423094 0.8388122 0.5406803 0.6991971 0.5064691 0.6991973 0.498646 0.8420705 0.4986486 0.8420705 0.4986486 0.8420704 0.5423094 0.8388122 0.5406803 0.4709771 0.7537969 0.4709771 0.7344923 0.4902818 0.7344923 0.6171441 0.642008 0.5422048 0.642008 0.6054144 0.6306042 0.5422048 0.642008 0.5422048 0.6371206 0.5539344 0.6306043 0.6054144 0.6306042 0.5422048 0.642008 0.5539344 0.6306043 0.8420705 0.6234399 0.6991973 0.6234402 0.6991973 0.6156204 0.6991973 0.6156204 0.6892571 0.61562 0.6892571 0.6148055 0.6892571 0.6148055 0.6861618 0.6148052 0.6861643 0.5814084 0.8388123 0.5814082 0.8388123 0.579779 0.8420705 0.579779 0.6892571 0.6148055 0.6861643 0.5814084 0.6991973 0.6156204 0.6861643 0.5814084 0.8388123 0.5814082 0.6991973 0.6156204 0.8420705 0.6234399 0.6991973 0.6156204 0.8388123 0.5814082 0.6243045 0.8999215 0.6227855 0.9025522 0.6288605 0.9025522 0.6227855 0.9025522 0.6243046 0.9051828 0.6288605 0.9025522 0.6243046 0.9051828 0.6273419 0.9051828 0.6288605 0.9025522 0.6288605 0.8791267 0.6288605 0.8852017 0.6227855 0.8852017 0.6288605 0.8721952 0.6288605 0.8782702 0.6227855 0.8782702 0.6288605 0.8574749 0.6227855 0.8574749 0.6227855 0.8513998 0.7478262 0.7175741 0.7599631 0.7175741 0.7599632 0.7697057 0.6755751 0.6727735 0.6755751 0.6646279 0.7274949 0.6646279 0.6634382 0.7776885 0.6634382 0.7697057 0.6674295 0.7697057 0.6674295 0.7697057 0.6674295 0.6727734 0.6755751 0.6727735 0.6755751 0.7776883 0.6634382 0.7776885 0.6674295 0.7697057 0.7277066 0.7776885 0.6755751 0.7776883 0.6755751 0.6727735 0.7277066 0.7776885 0.7277067 0.6727735 0.7358522 0.7697057 0.7277067 0.6727735 0.7358522 0.6727734 0.7358522 0.7697057 0.7358522 0.7697057 0.7398436 0.7697057 0.7398436 0.7776885 0.7358522 0.7175741 0.7358522 0.7697057 0.63892 0.7694939 0.789613 0.6237843 0.8332733 0.6235561 0.8332733 0.664284 0.6861643 0.5406805 0.8388122 0.5406803 0.8388123 0.5814082 0.4445917 0.7647963 0.4704062 0.7647963 0.4704062 0.7881416 0.4445917 0.7881416 0.4445917 0.8034058 0.4198996 0.8034058 0.4445917 0.7647963 0.4704062 0.7881416 0.4445917 0.7881416 0.4198996 0.749532 0.4445917 0.749532 0.4445917 0.7647963 0.4445917 0.7881416 0.4198996 0.8034058 0.4445917 0.7647963 0.6227855 0.8228157 0.6227855 0.8167406 0.6288605 0.8167406 0.6227855 0.8297476 0.6227855 0.8236726 0.6288605 0.8236725 0.6227855 0.8366795 0.6227855 0.830604 0.6288605 0.830604 0.6288605 0.8860582 0.6288605 0.8921332 0.6227855 0.8921332 0.4902818 0.7537969 0.4902818 0.7820808 0.4709771 0.7820808 - - - - - - - - - - - - -

78 77

-
- - - - -

8 0 0 12 0 1 9 0 2 49 1 3 62 1 4 50 1 5 56 2 6 41 2 7 57 2 8 27 3 9 30 3 10 28 3 11 5 4 12 3 4 13 4 4 14 12 3 15 16 3 16 26 3 17 4 3 18 7 3 19 5 3 20 53 1 21 44 1 22 54 1 23 56 5 24 45 5 25 48 5 26 38 0 27 40 0 28 41 0 29 65 1 30 69 1 31 68 1 32 9 4 33 72 4 34 10 4 35 30 0 36 34 0 37 35 0 38 3 1 39 6 1 40 4 1 41 11 3 42 70 3 43 9 3 44 34 6 45 36 6 46 20 6 47 7 0 48 0 0 49 5 0 50 1 7 51 6 7 52 2 7 53 13 0 54 12 0 55 14 0 56 58 3 57 64 3 58 59 3 59 56 0 60 42 0 61 45 0 62 60 1 63 46 1 64 51 1 65 73 0 66 70 0 67 71 0 68 54 7 69 43 7 70 55 7 71 26 7 72 25 7 73 33 7 74 1 8 75 3 8 76 0 8 77 62 8 78 29 8 79 21 8 80 33 3 81 22 3 82 32 3 83 30 4 84 19 4 85 28 4 86 40 3 87 39 3 88 53 3 89 13 7 90 71 7 91 11 7 92 57 9 93 41 9 94 40 9 95 52 4 96 47 4 97 53 4 98 64 1 99 61 1 100 59 1 101 61 3 102 67 3 103 60 3 104 84 1 105 81 1 106 82 1 107 75 8 108 83 8 109 76 8 110 69 3 111 17 3 112 68 3 113 49 10 114 65 10 115 17 10 116 88 3 117 24 3 118 23 3 119 42 8 120 43 8 121 44 8 122 50 11 123 21 11 124 18 11 125 31 4 126 27 4 127 16 4 128 37 7 129 22 7 130 20 7 131 37 0 132 33 0 133 32 0 134 10 8 135 73 8 136 13 8 137 82 3 138 85 3 139 84 3 140 79 12 141 78 12 142 86 12 143 75 7 144 79 7 145 80 7 146 85 0 147 79 0 148 86 0 149 85 13 150 76 13 151 84 13 152 75 1 153 78 1 154 74 1 155 18 0 156 29 0 157 17 0 158 46 8 159 50 8 160 51 8 161 19 1 162 20 1 163 25 1 164 87 0 165 89 0 166 24 0 167 88 7 168 90 7 169 87 7 170 92 8 171 89 8 172 90 8 173 24 4 174 91 4 175 23 4 176 23 1 177 92 1 178 88 1 179 9 0 180 10 0 181 8 0 182 10 0 183 15 0 184 8 0 185 12 0 186 13 0 187 11 0 188 12 0 189 11 0 190 9 0 191 49 1 192 63 1 193 62 1 194 56 14 195 38 14 196 41 14 197 27 3 198 31 3 199 30 3 200 5 4 201 0 4 202 3 4 203 12 3 204 8 3 205 16 3 206 4 3 207 6 3 208 7 3 209 53 1 210 47 1 211 44 1 212 48 15 213 52 15 214 56 15 215 52 16 216 39 16 217 56 16 218 39 17 219 38 17 220 56 17 221 38 0 222 39 0 223 40 0 224 65 1 225 58 1 226 69 1 227 9 4 228 70 4 229 72 4 230 30 0 231 31 0 232 34 0 233 3 1 234 2 1 235 6 1 236 11 3 237 71 3 238 70 3 239 20 18 240 19 18 241 34 18 242 19 8 243 35 8 244 34 8 245 34 8 246 15 8 247 14 8 248 36 8 249 37 8 250 20 8 251 34 8 252 14 8 253 36 8 254 7 0 255 1 0 256 0 0 257 1 7 258 7 7 259 6 7 260 15 0 261 10 0 262 14 0 263 10 0 264 13 0 265 14 0 266 58 3 267 65 3 268 64 3 269 56 0 270 57 0 271 42 0 272 60 1 273 67 1 274 46 1 275 73 0 276 72 0 277 70 0 278 54 7 279 44 7 280 43 7 281 36 7 282 14 7 283 33 7 284 14 7 285 12 7 286 33 7 287 12 19 288 26 19 289 33 19 290 1 8 291 2 8 292 3 8 293 62 8 294 63 8 295 29 8 296 33 3 297 25 3 298 22 3 299 30 4 300 35 4 301 19 4 302 52 3 303 53 3 304 39 3 305 53 20 306 54 20 307 40 20 308 54 3 309 55 3 310 40 3 311 13 7 312 73 7 313 71 7 314 40 21 315 55 21 316 57 21 317 55 22 318 43 22 319 57 22 320 43 23 321 42 23 322 57 23 323 52 4 324 48 4 325 47 4 326 64 1 327 66 1 328 61 1 329 61 3 330 66 3 331 67 3 332 84 1 333 83 1 334 81 1 335 75 8 336 81 8 337 83 8 338 69 3 339 18 3 340 17 3 341 49 24 342 46 24 343 65 24 344 46 4 345 67 4 346 66 4 347 66 4 348 64 4 349 65 4 350 46 4 351 66 4 352 65 4 353 29 4 354 63 4 355 49 4 356 65 25 357 68 25 358 17 25 359 17 26 360 29 26 361 49 26 362 88 3 363 87 3 364 24 3 365 44 27 366 47 27 367 42 27 368 47 8 369 48 8 370 45 8 371 42 28 372 47 28 373 45 28 374 18 7 375 69 7 376 58 7 377 58 29 378 59 29 379 61 29 380 61 7 381 60 7 382 51 7 383 50 7 384 62 7 385 21 7 386 61 30 387 51 30 388 58 30 389 51 31 390 50 31 391 58 31 392 18 32 393 58 32 394 50 32 395 16 4 396 8 4 397 31 4 398 8 4 399 15 4 400 31 4 401 15 4 402 34 4 403 31 4 404 37 7 405 32 7 406 22 7 407 37 0 408 36 0 409 33 0 410 10 8 411 72 8 412 73 8 413 82 3 414 80 3 415 85 3 416 79 8 417 74 8 418 78 8 419 82 7 420 81 7 421 75 7 422 75 7 423 74 7 424 79 7 425 80 33 426 82 33 427 75 33 428 85 0 429 80 0 430 79 0 431 85 4 432 86 4 433 76 4 434 86 4 435 77 4 436 76 4 437 76 4 438 83 4 439 84 4 440 75 1 441 76 1 442 78 1 443 18 0 444 21 0 445 29 0 446 46 8 447 49 8 448 50 8 449 25 1 450 26 1 451 16 1 452 27 1 453 28 1 454 19 1 455 25 1 456 16 1 457 27 1 458 20 1 459 22 1 460 25 1 461 27 1 462 19 1 463 25 1 464 87 0 465 90 0 466 89 0 467 88 7 468 92 7 469 90 7 470 92 8 471 91 8 472 89 8 473 24 4 474 89 4 475 91 4 476 23 1 477 91 1 478 92 1 479

-
-
-
- - - - 3.727994 -1.861196 6.468798 3.727994 0.1388037 8.468798 4.18592 -0.4937742 7.694431 5.727994 -1.861196 6.468798 5.727994 0.1388037 8.468798 3.727994 -0.8124906 8.468798 3.727994 -1.861196 7.646958 5.281291 -0.4937742 7.694431 5.727994 -0.8124906 8.468798 5.727994 -1.861196 7.646958 3.727994 -0.8665385 6.468798 3.727994 -0.8665385 7.079332 3.727994 -0.8423045 7.194181 3.727994 0.1388037 7.309332 3.727994 -0.6851414 7.309332 3.727994 -0.775721 7.278604 5.727994 0.1388037 7.309332 5.727994 -0.8665385 6.468798 5.727994 -0.8665385 7.079332 5.727994 -0.8423045 7.194181 5.727994 -0.6851414 7.309332 5.727994 -0.775721 7.278604 5.281291 -0.4937742 8.468798 4.18592 -0.8124906 8.468798 5.281291 -0.8124906 8.468798 4.18592 -0.4937742 8.468798 4.18592 -1.800619 7.694431 5.281291 -1.800619 7.694431 -21.3446 1.124289 13.34136 -21.3446 1.762395 13.34136 -21.3446 1.124287 -18.44267 6.414961 1.124289 13.34136 6.414961 1.762389 13.34136 6.414968 1.124287 -18.44267 6.414961 1.762389 -18.44268 -21.3446 1.762391 -18.44268 4.397377 1.124289 10.68454 4.435418 1.124289 10.40445 4.284427 1.124287 -14.30868 -17.73867 1.124287 -14.80351 3.849709 1.124287 -14.80351 4.100013 1.124287 -14.56858 4.397374 1.124287 -14.03167 -17.07256 1.124288 -15.17084 3.183602 1.124287 -15.17084 2.366617 1.124287 -15.36625 -15.82079 1.124287 -15.39126 1.931838 1.124287 -15.39126 -16.25558 1.124287 -15.36625 -17.43004 1.124287 -15.00634 -16.67708 1.124287 -15.29203 2.788122 1.124287 -15.29203 3.541083 1.124287 -15.00634 4.435416 1.124287 -13.74594 -15.82079 1.124289 12.01729 1.931841 1.124289 12.01729 -16.25557 1.124289 11.99278 2.366621 1.124288 11.99278 2.788125 1.124289 11.92002 3.183606 1.124289 11.80122 -17.43004 1.124289 11.63997 -17.07255 1.124289 11.80122 3.635648 1.124289 11.57905 3.541087 1.124289 11.63997 -16.67708 1.124289 11.92002 3.849712 1.124288 11.44115 4.100017 1.124288 11.21085 -18.17338 1.124289 10.95608 -17.98897 1.124289 11.21086 4.284431 1.124289 10.95608 -18.17339 1.124288 -14.30868 -17.98897 1.124287 -14.56858 -18.32437 1.124288 -13.74594 -18.28633 1.124288 -14.03167 -18.28633 1.124289 10.68454 -18.32437 1.124289 10.40445 -17.73867 1.124289 11.44114 -18.28633 1.762391 -14.03167 -17.98897 1.762391 -14.56858 -17.43004 1.762391 -15.00634 -17.73867 1.762391 -14.80351 -18.17339 1.762391 -14.30868 -16.67708 1.762391 -15.29203 2.788122 1.762389 -15.29203 -15.82079 1.762391 -15.39126 1.931838 1.76239 -15.39126 -16.25558 1.762391 -15.36626 2.366617 1.762389 -15.36625 -17.07256 1.762391 -15.17084 3.183602 1.76239 -15.17084 -18.32437 1.762392 -13.74594 -15.82079 1.762394 12.01729 1.931841 1.76239 12.01729 2.788125 1.762391 11.92002 -16.67708 1.762394 11.92002 -16.25557 1.762394 11.99278 2.366621 1.76239 11.99278 -17.07255 1.762394 11.80122 -17.73867 1.762395 11.44114 3.849712 1.762389 11.44115 3.640528 1.76239 11.5759 -17.43004 1.762394 11.63997 3.541087 1.76239 11.63997 3.183606 1.762391 11.80122 4.100017 1.76239 11.21085 -18.17338 1.762395 10.95608 4.28443 1.76239 10.95608 -18.28633 1.762395 10.68454 4.397376 1.76239 10.68454 4.284427 1.762389 -14.30868 4.397373 1.762389 -14.03167 3.541083 1.762389 -15.00634 3.849709 1.762389 -14.80351 4.100013 1.76239 -14.56858 4.435415 1.762389 -13.74594 -18.32437 1.762395 10.40445 -17.98897 1.762394 11.21085 4.435418 1.76239 10.40445 4.494221 0.1844011 8.676043 4.494221 0.1844011 -6.584051 4.494221 1.115921 8.676043 4.494221 1.115921 -6.584051 6.339184 0.1844011 8.676043 6.339184 0.1844011 -6.584051 6.339184 1.115921 8.676043 6.339184 1.115921 -6.584051 4.684525 -0.9721969 6.476446 4.684525 -0.9721969 -4.418558 4.848804 -0.979794 6.476446 4.848804 -0.979794 -4.418558 5.006771 -1.002294 6.476446 5.006771 -1.002294 -4.418558 5.152354 -1.038831 6.476446 5.152354 -1.038831 -4.418558 5.279959 -1.088002 6.476446 5.279959 -1.088002 -4.418558 5.384681 -1.147917 6.476446 5.384681 -1.147917 -4.418558 5.462497 -1.216274 6.476446 5.462497 -1.216274 -4.418558 5.510416 -1.290445 6.476446 5.510416 -1.290445 -4.418558 5.526596 -1.36758 6.476446 5.526596 -1.36758 -4.418558 5.510416 -1.444716 6.476446 5.510416 -1.444716 -4.418558 5.462497 -1.518887 6.476446 5.462497 -1.518887 -4.418558 5.384681 -1.587243 6.476446 5.384681 -1.587243 -4.418558 5.279959 -1.647158 6.476446 5.279959 -1.647158 -4.418558 5.152354 -1.696329 6.476446 5.152354 -1.696329 -4.418558 5.006771 -1.732867 6.476446 5.006771 -1.732867 -4.418558 4.848804 -1.755366 6.476446 4.848804 -1.755366 -4.418558 4.684525 -1.762964 6.476446 4.684525 -1.762964 -4.418558 4.520244 -1.755366 6.476446 4.520244 -1.755366 -4.418558 4.362277 -1.732867 6.476446 4.362277 -1.732867 -4.418558 4.216694 -1.696329 6.476446 4.216694 -1.696329 -4.418558 4.089089 -1.647158 6.476446 4.089089 -1.647158 -4.418558 3.984367 -1.587243 6.476446 3.984367 -1.587243 -4.418558 3.906551 -1.518887 6.476446 3.906551 -1.518887 -4.418558 3.858633 -1.444716 6.476446 3.858633 -1.444716 -4.418558 3.842453 -1.36758 6.476446 3.842453 -1.36758 -4.418558 3.858633 -1.290445 6.476446 3.858633 -1.290445 -4.418558 3.906551 -1.216274 6.476446 3.906551 -1.216274 -4.418558 3.984367 -1.147917 6.476446 3.984367 -1.147917 -4.418558 4.089089 -1.088002 6.476446 4.089089 -1.088002 -4.418558 4.216694 -1.038831 6.476446 4.216694 -1.038831 -4.418558 4.362277 -1.002294 6.476446 4.362277 -1.002294 -4.418558 4.520244 -0.979794 6.476446 4.520244 -0.979794 -4.418558 3.727994 -1.861196 -4.415396 3.727994 0.1388037 -6.415396 4.18592 -0.4937742 -5.641028 5.727994 -1.861196 -4.415396 5.727994 0.1388037 -6.415396 3.727994 -0.8124906 -6.415396 3.727994 -1.861196 -5.593556 5.281291 -0.4937742 -5.641028 5.727994 -0.8124906 -6.415396 5.727994 -1.861196 -5.593556 3.727994 -0.8665385 -4.415396 3.727994 -0.8665385 -5.02593 3.727994 -0.8423045 -5.140779 3.727994 0.1388037 -5.25593 3.727994 -0.6851414 -5.25593 3.727994 -0.775721 -5.225203 5.727994 0.1388037 -5.25593 5.727994 -0.8665385 -4.415396 5.727994 -0.8665385 -5.02593 5.727994 -0.8423045 -5.140779 5.727994 -0.6851414 -5.25593 5.727994 -0.775721 -5.225203 5.281291 -0.4937742 -6.415396 4.18592 -0.8124906 -6.415396 5.281291 -0.8124906 -6.415396 4.18592 -0.4937742 -6.415396 4.18592 -1.800619 -5.641028 5.281291 -1.800619 -5.641028 - - - - - - - - - - -1 -2.73574e-7 0 0 1 0 1 -1.53931e-6 0 0 -1 0 0 0 -1 0 0 1 0 -0.6168245 0.7871007 0 0.3212496 -0.9469946 0 0.7851837 -0.6192631 0 0.978455 -0.2064605 1 0 0 -1 0 0 0 4.48362e-6 1 -1 -6.01877e-6 -1.20019e-7 0 -1 0 0 -1 1.62288e-7 1 1.11432e-5 0 0 -8.96726e-6 -1 5.18076e-7 1 6.62836e-7 2.28311e-7 1 0 -1 4.41189e-7 0 1 0 0 0.05628126 3.003e-6 -0.9984151 0.1701017 8.73518e-7 -0.9854266 0.2877038 0 -0.9577195 0.4111741 1.90549e-6 -0.9115568 0.5415656 0 -0.8406586 0.6770756 -2.09744e-6 -0.7359136 0.8100551 -5.17138e-6 -0.5863537 0.9233159 0 -0.3840416 0.9909005 5.28733e-6 -0.1345973 0.05740696 3.07935e-6 0.9983509 0.1734343 0 0.9848455 0.2929975 0 0.9561133 0.4180176 0 0.908439 0.5492108 0 0.835684 0.6843632 -4.35362e-6 0.7291413 0.8155532 0 0.5786823 0.9259889 0 0.3775508 0.9912521 -5.18486e-6 0.1319818 -0.05627858 1.48673e-6 -0.9984152 -0.1701018 0 -0.9854265 -0.2877048 -1.35723e-6 -0.9577192 -0.4111742 0 -0.9115567 -0.5415588 -7.33668e-7 -0.840663 -0.6770778 -1.64777e-6 -0.7359114 -0.8100597 -1.18799e-6 -0.5863474 -0.9233148 -1.27046e-6 -0.3840442 -0.9909026 6.38906e-7 -0.1345816 -0.05740743 0 0.9983509 -0.1734266 0 0.9848469 -0.2929961 0 0.9561137 -0.4180259 0 0.9084352 -0.5492035 0 0.8356887 -0.6843608 0 0.7291436 -0.8155598 0 0.578673 -0.9259876 0 0.3775541 -0.9912528 -1.29623e-6 0.1319764 0 2.98908e-6 -1 0.04619568 0.9989325 0 0.1410092 0.9900083 0 0.2434237 0.9699201 0 0.3595672 0.9331192 0 0.4965986 0.8679803 0 0.6599681 0.7512936 0 0.8399519 0.5426608 0 0.9787015 0.2052886 0 0.9786997 -0.2052971 0 0.8399556 -0.5426552 0 0.6599648 -0.7512966 0 0.4965986 -0.8679803 0 0.3595672 -0.9331192 0 0.2434237 -0.9699201 0 0.1410092 -0.9900083 0 0.04619604 -0.9989325 0 -0.04619604 -0.9989325 0 -0.1410092 -0.9900083 0 -0.2434237 -0.9699201 0 -0.3595672 -0.9331192 0 -0.4965986 -0.8679803 0 -0.6599681 -0.7512936 0 -0.8399556 -0.5426552 0 -0.9787015 -0.2052886 0 -0.9786997 0.2052971 0 -0.8399519 0.5426608 0 -0.6599648 0.7512966 0 -0.4966011 0.8679789 0 -0.3595655 0.9331199 0 -0.2434237 0.9699201 0 -0.1410092 0.9900083 0 -0.0461955 0.9989325 0 1 2.73574e-7 0 0 -0.6168221 -0.7871026 0 0.3212496 0.9469946 0 0.7851819 0.6192652 0 0.978455 0.2064605 -1 -4.06904e-7 0 -1 -1.86275e-6 0 1 -3.73001e-7 0 1 4.06904e-7 0 1 9.31376e-7 0 0 -0.6168265 0.7870991 1.56308e-6 -0.6168261 0.7870995 -1.60235e-6 -0.6168252 0.7871003 0 -0.6168264 0.7870994 0 -0.6168258 0.7870998 0 0.32125 -0.9469944 0 0.7851842 -0.6192623 0 0.9784547 -0.2064616 0 0 1 -1 -6.01244e-6 0 -1.70065e-6 -1 2.31201e-6 0 -1 0 6.51737e-7 -1 7.30208e-7 -1.36724e-6 -1 -1.91067e-6 6.4053e-7 -1 -3.03275e-7 7.47038e-7 -1 -5.62355e-7 1.00609e-6 -1 1.68716e-6 -1.46233e-6 -1 -1.99165e-6 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1.37293e-7 -1 1.60166e-7 0 -1 0 0 -1 3.54433e-7 0 -1 0 0 -1 2.26443e-7 -5.62635e-7 -1 0 0 -1 0 2.49616e-7 -1 0 0 -1 0 0 -1 0 4.48038e-7 -1 5.09339e-7 -2.63855e-7 -1 3.15337e-7 4.37079e-7 -1 0 -4.06653e-7 -1 0 2.29587e-7 -1 5.69541e-7 -2.4069e-7 -1 -2.23906e-7 0 -1 4.14273e-7 0 -1 0 0 -1 0 0 -1 1.37189e-7 0 -1 0 1.83276e-6 -1 -1.41934e-6 -1.71328e-7 -1 0 -1.8979e-7 -1 -6.93929e-7 6.9429e-7 -1 2.92087e-6 1.84894e-7 -1 0 4.02724e-7 -1 -2.21016e-6 0 -1 0 -4.48068e-7 -1 -5.86771e-7 -9.25238e-7 -1 2.78225e-6 1 0 2.10034e-7 0 -8.96729e-6 -1 -5.67645e-7 1 -2.14496e-6 1.05754e-6 1 1.19418e-6 1.2192e-6 1 -1.28323e-6 -8.4968e-7 1 1.7886e-6 6.74844e-7 1 6.5905e-7 -5.2197e-7 1 0 1.23626e-7 1 0 -5.17984e-7 1 5.62354e-7 0 1 -1.39085e-7 0 1 -1.301e-7 3.00725e-7 1 0 4.05264e-7 1 0 9.44221e-7 1 -5.86521e-7 7.32599e-7 1 -6.867e-7 2.05287e-7 1 0 -1.32146e-6 1 -6.40664e-7 -6.21227e-7 1 4.50818e-7 4.93527e-7 1 -2.71231e-7 1.05734e-6 1 4.51081e-7 8.43063e-7 1 3.6231e-7 0 1 0 0 1 -2.54671e-7 -4.99234e-7 1 -6.30088e-7 0 1 0 0 1 5.92197e-7 4.48606e-7 1 -1.21027e-6 5.2771e-7 1 5.60598e-7 -4.11365e-7 1 -5.65788e-7 0 1 0 0 1 6.51059e-7 0 1 0 0 1 0 8.04277e-7 1 1.46336e-6 1.27788e-6 1 -3.0368e-6 8.64686e-7 1 -8.89933e-7 -1.7219e-7 1 -1.53889e-6 0 1 8.54073e-7 1.42626e-7 1 9.60403e-7 -2.92164e-7 1 8.28806e-7 7.95922e-7 1 0 -8.55044e-7 1 -2.68237e-6 2.14718e-7 1 2.07571e-7 0 1 1.39112e-6 -1 -9.90161e-7 0 0 0 1 1 5.65325e-6 0 0.05628144 1.53974e-6 -0.998415 0.1700982 0 -0.9854272 0.2877005 2.33483e-6 -0.9577205 0.411174 1.37223e-6 -0.9115568 0.5415688 2.60508e-6 -0.8406564 0.677082 -4.39408e-6 -0.7359077 0.8100491 4.75194e-6 -0.5863622 0.9233176 0 -0.3840374 0.9909003 0 -0.1345977 0.05740696 0 0.9983509 0.1734334 2.61901e-6 0.9848456 0.2929963 0 0.9561136 0.4180241 0 0.908436 0.5492108 -3.86339e-6 0.835684 0.6843631 0 0.7291414 0.8155521 0 0.5786838 0.9259904 -7.25998e-7 0.3775475 0.991252 0 0.1319832 -0.05627518 0 -0.9984154 -0.1701086 -1.46751e-6 -0.9854254 -0.2877048 0 -0.9577192 -0.4111776 0 -0.9115552 -0.5415547 0 -0.8406656 -0.5415782 -2.96121e-7 -0.8406504 -0.5415646 0 -0.8406592 -0.6770725 0 -0.7359163 -0.8100597 -2.37435e-7 -0.5863475 -0.9233122 -1.27048e-6 -0.3840506 -0.9909021 -2.6437e-6 -0.1345849 -0.05740737 0 0.9983509 -0.173434 0 0.9848456 -0.2929974 0 0.9561133 -0.41802 0 0.9084379 -0.5491979 0 0.8356925 -0.6843639 0 0.7291407 -0.8155586 0 0.5786747 -0.9259859 -1.249e-6 0.3775582 -0.991253 -1.29622e-6 0.1319757 0 1.49455e-6 -1 0.04619568 0.9989325 0 0.2434237 0.9699201 0 0.3595672 0.9331192 0 0.6599648 0.7512966 0 0.8399556 0.5426552 0 0.9786998 0.2052971 0 0.9787015 -0.2052886 0 0.8399519 -0.5426608 0 0.6599681 -0.7512936 0 0.3595672 -0.9331192 0 0.2434237 -0.9699201 0 0.04619604 -0.9989325 0 -0.04619586 -0.9989325 0 -0.2434237 -0.9699201 0 -0.3595654 -0.9331199 0 -0.4966011 -0.8679789 0 -0.6599648 -0.7512966 0 -0.8399519 -0.5426608 0 -0.9786998 -0.2052971 0 -0.9787015 0.2052886 0 -0.8399556 0.5426552 0 -0.6599681 0.7512936 0 -0.4965986 0.8679803 0 -0.3595672 0.9331192 0 -0.2434237 0.9699201 0 -4.98155e-6 0 -1 -6.68299e-6 0 -1 -1.64417e-5 0 -1 1.61257e-5 0 -1 3.89209e-6 0 -1 -3.89209e-6 0 -1 4.98155e-6 0 -1 1.64417e-5 0 -1 -1.61257e-5 0 -1 6.68296e-6 0 -1 -0.04619568 0.9989325 0 -7.78417e-6 0 1 1.01248e-5 0 1 7.78417e-6 0 1 -1.01247e-5 0 1 -1 -4.06904e-7 0 -1 1.865e-7 0 -1 -5.13105e-7 0 1 4.06904e-7 0 1 -3.7255e-6 0 -1.12211e-6 0 -1 2.18922e-6 0 -1 1.56308e-6 -0.6168262 -0.7870994 0 -0.6168265 -0.7870991 0 -0.6168264 -0.7870994 -1.90279e-6 -0.6168259 -0.7870997 0 -0.6168207 -0.7871038 0 0.32125 0.9469944 0 0.7851824 0.6192645 0 0.9784547 0.2064616 - - - - - - - - - - 0.5829028 0.8741281 0.5759928 0.8693662 0.5762518 0.8687286 0.58358 0.8806749 0.5977763 0.8893174 0.583401 0.8890087 0.5983179 0.8651218 0.6052753 0.8684427 0.6051308 0.8691719 0.5836983 0.8557443 0.5983179 0.8651218 0.5833635 0.8645536 0.5829765 0.9087723 0.5975053 0.9019319 0.5973518 0.9090812 0.5866652 0.8758175 0.5948213 0.8762992 0.5979552 0.8809837 0.5833635 0.8645536 0.5983179 0.8651218 0.5866938 0.8652504 0.5832244 0.8972349 0.5975053 0.9019319 0.5831301 0.9016231 0.5976491 0.8952397 0.583401 0.8890087 0.5977763 0.8893174 0.5976491 0.8952397 0.5832591 0.8956184 0.5832738 0.894931 0.5976343 0.8959271 0.5832425 0.8963913 0.5832591 0.8956184 0.5976177 0.8966999 0.5832244 0.8972349 0.5832425 0.8963913 0.5891436 0.872571 0.5856925 0.873784 0.5866938 0.8652504 0.5891436 0.872571 0.5948213 0.8762992 0.5866652 0.8758175 0.5922468 0.8720728 0.5960173 0.8739434 0.5948213 0.8762992 0.5922468 0.8720728 0.5866938 0.8652504 0.5951416 0.8655429 0.8747341 0.6686291 0.9800187 0.6638599 0.8772836 0.6654723 0.8772836 0.6654723 0.8702359 0.5399155 0.8747341 0.6686291 0.3594714 0.08487296 0.3717506 0.09323066 0.4203745 0.09323066 0.4203745 0.1683018 0.3717506 0.1683018 0.3594715 0.1719284 0.9800187 0.6638599 0.988224 0.5399155 0.98489 0.542671 0.98489 0.542671 0.8702359 0.5399155 0.8737322 0.5433948 0.96507 0.5536386 0.9673824 0.5538664 0.98489 0.542671 0.9645344 0.6593827 0.8965999 0.6600069 0.9800187 0.6638599 0.4197161 0.1067337 0.4184184 0.1542565 0.4197161 0.1546524 0.3799234 0.1032771 0.4141324 0.1040481 0.4142426 0.1028007 0.3741194 0.1073929 0.3726792 0.1534482 0.3753837 0.1077779 0.3772959 0.156802 0.376149 0.1579675 0.3771032 0.1581397 0.3764517 0.1566714 0.3752005 0.1577257 0.376149 0.1579675 0.3756479 0.1564411 0.3742792 0.1573736 0.3752005 0.1577257 0.3749027 0.1561297 0.3734236 0.156902 0.3742792 0.1573736 0.3727265 0.1563007 0.3742395 0.1557439 0.3736785 0.1553298 0.3732382 0.1548638 0.3727265 0.1563007 0.3736785 0.1553298 0.3729261 0.1544234 0.3721558 0.155674 0.3732382 0.1548638 0.3727405 0.1539547 0.3717767 0.1550004 0.3729261 0.1544234 0.3713719 0.153724 0.3727405 0.1539547 0.3726792 0.1534482 0.3800379 0.1045774 0.3790017 0.1033669 0.3792061 0.1046416 0.3792061 0.1046416 0.3780554 0.1035228 0.3784186 0.1048017 0.3780554 0.1035228 0.3776854 0.1050493 0.3784186 0.1048017 0.3776854 0.1050493 0.3762841 0.1042311 0.3770437 0.1053825 0.3762841 0.1042311 0.3764982 0.1057805 0.3770437 0.1053825 0.3755586 0.1047983 0.3760684 0.1062317 0.3764982 0.1057805 0.3749963 0.1054374 0.3757491 0.1067205 0.3760684 0.1062317 0.3745903 0.1061026 0.3755258 0.1072362 0.3757491 0.1067205 0.3743115 0.1067612 0.3753837 0.1077779 0.3755258 0.1072362 0.4146999 0.1586959 0.4136176 0.1574339 0.4137266 0.158786 0.4146999 0.1586959 0.4152651 0.1571822 0.4144594 0.1573493 0.4156677 0.158479 0.4160067 0.1569247 0.4152651 0.1571822 0.417439 0.1577155 0.4160067 0.1569247 0.4165772 0.1581445 0.4168395 0.156434 0.4176647 0.1575607 0.4172371 0.156145 0.4176988 0.1557037 0.4181497 0.1571845 0.4187476 0.1565666 0.4180518 0.1552377 0.4187476 0.1565666 0.4191859 0.1559188 0.4182984 0.1547583 0.4191859 0.1559188 0.4194889 0.1552774 0.4182984 0.1547583 0.4197161 0.1546524 0.4184184 0.1542565 0.4151407 0.1028935 0.4141324 0.1040481 0.4149321 0.1041302 0.4160482 0.1030718 0.4149321 0.1041302 0.4156864 0.1042955 0.4160482 0.1030718 0.416376 0.1045328 0.4168971 0.1033872 0.4176927 0.1037786 0.416376 0.1045328 0.4169902 0.1048504 0.4175004 0.1052117 0.4176927 0.1037786 0.4169902 0.1048504 0.4179022 0.1056124 0.418353 0.1043033 0.4175004 0.1052117 0.4179022 0.1056124 0.4192682 0.105473 0.4188627 0.1048811 0.418194 0.1060482 0.4195541 0.1060992 0.4192682 0.105473 0.4184219 0.1070324 0.4195541 0.1060992 0.4183634 0.1065082 0.4137266 0.158786 0.3772959 0.156802 0.3771032 0.1581397 0.7690456 0.3862641 0.7977539 0.4147287 0.797632 0.3861422 0.7404592 0.386386 0.7691676 0.4148506 0.7690456 0.3862641 0.7118726 0.3865079 0.740581 0.4149725 0.7404592 0.386386 0.6832862 0.3866298 0.7119946 0.4150944 0.7118726 0.3865079 0.7117508 0.3579214 0.7404592 0.386386 0.7403372 0.3577995 0.7119946 0.4150944 0.740703 0.4435589 0.740581 0.4149725 0.6973169 0.01760131 0.7027313 0.1042311 0.7027313 0.01760131 0.6919024 0.01760131 0.6973169 0.1042311 0.6973169 0.01760131 0.6864882 0.01760131 0.6919024 0.1042311 0.6919024 0.01760131 0.6810737 0.01760131 0.6864882 0.1042311 0.6864882 0.01760131 0.6756594 0.01760131 0.6810737 0.1042311 0.6810737 0.01760131 0.6702451 0.01760131 0.6756595 0.1042311 0.6756594 0.01760131 0.6648307 0.01760131 0.6702451 0.1042311 0.6702451 0.01760131 0.6594162 0.01760131 0.6648307 0.1042311 0.6648307 0.01760131 0.654002 0.01760131 0.6594165 0.1042311 0.6594162 0.01760131 0.6485877 0.01760131 0.654002 0.1042311 0.654002 0.01760131 0.6431734 0.01760131 0.6485877 0.1042311 0.6485877 0.01760131 0.637759 0.01760131 0.6431734 0.1042311 0.6431734 0.01760131 0.6323445 0.01760131 0.637759 0.1042311 0.637759 0.01760131 0.6269301 0.01760131 0.6323445 0.1042311 0.6323445 0.01760131 0.6215159 0.01760131 0.6269304 0.1042311 0.6269301 0.01760131 0.6161015 0.01760131 0.6215159 0.1042311 0.6215159 0.01760131 0.6106873 0.01760131 0.6161015 0.1042311 0.6161015 0.01760131 0.6052728 0.01760131 0.6106873 0.1042311 0.6106873 0.01760131 0.5998584 0.01760131 0.6052728 0.1042311 0.6052728 0.01760131 0.5944439 0.01760131 0.5998584 0.1042311 0.5998584 0.01760131 0.5890297 0.01760131 0.5944442 0.1042311 0.5944439 0.01760131 0.5836153 0.01760131 0.5890297 0.1042311 0.5890297 0.01760131 0.5782009 0.01760131 0.5836153 0.1042311 0.5836153 0.01760131 0.5727866 0.01760131 0.5782011 0.1042311 0.5782009 0.01760131 0.5673722 0.01760131 0.5727866 0.1042311 0.5727866 0.01760131 0.561958 0.01760131 0.5673722 0.1042311 0.5673722 0.01760131 0.5565436 0.01760131 0.561958 0.1042311 0.561958 0.01760131 0.5511292 0.01760131 0.5565436 0.1042311 0.5565436 0.01760131 0.5457149 0.01760131 0.5511292 0.1042311 0.5511292 0.01760131 0.5403005 0.01760131 0.5457149 0.1042311 0.5457149 0.01760131 0.55347 0.9863667 0.5585976 0.9842427 0.5202811 0.9459263 0.534886 0.01760131 0.5403005 0.1042311 0.5403005 0.01760131 0.5294719 0.01760131 0.534886 0.1042311 0.534886 0.01760131 0.6075842 0.9879301 0.6021404 0.9868473 0.6374531 0.9515348 0.5708588 0.8965264 0.5711222 0.8958779 0.5640935 0.8910341 0.5489646 0.8755837 0.5634047 0.8843748 0.5635867 0.8758978 0.5480147 0.8908329 0.5412341 0.8954507 0.5414837 0.8960753 0.5484136 0.9001951 0.5632844 0.9097337 0.5636249 0.9007732 0.5492402 0.8627526 0.5640186 0.8557946 0.5493964 0.8554806 0.5602664 0.8893156 0.5634047 0.8843748 0.5487825 0.8840608 0.5602375 0.9000642 0.5516446 0.8997668 0.5484136 0.9001951 0.5492402 0.8627526 0.5637665 0.8675304 0.5638623 0.8630667 0.5635867 0.8758978 0.549094 0.8695598 0.5489646 0.8755837 0.5637312 0.8691745 0.549094 0.8695598 0.5637161 0.8698739 0.5637481 0.8683885 0.549109 0.8688604 0.5637312 0.8691745 0.5637665 0.8675304 0.5491259 0.8680744 0.5637481 0.8683885 0.5612559 0.8913843 0.5577455 0.8926178 0.5602375 0.9000642 0.5519703 0.8888258 0.5577455 0.8926178 0.5602664 0.8893156 0.5507537 0.8912221 0.554589 0.8931245 0.5519703 0.8888258 0.5602375 0.9000642 0.554589 0.8931245 0.5516446 0.8997668 0.5755944 0.8672967 0.5722714 0.8644242 0.576951 0.8590105 0.576951 0.8590105 0.5833635 0.8645536 0.5755944 0.8672967 0.5833635 0.8645536 0.5829028 0.8741281 0.5762518 0.8687286 0.5755944 0.8672967 0.5833635 0.8645536 0.5761055 0.867969 0.5829028 0.8741281 0.5784271 0.8793057 0.5759928 0.8693662 0.5784271 0.8793057 0.5721164 0.8738508 0.5759928 0.8693662 0.5761055 0.867969 0.5833635 0.8645536 0.5762518 0.8687286 0.58358 0.8806749 0.5979552 0.8809837 0.5977763 0.8893174 0.6053762 0.8697861 0.6090781 0.8741165 0.602984 0.8793258 0.602984 0.8793258 0.5987101 0.8743261 0.6053762 0.8697861 0.5987101 0.8743261 0.5983179 0.8651218 0.6051308 0.8691719 0.6053762 0.8697861 0.5987101 0.8743261 0.6051308 0.8691719 0.5983179 0.8651218 0.6045102 0.8598284 0.6057701 0.8677994 0.6045102 0.8598284 0.6089789 0.8650563 0.6057701 0.8677994 0.5983179 0.8651218 0.6057701 0.8677994 0.6052753 0.8684427 0.5836983 0.8557443 0.5986527 0.8563125 0.5983179 0.8651218 0.5829765 0.9087723 0.5831301 0.9016231 0.5975053 0.9019319 0.5948213 0.8762992 0.5960173 0.8739434 0.5987101 0.8743261 0.58358 0.8806749 0.5829028 0.8741281 0.5866652 0.8758175 0.5829028 0.8741281 0.5856925 0.873784 0.5866652 0.8758175 0.5948213 0.8762992 0.5987101 0.8743261 0.5979552 0.8809837 0.58358 0.8806749 0.5866652 0.8758175 0.5979552 0.8809837 0.5856925 0.873784 0.5829028 0.8741281 0.5866938 0.8652504 0.5829028 0.8741281 0.5833635 0.8645536 0.5866938 0.8652504 0.5983179 0.8651218 0.5987101 0.8743261 0.5951416 0.8655429 0.5987101 0.8743261 0.5960173 0.8739434 0.5951416 0.8655429 0.5983179 0.8651218 0.5951416 0.8655429 0.5866938 0.8652504 0.5832244 0.8972349 0.5975996 0.8975437 0.5975053 0.9019319 0.5976491 0.8952397 0.5832738 0.894931 0.583401 0.8890087 0.5976491 0.8952397 0.5976343 0.8959271 0.5832591 0.8956184 0.5976343 0.8959271 0.5976177 0.8966999 0.5832425 0.8963913 0.5976177 0.8966999 0.5975996 0.8975437 0.5832244 0.8972349 0.5891436 0.872571 0.5866652 0.8758175 0.5856925 0.873784 0.5891436 0.872571 0.5922468 0.8720728 0.5948213 0.8762992 0.5922468 0.8720728 0.5951416 0.8655429 0.5960173 0.8739434 0.5922468 0.8720728 0.5891436 0.872571 0.5866938 0.8652504 0.8747341 0.6686291 0.9823707 0.6662312 0.9800187 0.6638599 0.8772836 0.6654723 0.8737322 0.5433948 0.8702359 0.5399155 0.3594715 0.1719284 0.367084 0.1671015 0.3664976 0.1667238 0.3594715 0.1719284 0.3664976 0.1667238 0.3658121 0.166093 0.4263131 0.166093 0.4256275 0.1667237 0.4355041 0.1719284 0.4268183 0.1653952 0.4263131 0.166093 0.4355041 0.1719284 0.3594715 0.1719284 0.3658121 0.166093 0.365307 0.1653952 0.3594715 0.1719284 0.365307 0.1653952 0.3649976 0.1646515 0.4271275 0.1646515 0.4268183 0.1653952 0.4355041 0.1719284 0.4272318 0.1638843 0.4271275 0.1646515 0.4355041 0.1719284 0.3594715 0.1719284 0.3649976 0.1646515 0.3648934 0.1638843 0.3594715 0.1719284 0.3648934 0.1638843 0.3648934 0.09773713 0.4272318 0.1638843 0.4355041 0.1719284 0.4272318 0.09773713 0.4355041 0.1719284 0.435504 0.08487296 0.4272318 0.09773713 0.3594714 0.08487296 0.3594715 0.1719284 0.3648934 0.09773713 0.3594714 0.08487296 0.3648934 0.09773713 0.3649976 0.09695458 0.4271275 0.09695458 0.4272318 0.09773713 0.435504 0.08487296 0.4268183 0.09619581 0.4271275 0.09695458 0.435504 0.08487296 0.3594714 0.08487296 0.3649976 0.09695458 0.365307 0.09619581 0.3594714 0.08487296 0.365307 0.09619581 0.3658121 0.09548395 0.4263131 0.09548395 0.4268183 0.09619581 0.435504 0.08487296 0.4256275 0.09484052 0.4263131 0.09548395 0.435504 0.08487296 0.3594714 0.08487296 0.3658121 0.09548395 0.3664976 0.09484052 0.3594714 0.08487296 0.3664976 0.09484052 0.367343 0.09428495 0.4247822 0.09428495 0.4256275 0.09484052 0.435504 0.08487296 0.4238031 0.09383445 0.4247822 0.09428495 0.435504 0.08487296 0.3594714 0.08487296 0.367343 0.09428495 0.3683221 0.09383434 0.3594714 0.08487296 0.3683221 0.09383434 0.3694053 0.09350246 0.4227199 0.09350246 0.4238031 0.09383445 0.435504 0.08487296 0.4215654 0.09329915 0.4227199 0.09350246 0.435504 0.08487296 0.3594714 0.08487296 0.3694053 0.09350246 0.3705598 0.09329915 0.3594714 0.08487296 0.3705598 0.09329915 0.3717506 0.09323066 0.4215654 0.09329915 0.435504 0.08487296 0.4203745 0.09323066 0.435504 0.08487296 0.3594714 0.08487296 0.4203745 0.09323066 0.4355041 0.1719284 0.4256275 0.1667237 0.4247822 0.1672683 0.4355041 0.1719284 0.4247822 0.1672683 0.4238031 0.16771 0.367343 0.1672683 0.367084 0.1671015 0.3594715 0.1719284 0.3683221 0.16771 0.367343 0.1672683 0.3594715 0.1719284 0.4355041 0.1719284 0.4238031 0.16771 0.4227199 0.1680353 0.4355041 0.1719284 0.4227199 0.1680353 0.4215654 0.1682347 0.3694053 0.1680353 0.3683221 0.16771 0.3594715 0.1719284 0.3705598 0.1682347 0.3694053 0.1680353 0.3594715 0.1719284 0.3594715 0.1719284 0.4355041 0.1719284 0.4203745 0.1683018 0.4355041 0.1719284 0.4215654 0.1682347 0.4203745 0.1683018 0.3717506 0.1683018 0.3705598 0.1682347 0.3594715 0.1719284 0.9800187 0.6638599 0.9823707 0.6662312 0.988224 0.5399155 0.98489 0.542671 0.988224 0.5399155 0.8702359 0.5399155 0.8772836 0.6654723 0.8886047 0.6579787 0.8875663 0.6571196 0.8772836 0.6654723 0.8875663 0.6571196 0.8867759 0.656144 0.9721305 0.6571642 0.9713081 0.6576603 0.9800187 0.6638599 0.9731183 0.6563533 0.9721305 0.6571642 0.9800187 0.6638599 0.8772836 0.6654723 0.8867759 0.656144 0.8862538 0.6550688 0.8772836 0.6654723 0.8862538 0.6550688 0.8860207 0.6539182 0.9738857 0.6554199 0.9731183 0.6563533 0.9800187 0.6638599 0.9744104 0.6543584 0.9738857 0.6554199 0.9800187 0.6638599 0.8737322 0.5433948 0.8772836 0.6654723 0.8835555 0.5616279 0.8772836 0.6654723 0.8860207 0.6539182 0.8835555 0.5616279 0.9746546 0.6531665 0.9744104 0.6543584 0.9800187 0.6638599 0.9772418 0.5615525 0.9746546 0.6531665 0.9800187 0.6638599 0.8737322 0.5433948 0.8835555 0.5616279 0.8838283 0.5603622 0.8737322 0.5433948 0.8838283 0.5603622 0.8844028 0.5591583 0.9772418 0.5615525 0.9800187 0.6638599 0.98489 0.542671 0.9770376 0.5601555 0.9772418 0.5615525 0.98489 0.542671 0.8737322 0.5433948 0.8844028 0.5591583 0.8852557 0.5580468 0.8737322 0.5433948 0.8852557 0.5580468 0.8863642 0.5570533 0.9764862 0.5588477 0.9770376 0.5601555 0.98489 0.542671 0.9756205 0.5576542 0.9764862 0.5588477 0.98489 0.542671 0.8737322 0.5433948 0.8863642 0.5570533 0.8877077 0.5561998 0.8737322 0.5433948 0.8877077 0.5561998 0.8892661 0.5555065 0.9744692 0.5565906 0.9756205 0.5576542 0.98489 0.542671 0.9730545 0.5556685 0.9744692 0.5565906 0.98489 0.542671 0.8737322 0.5433948 0.8892661 0.5555065 0.8910198 0.5549933 0.8737322 0.5433948 0.8910198 0.5549933 0.8929489 0.5546807 0.9713932 0.5548988 0.9730545 0.5556685 0.98489 0.542671 0.9694979 0.554293 0.9713932 0.5548988 0.98489 0.542671 0.98489 0.542671 0.8737322 0.5433948 0.8950319 0.5545884 0.8737322 0.5433948 0.8929489 0.5546807 0.8950319 0.5545884 0.9673824 0.5538664 0.9694979 0.554293 0.98489 0.542671 0.98489 0.542671 0.8950319 0.5545884 0.96507 0.5536386 0.8898702 0.6587074 0.8886047 0.6579787 0.8772836 0.6654723 0.9800187 0.6638599 0.9713081 0.6576603 0.9709069 0.6579104 0.9800187 0.6638599 0.9709069 0.6579104 0.9695236 0.6584946 0.8913381 0.6592912 0.8898702 0.6587074 0.8772836 0.6654723 0.8929772 0.6597141 0.8913381 0.6592912 0.8772836 0.6654723 0.9800187 0.6638599 0.9695236 0.6584946 0.9679738 0.658948 0.9800187 0.6638599 0.9679738 0.658948 0.9662953 0.6592516 0.8947471 0.6599586 0.8929772 0.6597141 0.8772836 0.6654723 0.8965999 0.6600069 0.8947471 0.6599586 0.8772836 0.6654723 0.8772836 0.6654723 0.9800187 0.6638599 0.8965999 0.6600069 0.9800187 0.6638599 0.9662953 0.6592516 0.9645344 0.6593827 0.4197161 0.1067337 0.4184219 0.1070324 0.4184184 0.1542565 0.3799234 0.1032771 0.3800379 0.1045774 0.4141324 0.1040481 0.3741194 0.1073929 0.3713719 0.153724 0.3726792 0.1534482 0.3772959 0.156802 0.3764517 0.1566714 0.376149 0.1579675 0.3764517 0.1566714 0.3756479 0.1564411 0.3752005 0.1577257 0.3756479 0.1564411 0.3749027 0.1561297 0.3742792 0.1573736 0.3749027 0.1561297 0.3742395 0.1557439 0.3734236 0.156902 0.3727265 0.1563007 0.3734236 0.156902 0.3742395 0.1557439 0.3732382 0.1548638 0.3721558 0.155674 0.3727265 0.1563007 0.3729261 0.1544234 0.3717767 0.1550004 0.3721558 0.155674 0.3727405 0.1539547 0.3715383 0.1543521 0.3717767 0.1550004 0.3713719 0.153724 0.3715383 0.1543521 0.3727405 0.1539547 0.3800379 0.1045774 0.3799234 0.1032771 0.3790017 0.1033669 0.3792061 0.1046416 0.3790017 0.1033669 0.3780554 0.1035228 0.3780554 0.1035228 0.3771506 0.1038295 0.3776854 0.1050493 0.3776854 0.1050493 0.3771506 0.1038295 0.3762841 0.1042311 0.3762841 0.1042311 0.3755586 0.1047983 0.3764982 0.1057805 0.3755586 0.1047983 0.3749963 0.1054374 0.3760684 0.1062317 0.3749963 0.1054374 0.3745903 0.1061026 0.3757491 0.1067205 0.3745903 0.1061026 0.3743115 0.1067612 0.3755258 0.1072362 0.3743115 0.1067612 0.3741194 0.1073929 0.3753837 0.1077779 0.4146999 0.1586959 0.4144594 0.1573493 0.4136176 0.1574339 0.4146999 0.1586959 0.4156677 0.158479 0.4152651 0.1571822 0.4156677 0.158479 0.4165772 0.1581445 0.4160067 0.1569247 0.417439 0.1577155 0.4166542 0.1565638 0.4160067 0.1569247 0.4168395 0.156434 0.4166542 0.1565638 0.417439 0.1577155 0.417439 0.1577155 0.4176647 0.1575607 0.4168395 0.156434 0.4176647 0.1575607 0.4181497 0.1571845 0.4172371 0.156145 0.4176988 0.1557037 0.4172371 0.156145 0.4181497 0.1571845 0.4180518 0.1552377 0.4176988 0.1557037 0.4187476 0.1565666 0.4182984 0.1547583 0.4180518 0.1552377 0.4191859 0.1559188 0.4182984 0.1547583 0.4194889 0.1552774 0.4197161 0.1546524 0.4151407 0.1028935 0.4142426 0.1028007 0.4141324 0.1040481 0.4160482 0.1030718 0.4151407 0.1028935 0.4149321 0.1041302 0.4160482 0.1030718 0.4156864 0.1042955 0.416376 0.1045328 0.4176927 0.1037786 0.4168971 0.1033872 0.416376 0.1045328 0.4175004 0.1052117 0.418353 0.1043033 0.4176927 0.1037786 0.4179022 0.1056124 0.4188627 0.1048811 0.418353 0.1043033 0.4179022 0.1056124 0.418194 0.1060482 0.4192682 0.105473 0.418194 0.1060482 0.4183634 0.1065082 0.4195541 0.1060992 0.4184219 0.1070324 0.4197161 0.1067337 0.4195541 0.1060992 0.4137266 0.158786 0.4136176 0.1574339 0.3772959 0.156802 0.7690456 0.3862641 0.7691676 0.4148506 0.7977539 0.4147287 0.7404592 0.386386 0.740581 0.4149725 0.7691676 0.4148506 0.7118726 0.3865079 0.7119946 0.4150944 0.740581 0.4149725 0.6832862 0.3866298 0.6834081 0.4152163 0.7119946 0.4150944 0.7117508 0.3579214 0.7118726 0.3865079 0.7404592 0.386386 0.7119946 0.4150944 0.7121165 0.4436808 0.740703 0.4435589 0.6973169 0.01760131 0.6973169 0.1042311 0.7027313 0.1042311 0.6919024 0.01760131 0.6919024 0.1042311 0.6973169 0.1042311 0.6864882 0.01760131 0.6864882 0.1042311 0.6919024 0.1042311 0.6810737 0.01760131 0.6810737 0.1042311 0.6864882 0.1042311 0.6756594 0.01760131 0.6756595 0.1042311 0.6810737 0.1042311 0.6702451 0.01760131 0.6702451 0.1042311 0.6756595 0.1042311 0.6648307 0.01760131 0.6648307 0.1042311 0.6702451 0.1042311 0.6594162 0.01760131 0.6594165 0.1042311 0.6648307 0.1042311 0.654002 0.01760131 0.654002 0.1042311 0.6594165 0.1042311 0.6485877 0.01760131 0.6485877 0.1042311 0.654002 0.1042311 0.6431734 0.01760131 0.6431734 0.1042311 0.6485877 0.1042311 0.637759 0.01760131 0.637759 0.1042311 0.6431734 0.1042311 0.6323445 0.01760131 0.6323445 0.1042311 0.637759 0.1042311 0.6269301 0.01760131 0.6269304 0.1042311 0.6323445 0.1042311 0.6215159 0.01760131 0.6215159 0.1042311 0.6269304 0.1042311 0.6161015 0.01760131 0.6161015 0.1042311 0.6215159 0.1042311 0.6106873 0.01760131 0.6106873 0.1042311 0.6161015 0.1042311 0.6052728 0.01760131 0.6052728 0.1042311 0.6106873 0.1042311 0.5998584 0.01760131 0.5998584 0.1042311 0.6052728 0.1042311 0.5944439 0.01760131 0.5944442 0.1042311 0.5998584 0.1042311 0.5890297 0.01760131 0.5890297 0.1042311 0.5944442 0.1042311 0.5836153 0.01760131 0.5836153 0.1042311 0.5890297 0.1042311 0.5782009 0.01760131 0.5782011 0.1042311 0.5836153 0.1042311 0.5727866 0.01760131 0.5727866 0.1042311 0.5782011 0.1042311 0.5673722 0.01760131 0.5673722 0.1042311 0.5727866 0.1042311 0.561958 0.01760131 0.561958 0.1042311 0.5673722 0.1042311 0.5565436 0.01760131 0.5565436 0.1042311 0.561958 0.1042311 0.5511292 0.01760131 0.5511292 0.1042311 0.5565436 0.1042311 0.5457149 0.01760131 0.5457149 0.1042311 0.5511292 0.1042311 0.5403005 0.01760131 0.5403005 0.1042311 0.5457149 0.1042311 0.5632127 0.981159 0.5671373 0.9772344 0.5319045 0.9343031 0.5671373 0.9772344 0.5702208 0.9726195 0.5370322 0.932179 0.5702208 0.9726195 0.5723448 0.9674917 0.542476 0.9310963 0.5723448 0.9674917 0.5734275 0.962048 0.5480262 0.9310963 0.5734275 0.962048 0.5734275 0.9564977 0.5480262 0.9310963 0.5734275 0.9564977 0.5723448 0.9510542 0.55347 0.9321792 0.5480262 0.9310963 0.5734275 0.9564977 0.55347 0.9321792 0.5723448 0.9510542 0.5702208 0.9459263 0.5585976 0.9343031 0.5702208 0.9459263 0.5671371 0.9413113 0.5632127 0.9373867 0.5585976 0.9343031 0.5702208 0.9459263 0.5632127 0.9373867 0.5585976 0.9343031 0.55347 0.9321792 0.5723448 0.9510542 0.5480262 0.9310963 0.542476 0.9310963 0.5723448 0.9674917 0.542476 0.9310963 0.5370322 0.932179 0.5702208 0.9726195 0.5370322 0.932179 0.5319045 0.9343031 0.5671373 0.9772344 0.5319045 0.9343031 0.5272895 0.9373867 0.5632127 0.981159 0.5272895 0.9373867 0.5233649 0.9413113 0.5632127 0.981159 0.5233649 0.9413113 0.5202811 0.9459263 0.5585976 0.9842427 0.5632127 0.981159 0.5233649 0.9413113 0.5585976 0.9842427 0.5202811 0.9459263 0.5181573 0.951054 0.55347 0.9863667 0.5181573 0.951054 0.5170744 0.9564977 0.5480262 0.9874495 0.55347 0.9863667 0.5181573 0.951054 0.5480262 0.9874495 0.5170744 0.9564977 0.5170744 0.962048 0.542476 0.9874495 0.5170744 0.962048 0.5181573 0.9674917 0.5370322 0.9863667 0.542476 0.9874495 0.5170744 0.962048 0.5370322 0.9863667 0.5181573 0.9674917 0.5202811 0.9726195 0.5319045 0.9842427 0.5202811 0.9726195 0.5233649 0.9772344 0.5272895 0.981159 0.5319045 0.9842427 0.5202811 0.9726195 0.5272895 0.981159 0.5319045 0.9842427 0.5370322 0.9863667 0.5181573 0.9674917 0.542476 0.9874495 0.5480262 0.9874495 0.5170744 0.9564977 0.534886 0.01760131 0.534886 0.1042311 0.5403005 0.1042311 0.5294719 0.01760131 0.5294719 0.1042311 0.534886 0.1042311 0.5970128 0.9847232 0.5923977 0.9816396 0.6283209 0.9378673 0.5923977 0.9816396 0.5884731 0.977715 0.6237061 0.9347837 0.5884731 0.977715 0.5853894 0.9731001 0.6237061 0.9347837 0.5853894 0.9731001 0.5832656 0.9679723 0.6185782 0.9326598 0.6237061 0.9347837 0.5853894 0.9731001 0.6185782 0.9326598 0.5832656 0.9679723 0.5821827 0.9625286 0.6075842 0.9315769 0.5821827 0.9625286 0.5821827 0.9569783 0.6021407 0.9326596 0.5821827 0.9569783 0.5832656 0.9515346 0.6021407 0.9326596 0.5832656 0.9515346 0.5853896 0.9464069 0.5970128 0.9347837 0.6021407 0.9326596 0.5832656 0.9515346 0.5970128 0.9347837 0.5853896 0.9464069 0.5884731 0.9417919 0.5923979 0.9378673 0.5923979 0.9378673 0.5970128 0.9347837 0.5853896 0.9464069 0.6021407 0.9326596 0.6075842 0.9315769 0.5821827 0.9625286 0.6075842 0.9315769 0.6131346 0.9315769 0.5832656 0.9679723 0.6131346 0.9315769 0.6185782 0.9326598 0.5832656 0.9679723 0.6237061 0.9347837 0.6283209 0.9378673 0.5923977 0.9816396 0.6283209 0.9378673 0.6322456 0.941792 0.5970128 0.9847232 0.6322456 0.941792 0.635329 0.946407 0.5970128 0.9847232 0.635329 0.946407 0.6374531 0.9515348 0.6021404 0.9868473 0.5970128 0.9847232 0.635329 0.946407 0.6021404 0.9868473 0.6374531 0.9515348 0.638536 0.9569783 0.6131344 0.9879301 0.638536 0.9569783 0.638536 0.9625287 0.6185782 0.9868473 0.638536 0.9625287 0.6374531 0.9679724 0.6185782 0.9868473 0.6374531 0.9679724 0.635329 0.9731002 0.6237059 0.9847233 0.6185782 0.9868473 0.6374531 0.9679724 0.6237059 0.9847233 0.635329 0.9731002 0.6322456 0.977715 0.6283209 0.9816396 0.6283209 0.9816396 0.6237059 0.9847233 0.635329 0.9731002 0.6185782 0.9868473 0.6131344 0.9879301 0.638536 0.9569783 0.6131344 0.9879301 0.6075842 0.9879301 0.6374531 0.9515348 0.5701476 0.9064114 0.5749076 0.9009044 0.5715274 0.8979828 0.5701476 0.9064114 0.5715274 0.8979828 0.5636249 0.9007732 0.5715274 0.8979828 0.5710076 0.8972991 0.5636249 0.9007732 0.5640935 0.8910341 0.5636249 0.9007732 0.5708588 0.8965264 0.5750653 0.8913162 0.568646 0.8857674 0.5711222 0.8958779 0.568646 0.8857674 0.5640935 0.8910341 0.5711222 0.8958779 0.5636249 0.9007732 0.5710076 0.8972991 0.5708588 0.8965264 0.5489646 0.8755837 0.5487825 0.8840608 0.5634047 0.8843748 0.5408334 0.8974715 0.5375694 0.9002617 0.542115 0.9055793 0.542115 0.9055793 0.5484136 0.9001951 0.5408334 0.8974715 0.5484136 0.9001951 0.5480147 0.8908329 0.5414837 0.8960753 0.5408334 0.8974715 0.5484136 0.9001951 0.5413367 0.8968171 0.5480147 0.8908329 0.5436673 0.8857471 0.5412341 0.8954507 0.5436673 0.8857471 0.5374686 0.8910458 0.5412341 0.8954507 0.5413367 0.8968171 0.5484136 0.9001951 0.5414837 0.8960753 0.5484136 0.9001951 0.5480731 0.9091557 0.5632844 0.9097337 0.5492402 0.8627526 0.5638623 0.8630667 0.5640186 0.8557946 0.5480147 0.8908329 0.5507537 0.8912221 0.5519703 0.8888258 0.5602664 0.8893156 0.5612559 0.8913843 0.5640935 0.8910341 0.5487825 0.8840608 0.5480147 0.8908329 0.5519703 0.8888258 0.5602664 0.8893156 0.5640935 0.8910341 0.5634047 0.8843748 0.5487825 0.8840608 0.5519703 0.8888258 0.5602664 0.8893156 0.5636249 0.9007732 0.5640935 0.8910341 0.5602375 0.9000642 0.5640935 0.8910341 0.5612559 0.8913843 0.5602375 0.9000642 0.5507537 0.8912221 0.5480147 0.8908329 0.5516446 0.8997668 0.5480147 0.8908329 0.5484136 0.9001951 0.5516446 0.8997668 0.5636249 0.9007732 0.5602375 0.9000642 0.5484136 0.9001951 0.5492402 0.8627526 0.5491443 0.8672162 0.5637665 0.8675304 0.5635867 0.8758978 0.5637161 0.8698739 0.549094 0.8695598 0.5637312 0.8691745 0.549109 0.8688604 0.549094 0.8695598 0.5637481 0.8683885 0.5491259 0.8680744 0.549109 0.8688604 0.5637665 0.8675304 0.5491443 0.8672162 0.5491259 0.8680744 0.5612559 0.8913843 0.5602664 0.8893156 0.5577455 0.8926178 0.5519703 0.8888258 0.554589 0.8931245 0.5577455 0.8926178 0.5507537 0.8912221 0.5516446 0.8997668 0.554589 0.8931245 0.5602375 0.9000642 0.5577455 0.8926178 0.554589 0.8931245 - - - - - - - - - - - - - - -

5 0 0 14 0 1 15 0 2 1 1 3 16 1 4 13 1 5 9 2 6 19 2 7 21 2 8 0 3 9 9 3 10 6 3 11 0 4 12 17 4 13 3 4 14 25 5 15 22 5 16 4 5 17 6 6 18 9 6 19 26 6 20 11 1 21 17 1 22 10 1 23 20 4 24 13 4 25 16 4 26 20 7 27 15 7 28 14 7 29 21 8 30 12 8 31 15 8 32 19 9 33 11 9 34 12 9 35 2 10 36 23 10 37 26 10 38 2 3 39 22 3 40 25 3 41 7 11 42 24 11 43 22 11 44 7 5 45 26 5 46 27 5 47 28 12 48 32 12 49 29 12 50 29 13 51 30 13 52 28 13 53 33 14 54 47 14 55 46 14 56 54 15 57 55 15 58 31 15 59 32 16 60 33 16 61 34 16 62 34 17 63 30 17 64 35 17 65 85 18 66 87 18 67 34 18 68 92 19 69 91 19 70 32 19 71 114 20 72 37 20 73 117 20 74 84 5 75 47 5 76 85 5 77 90 21 78 75 21 79 72 21 80 54 22 81 95 22 82 91 22 83 56 23 84 94 23 85 95 23 86 64 24 87 97 24 88 94 24 89 61 25 90 101 25 91 97 25 92 98 26 93 60 26 94 76 26 95 68 27 96 98 27 97 76 27 98 67 28 99 116 28 100 68 28 101 74 29 102 105 29 103 67 29 104 115 30 105 74 30 106 75 30 107 46 31 108 86 31 109 48 31 110 48 32 111 82 32 112 50 32 113 82 33 114 43 33 115 50 33 116 43 34 117 79 34 118 49 34 119 79 35 120 39 35 121 49 35 122 80 36 123 71 36 124 39 36 125 78 37 126 70 37 127 71 37 128 81 38 129 73 38 130 70 38 131 77 39 132 72 39 133 73 39 134 96 40 135 55 40 136 92 40 137 96 41 138 58 41 139 57 41 140 93 42 141 59 42 142 58 42 143 102 43 144 59 43 145 103 43 146 62 44 147 100 44 148 65 44 149 66 45 150 99 45 151 104 45 152 69 46 153 104 46 154 106 46 155 36 47 156 106 47 157 108 47 158 36 48 159 117 48 160 37 48 161 87 49 162 47 49 163 45 49 164 83 50 165 45 50 166 51 50 167 83 51 168 44 51 169 89 51 170 111 52 171 44 52 172 52 52 173 40 53 174 111 53 175 52 53 176 41 54 177 112 54 178 40 54 179 41 55 180 109 55 181 113 55 182 38 56 183 110 56 184 109 56 185 53 57 186 110 57 187 42 57 188 92 58 189 54 58 190 91 58 191 120 11 192 119 11 193 118 11 194 124 1 195 121 1 196 120 1 197 122 10 198 125 10 199 124 10 200 118 3 201 123 3 202 122 3 203 118 5 204 124 5 205 120 5 206 123 4 207 121 4 208 125 4 209 205 11 312 204 11 313 195 11 314 206 1 315 191 1 316 203 1 317 198 91 318 210 91 319 211 91 320 199 3 321 190 3 322 196 3 323 207 5 324 190 5 325 193 5 326 215 4 327 191 4 328 194 4 329 216 92 330 217 92 331 199 92 332 207 1 333 201 1 334 200 1 335 203 5 336 210 5 337 206 5 338 205 93 339 210 93 340 204 93 341 202 94 342 211 94 343 205 94 344 201 95 345 209 95 346 202 95 347 213 10 348 192 10 349 216 10 350 212 3 351 192 3 352 215 3 353 214 11 354 197 11 355 212 11 356 216 4 357 197 4 358 217 4 359 11 11 360 10 11 361 0 11 362 0 96 363 6 96 364 11 96 365 6 11 366 5 11 367 15 11 368 11 97 369 6 97 370 12 97 371 5 11 372 1 11 373 14 11 374 1 11 375 13 11 376 14 11 377 12 11 378 6 11 379 15 11 380 1 1 381 4 1 382 16 1 383 20 10 384 16 10 385 4 10 386 4 10 387 8 10 388 20 10 389 8 98 390 9 98 391 21 98 392 20 10 393 8 10 394 21 10 395 9 99 396 3 99 397 18 99 398 3 10 399 17 10 400 18 10 401 9 100 402 18 100 403 19 100 404 0 3 405 3 3 406 9 3 407 0 4 408 10 4 409 17 4 410 22 5 411 24 5 412 8 5 413 1 5 414 5 5 415 25 5 416 5 5 417 23 5 418 25 5 419 22 5 420 8 5 421 4 5 422 1 5 423 25 5 424 4 5 425 23 101 426 5 101 427 26 101 428 5 102 429 6 102 430 26 102 431 9 103 432 8 103 433 27 103 434 8 104 435 24 104 436 27 104 437 9 105 438 27 105 439 26 105 440 11 1 441 18 1 442 17 1 443 20 4 444 14 4 445 13 4 446 20 106 447 21 106 448 15 106 449 21 107 450 19 107 451 12 107 452 19 108 453 18 108 454 11 108 455 2 10 456 25 10 457 23 10 458 2 3 459 7 3 460 22 3 461 7 11 462 27 11 463 24 11 464 7 5 465 2 5 466 26 5 467 28 109 468 31 109 469 32 109 470 29 110 471 35 110 472 30 110 473 31 111 474 62 111 475 65 111 476 31 112 477 65 112 478 66 112 479 68 113 480 76 113 481 28 113 482 67 114 483 68 114 484 28 114 485 31 115 486 66 115 487 69 115 488 31 116 489 69 116 490 36 116 491 74 117 492 67 117 493 28 117 494 75 118 495 74 118 496 28 118 497 31 119 498 36 119 499 37 119 500 31 120 501 37 120 502 53 120 503 75 121 504 28 121 505 72 121 506 28 122 507 30 122 508 72 122 509 33 123 510 31 123 511 53 123 512 33 124 513 53 124 514 42 124 515 73 125 516 72 125 517 30 125 518 70 126 519 73 126 520 30 126 521 33 127 522 42 127 523 38 127 524 33 128 525 38 128 526 41 128 527 71 129 528 70 129 529 30 129 530 39 130 531 71 130 532 30 130 533 33 131 534 41 131 535 40 131 536 33 132 537 40 132 538 52 132 539 49 133 540 39 133 541 30 133 542 43 134 543 49 134 544 30 134 545 33 135 546 52 135 547 44 135 548 33 136 549 44 136 550 51 136 551 50 137 552 43 137 553 30 137 554 48 138 555 50 138 556 30 138 557 33 139 558 51 139 559 45 139 560 33 140 561 45 140 562 47 140 563 48 141 564 30 141 565 46 141 566 30 142 567 33 142 568 46 142 569 28 143 570 76 143 571 60 143 572 28 144 573 60 144 574 61 144 575 63 145 576 62 145 577 31 145 578 59 146 579 63 146 580 31 146 581 28 147 582 61 147 583 64 147 584 28 148 585 64 148 586 56 148 587 58 149 588 59 149 589 31 149 590 57 150 591 58 150 592 31 150 593 31 151 594 28 151 595 54 151 596 28 152 597 56 152 598 54 152 599 55 153 600 57 153 601 31 153 602 32 154 603 31 154 604 33 154 605 34 155 606 33 155 607 30 155 608 29 156 609 98 156 610 116 156 611 29 157 612 116 157 613 105 157 614 99 158 615 100 158 616 32 158 617 104 159 618 99 159 619 32 159 620 29 160 621 105 160 622 107 160 623 29 161 624 107 161 625 115 161 626 106 162 627 104 162 628 32 162 629 108 163 630 106 163 631 32 163 632 35 164 633 29 164 634 90 164 635 29 165 636 115 165 637 90 165 638 117 166 639 108 166 640 32 166 641 114 167 642 117 167 643 32 167 644 35 168 645 90 168 646 77 168 647 35 169 648 77 169 649 81 169 650 114 170 651 32 170 652 34 170 653 110 171 654 114 171 655 34 171 656 35 172 657 81 172 658 78 172 659 35 173 660 78 173 661 80 173 662 109 174 663 110 174 664 34 174 665 113 175 666 109 175 667 34 175 668 35 176 669 80 176 670 79 176 671 35 177 672 79 177 673 88 177 674 112 178 675 113 178 676 34 178 677 111 179 678 112 179 679 34 179 680 35 180 681 88 180 682 82 180 683 35 181 684 82 181 685 86 181 686 89 182 687 111 182 688 34 182 689 83 183 690 89 183 691 34 183 692 34 184 693 35 184 694 84 184 695 35 185 696 86 185 697 84 185 698 87 186 699 83 186 700 34 186 701 34 187 702 84 187 703 85 187 704 101 188 705 98 188 706 29 188 707 32 189 708 100 189 709 102 189 710 32 190 711 102 190 712 103 190 713 97 191 714 101 191 715 29 191 716 94 192 717 97 192 718 29 192 719 32 193 720 103 193 721 93 193 722 32 194 723 93 194 724 96 194 725 95 195 726 94 195 727 29 195 728 91 196 729 95 196 730 29 196 731 29 197 732 32 197 733 91 197 734 32 198 735 96 198 736 92 198 737 114 199 738 53 199 739 37 199 740 84 200 741 46 200 742 47 200 743 90 201 744 115 201 745 75 201 746 54 202 747 56 202 748 95 202 749 56 203 750 64 203 751 94 203 752 64 204 753 61 204 754 97 204 755 61 205 756 60 205 757 101 205 758 98 206 759 101 206 760 60 206 761 68 207 762 116 207 763 98 207 764 67 208 765 105 208 766 116 208 767 74 209 768 107 209 769 105 209 770 115 210 771 107 210 772 74 210 773 46 211 774 84 211 775 86 211 776 48 212 777 86 212 778 82 212 779 82 213 780 88 213 781 43 213 782 43 214 783 88 214 784 79 214 785 79 215 786 80 215 787 39 215 788 80 216 789 78 216 790 71 216 791 78 217 792 81 217 793 70 217 794 81 218 795 77 218 796 73 218 797 77 219 798 90 219 799 72 219 800 96 220 801 57 220 802 55 220 803 96 221 804 93 221 805 58 221 806 93 222 807 103 222 808 59 222 809 102 223 810 63 223 811 59 223 812 62 224 813 63 224 814 102 224 815 102 225 816 100 225 817 62 225 818 100 226 819 99 226 820 65 226 821 66 227 822 65 227 823 99 227 824 69 228 825 66 228 826 104 228 827 36 229 828 69 229 829 106 229 830 36 230 831 108 230 832 117 230 833 87 231 834 85 231 835 47 231 836 83 232 837 87 232 838 45 232 839 83 233 840 51 233 841 44 233 842 111 234 843 89 234 844 44 234 845 40 235 846 112 235 847 111 235 848 41 236 849 113 236 850 112 236 851 41 237 852 38 237 853 109 237 854 38 238 855 42 238 856 110 238 857 53 239 858 114 239 859 110 239 860 92 240 861 55 240 862 54 240 863 120 11 864 121 11 865 119 11 866 124 1 867 125 1 868 121 1 869 122 10 870 123 10 871 125 10 872 118 3 873 119 3 874 123 3 875 118 5 876 122 5 877 124 5 878 123 4 879 119 4 880 121 4 881 190 11 1152 200 11 1153 201 11 1154 190 281 1155 201 281 1156 196 281 1157 201 11 1158 202 11 1159 196 11 1160 195 282 1161 196 282 1162 205 282 1163 203 11 1164 191 11 1165 204 11 1166 191 11 1167 195 11 1168 204 11 1169 196 283 1170 202 283 1171 205 283 1172 206 1 1173 194 1 1174 191 1 1175 208 10 1176 207 10 1177 193 10 1178 193 284 1179 199 284 1180 208 284 1181 199 10 1182 198 10 1183 211 10 1184 208 285 1185 199 285 1186 209 285 1187 198 10 1188 194 10 1189 210 10 1190 194 10 1191 206 10 1192 210 10 1193 209 10 1194 199 10 1195 211 10 1196 199 3 1197 193 3 1198 190 3 1199 207 5 1200 200 5 1201 190 5 1202 198 4 1203 214 4 1204 212 4 1205 215 4 1206 213 4 1207 195 4 1208 194 286 1209 198 286 1210 212 286 1211 215 287 1212 195 287 1213 191 287 1214 194 4 1215 212 4 1216 215 4 1217 196 288 1218 195 288 1219 216 288 1220 195 289 1221 213 289 1222 216 289 1223 214 290 1224 198 290 1225 217 290 1226 198 291 1227 199 291 1228 217 291 1229 196 292 1230 216 292 1231 199 292 1232 207 1 1233 208 1 1234 201 1 1235 203 5 1236 204 5 1237 210 5 1238 205 293 1239 211 293 1240 210 293 1241 202 294 1242 209 294 1243 211 294 1244 201 295 1245 208 295 1246 209 295 1247 213 10 1248 215 10 1249 192 10 1250 212 3 1251 197 3 1252 192 3 1253 214 11 1254 217 11 1255 197 11 1256 216 4 1257 192 4 1258 197 4 1259

-
- - - - -

128 59 210 127 59 211 126 59 212 130 60 213 129 60 214 128 60 215 132 61 216 131 61 217 130 61 218 134 62 219 133 62 220 132 62 221 136 63 222 135 63 223 134 63 224 138 64 225 137 64 226 136 64 227 140 65 228 139 65 229 138 65 230 142 66 231 141 66 232 140 66 233 144 67 234 143 67 235 142 67 236 146 68 237 145 68 238 144 68 239 148 69 240 147 69 241 146 69 242 150 70 243 149 70 244 148 70 245 152 71 246 151 71 247 150 71 248 154 72 249 153 72 250 152 72 251 156 73 252 155 73 253 154 73 254 158 74 255 157 74 256 156 74 257 160 75 258 159 75 259 158 75 260 162 76 261 161 76 262 160 76 263 164 77 264 163 77 265 162 77 266 166 78 267 165 78 268 164 78 269 168 79 270 167 79 271 166 79 272 170 80 273 169 80 274 168 80 275 172 81 276 171 81 277 170 81 278 174 82 279 173 82 280 172 82 281 176 83 282 175 83 283 174 83 284 178 84 285 177 84 286 176 84 287 180 85 288 179 85 289 178 85 290 182 86 291 181 86 292 180 86 293 184 87 294 183 87 295 182 87 296 186 88 297 185 88 298 184 88 299 187 4 300 189 4 301 163 4 302 188 89 303 187 89 304 186 89 305 126 90 306 189 90 307 188 90 308 132 5 309 130 5 310 152 5 311 128 241 882 129 241 883 127 241 884 130 60 885 131 60 886 129 60 887 132 242 888 133 242 889 131 242 890 134 243 891 135 243 892 133 243 893 136 63 894 137 63 895 135 63 896 138 244 897 139 244 898 137 244 899 140 245 900 141 245 901 139 245 902 142 246 903 143 246 904 141 246 905 144 247 906 145 247 907 143 247 908 146 248 909 147 248 910 145 248 911 148 249 912 149 249 913 147 249 914 150 70 915 151 70 916 149 70 917 152 250 918 153 250 919 151 250 920 154 251 921 155 251 922 153 251 923 156 73 924 157 73 925 155 73 926 158 252 927 159 252 928 157 252 929 160 253 930 161 253 931 159 253 932 162 76 933 163 76 934 161 76 935 164 254 936 165 254 937 163 254 938 166 255 939 167 255 940 165 255 941 168 256 942 169 256 943 167 256 944 170 257 945 171 257 946 169 257 947 172 258 948 173 258 949 171 258 950 174 259 951 175 259 952 173 259 953 176 260 954 177 260 955 175 260 956 178 261 957 179 261 958 177 261 959 180 262 960 181 262 961 179 262 962 182 263 963 183 263 964 181 263 965 184 264 966 185 264 967 183 264 968 186 265 969 187 265 970 185 265 971 127 4 972 129 4 973 157 4 974 129 4 975 131 4 976 155 4 977 131 266 978 133 266 979 153 266 980 133 267 981 135 267 982 151 267 983 135 4 984 137 4 985 151 4 986 137 4 987 139 4 988 149 4 989 151 4 990 137 4 991 149 4 992 139 268 993 141 268 994 147 268 995 141 4 996 143 4 997 145 4 998 147 269 999 141 269 1000 145 269 1001 147 4 1002 149 4 1003 139 4 1004 151 4 1005 153 4 1006 133 4 1007 153 4 1008 155 4 1009 131 4 1010 155 270 1011 157 270 1012 129 270 1013 157 4 1014 159 4 1015 127 4 1016 159 4 1017 161 4 1018 127 4 1019 161 271 1020 163 271 1021 189 271 1022 127 4 1023 161 4 1024 189 4 1025 163 4 1026 165 4 1027 187 4 1028 165 4 1029 167 4 1030 185 4 1031 187 272 1032 165 272 1033 185 272 1034 167 4 1035 169 4 1036 183 4 1037 169 4 1038 171 4 1039 181 4 1040 183 4 1041 169 4 1042 181 4 1043 171 273 1044 173 273 1045 179 273 1046 173 4 1047 175 4 1048 177 4 1049 179 274 1050 173 274 1051 177 274 1052 179 4 1053 181 4 1054 171 4 1055 183 275 1056 185 275 1057 167 275 1058 188 89 1059 189 89 1060 187 89 1061 126 276 1062 127 276 1063 189 276 1064 128 5 1065 126 5 1066 158 5 1067 126 5 1068 188 5 1069 160 5 1070 188 277 1071 186 277 1072 160 277 1073 186 5 1074 184 5 1075 162 5 1076 160 5 1077 186 5 1078 162 5 1079 184 5 1080 182 5 1081 166 5 1082 182 5 1083 180 5 1084 168 5 1085 180 5 1086 178 5 1087 168 5 1088 178 5 1089 176 5 1090 170 5 1091 168 278 1092 178 278 1093 170 278 1094 176 5 1095 174 5 1096 172 5 1097 172 5 1098 170 5 1099 176 5 1100 168 5 1101 166 5 1102 182 5 1103 166 5 1104 164 5 1105 184 5 1106 164 5 1107 162 5 1108 184 5 1109 160 5 1110 158 5 1111 126 5 1112 158 5 1113 156 5 1114 128 5 1115 156 279 1116 154 279 1117 128 279 1118 154 5 1119 152 5 1120 130 5 1121 128 5 1122 154 5 1123 130 5 1124 152 5 1125 150 5 1126 134 5 1127 150 5 1128 148 5 1129 136 5 1130 148 5 1131 146 5 1132 136 5 1133 146 5 1134 144 5 1135 138 5 1136 136 280 1137 146 280 1138 138 280 1139 144 5 1140 142 5 1141 140 5 1142 140 5 1143 138 5 1144 144 5 1145 136 5 1146 134 5 1147 150 5 1148 134 5 1149 132 5 1150 152 5 1151

-
-
-
- - - - 2.414493 -1.861196 6.468798 2.414493 0.1388037 8.468798 2.872419 -0.4937742 7.694431 4.414494 -1.861196 6.468798 4.414494 0.1388037 8.468798 2.414493 -0.8124906 8.468798 2.414493 -1.861196 7.646958 3.96779 -0.4937742 7.694431 4.414494 -0.8124906 8.468798 4.414494 -1.861196 7.646958 2.414493 -0.8665385 6.468798 2.414493 -0.8665385 7.079332 2.414493 -0.8423045 7.194181 2.414493 0.1388037 7.309332 2.414493 -0.6851414 7.309332 2.414493 -0.775721 7.278604 4.414494 0.1388037 7.309332 4.414494 -0.8665385 6.468798 4.414494 -0.8665385 7.079332 4.414494 -0.8423045 7.194181 4.414494 -0.6851414 7.309332 4.414494 -0.775721 7.278604 3.96779 -0.4937742 8.468798 2.872419 -0.8124906 8.468798 3.96779 -0.8124906 8.468798 2.872419 -0.4937742 8.468798 2.872419 -1.800619 7.694431 3.96779 -1.800619 7.694431 -16.15029 1.124289 13.34136 -16.15029 1.762395 13.34136 -16.15028 1.124287 -18.44267 5.10146 1.124289 13.34136 5.10146 1.762389 13.34136 5.101467 1.124287 -18.44267 5.10146 1.762389 -18.44268 -16.15029 1.762391 -18.44268 3.083875 1.124289 10.68454 3.121917 1.124289 10.40445 2.970926 1.124287 -14.30868 -12.54435 1.124287 -14.80351 2.536208 1.124287 -14.80351 2.786512 1.124287 -14.56858 3.083873 1.124287 -14.03167 -11.87825 1.124288 -15.17084 1.870101 1.124287 -15.17084 1.053116 1.124287 -15.36625 -10.62648 1.124287 -15.39126 0.6183364 1.124287 -15.39126 -11.06126 1.124287 -15.36625 -12.23573 1.124287 -15.00634 -11.48277 1.124287 -15.29203 1.474621 1.124287 -15.29203 2.227582 1.124287 -15.00634 3.121915 1.124287 -13.74594 -10.62648 1.124289 12.01729 0.6183403 1.124289 12.01729 -11.06126 1.124289 11.99278 1.053119 1.124288 11.99278 1.474624 1.124289 11.92002 1.870105 1.124289 11.80122 -12.23573 1.124289 11.63997 -11.87824 1.124289 11.80122 2.322147 1.124289 11.57905 2.227586 1.124289 11.63997 -11.48276 1.124289 11.92002 2.536211 1.124288 11.44115 2.786516 1.124288 11.21085 -12.97907 1.124289 10.95608 -12.79465 1.124289 11.21086 2.97093 1.124289 10.95608 -12.97907 1.124288 -14.30868 -12.79466 1.124287 -14.56858 -13.13006 1.124288 -13.74594 -13.09202 1.124288 -14.03167 -13.09201 1.124289 10.68454 -13.13006 1.124289 10.40445 -12.54435 1.124289 11.44114 -13.09202 1.762391 -14.03167 -12.79466 1.762391 -14.56858 -12.23573 1.762391 -15.00634 -12.54435 1.762391 -14.80351 -12.97907 1.762391 -14.30868 -11.48277 1.762391 -15.29203 1.474621 1.762389 -15.29203 -10.62648 1.762391 -15.39126 0.6183364 1.76239 -15.39126 -11.06126 1.762391 -15.36626 1.053116 1.762389 -15.36625 -11.87825 1.762391 -15.17084 1.870101 1.76239 -15.17084 -13.13006 1.762392 -13.74594 -10.62648 1.762394 12.01729 0.6183403 1.76239 12.01729 1.474624 1.762391 11.92002 -11.48276 1.762394 11.92002 -11.06126 1.762394 11.99278 1.053119 1.76239 11.99278 -11.87824 1.762394 11.80122 -12.54435 1.762395 11.44114 2.536211 1.762389 11.44115 2.327027 1.76239 11.5759 -12.23573 1.762394 11.63997 2.227586 1.76239 11.63997 1.870105 1.762391 11.80122 2.786516 1.76239 11.21085 -12.97907 1.762395 10.95608 2.970929 1.76239 10.95608 -13.09201 1.762395 10.68454 3.083874 1.76239 10.68454 2.970926 1.762389 -14.30868 3.083872 1.762389 -14.03167 2.227582 1.762389 -15.00634 2.536208 1.762389 -14.80351 2.786512 1.76239 -14.56858 3.121914 1.762389 -13.74594 -13.13006 1.762395 10.40445 -12.79465 1.762394 11.21085 3.121917 1.76239 10.40445 3.18072 0.1844011 8.676043 3.18072 0.1844011 -6.584051 3.18072 1.115921 8.676043 3.18072 1.115921 -6.584051 5.025683 0.1844011 8.676043 5.025683 0.1844011 -6.584051 5.025683 1.115921 8.676043 5.025683 1.115921 -6.584051 3.371023 -0.9721969 6.476446 3.371023 -0.9721969 -4.418558 3.535303 -0.979794 6.476446 3.535303 -0.979794 -4.418558 3.69327 -1.002294 6.476446 3.69327 -1.002294 -4.418558 3.838853 -1.038831 6.476446 3.838853 -1.038831 -4.418558 3.966458 -1.088002 6.476446 3.966458 -1.088002 -4.418558 4.07118 -1.147917 6.476446 4.07118 -1.147917 -4.418558 4.148996 -1.216274 6.476446 4.148996 -1.216274 -4.418558 4.196915 -1.290445 6.476446 4.196915 -1.290445 -4.418558 4.213095 -1.36758 6.476446 4.213095 -1.36758 -4.418558 4.196915 -1.444716 6.476446 4.196915 -1.444716 -4.418558 4.148996 -1.518887 6.476446 4.148996 -1.518887 -4.418558 4.07118 -1.587243 6.476446 4.07118 -1.587243 -4.418558 3.966458 -1.647158 6.476446 3.966458 -1.647158 -4.418558 3.838853 -1.696329 6.476446 3.838853 -1.696329 -4.418558 3.69327 -1.732867 6.476446 3.69327 -1.732867 -4.418558 3.535303 -1.755366 6.476446 3.535303 -1.755366 -4.418558 3.371023 -1.762964 6.476446 3.371023 -1.762964 -4.418558 3.206743 -1.755366 6.476446 3.206743 -1.755366 -4.418558 3.048776 -1.732867 6.476446 3.048776 -1.732867 -4.418558 2.903193 -1.696329 6.476446 2.903193 -1.696329 -4.418558 2.775588 -1.647158 6.476446 2.775588 -1.647158 -4.418558 2.670866 -1.587243 6.476446 2.670866 -1.587243 -4.418558 2.59305 -1.518887 6.476446 2.59305 -1.518887 -4.418558 2.545132 -1.444716 6.476446 2.545132 -1.444716 -4.418558 2.528951 -1.36758 6.476446 2.528951 -1.36758 -4.418558 2.545132 -1.290445 6.476446 2.545132 -1.290445 -4.418558 2.59305 -1.216274 6.476446 2.59305 -1.216274 -4.418558 2.670866 -1.147917 6.476446 2.670866 -1.147917 -4.418558 2.775588 -1.088002 6.476446 2.775588 -1.088002 -4.418558 2.903193 -1.038831 6.476446 2.903193 -1.038831 -4.418558 3.048776 -1.002294 6.476446 3.048776 -1.002294 -4.418558 3.206743 -0.979794 6.476446 3.206743 -0.979794 -4.418558 2.414493 -1.861196 -4.415396 2.414493 0.1388037 -6.415396 2.872419 -0.4937742 -5.641028 4.414494 -1.861196 -4.415396 4.414494 0.1388037 -6.415396 2.414493 -0.8124906 -6.415396 2.414493 -1.861196 -5.593556 3.96779 -0.4937742 -5.641028 4.414494 -0.8124906 -6.415396 4.414494 -1.861196 -5.593556 2.414493 -0.8665385 -4.415396 2.414493 -0.8665385 -5.02593 2.414493 -0.8423045 -5.140779 2.414493 0.1388037 -5.25593 2.414493 -0.6851414 -5.25593 2.414493 -0.775721 -5.225203 4.414494 0.1388037 -5.25593 4.414494 -0.8665385 -4.415396 4.414494 -0.8665385 -5.02593 4.414494 -0.8423045 -5.140779 4.414494 -0.6851414 -5.25593 4.414494 -0.775721 -5.225203 3.96779 -0.4937742 -6.415396 2.872419 -0.8124906 -6.415396 3.96779 -0.8124906 -6.415396 2.872419 -0.4937742 -6.415396 2.872419 -1.800619 -5.641028 3.96779 -1.800619 -5.641028 - - - - - - - - - - -1 -4.10361e-7 0 0 1 0 1 5.13103e-7 0 0 -1 0 0 0 -1 0 0 1 0 -0.6168245 0.7871007 0 0.3212497 -0.9469946 0 0.7851838 -0.6192629 0 0.978455 -0.2064605 1 0 0 -1 0 0 0 4.48362e-6 1 -1 -6.01877e-6 -1.20019e-7 0 -1 0 0 -1 1.28105e-7 1 1.19068e-5 0 0 -8.96727e-6 -1 5.18075e-7 1 6.62835e-7 3.60443e-7 1 -5.1242e-7 -1 6.03762e-7 0 1 0 0 0.05628126 3.003e-6 -0.9984151 0.1701017 1.31028e-6 -0.9854266 0.2877038 0 -0.9577195 0.4111741 9.52743e-7 -0.9115568 0.5415656 2.03546e-6 -0.8406586 0.6770756 1.80727e-6 -0.7359136 0.8100551 -3.05435e-6 -0.5863537 0.9233159 2.54094e-6 -0.3840416 0.9909005 2.64366e-6 -0.1345973 0.05740696 2.98585e-6 0.9983509 0.1734343 0 0.9848455 0.2929975 0 0.9561133 0.4180176 0 0.908439 0.5492108 0 0.835684 0.6843632 -4.35362e-6 0.7291413 0.8155532 0 0.5786823 0.9259889 0 0.3775508 0.9912521 0 0.1319818 -0.05627858 1.49361e-6 -0.9984152 -0.1701018 0 -0.9854265 -0.2877048 -1.58344e-6 -0.9577192 -0.4111742 0 -0.9115567 -0.5415588 -7.33668e-7 -0.840663 -0.6770778 -1.64777e-6 -0.7359114 -0.8100597 -1.18799e-6 -0.5863474 -0.9233148 -1.9057e-6 -0.3840442 -0.9909026 6.28319e-7 -0.1345816 -0.05740743 0 0.9983509 -0.1734266 0 0.9848469 -0.2929961 0 0.9561137 -0.4180259 0 0.9084352 -0.5492035 0 0.8356887 -0.6843608 0 0.7291436 -0.8155598 0 0.578673 -0.9259876 0 0.3775541 -0.9912528 -1.29623e-6 0.1319764 0 2.98908e-6 -1 0.04619568 0.9989325 0 0.1410086 0.9900084 0 0.2434237 0.9699201 0 0.3595672 0.9331192 0 0.4966011 0.8679789 0 0.6599648 0.7512966 0 0.8399519 0.5426608 0 0.9786997 0.2052971 0 0.9786979 -0.2053056 0 0.8399556 -0.5426552 0 0.6599715 -0.7512907 0 0.4965986 -0.8679803 0 0.3595672 -0.9331192 0 0.2434225 -0.9699203 0 0.1410092 -0.9900083 0 0.04619604 -0.9989325 0 -0.04619622 -0.9989325 0 -0.1410092 -0.9900083 0 -0.2434237 -0.9699201 0 -0.3595672 -0.9331192 0 -0.4965986 -0.8679803 0 -0.6599665 -0.7512952 0 -0.8399538 -0.542658 0 -0.9786997 -0.2052971 0 -0.9786997 0.2052971 0 -0.8399574 0.5426524 0 -0.6599681 0.7512936 0 -0.4965986 0.8679803 0 -0.3595672 0.9331192 0 -0.2434231 0.9699203 0 -0.1410092 0.9900083 0 -0.0461955 0.9989325 0 1 2.73574e-7 0 0 -0.6168228 -0.7871021 0 0.3212497 0.9469946 0 0.785182 0.6192651 0 0.978455 0.2064605 -1 2.03452e-7 0 1 -1.865e-7 0 1 -1.86275e-6 0 0 -0.6168259 0.7870997 1.56308e-6 -0.6168268 0.787099 -1.60235e-6 -0.6168263 0.7870994 0 -0.6168264 0.7870993 0 -0.6168272 0.7870987 0 0.3212496 -0.9469946 0 0.7851842 -0.6192623 0 0.9784547 -0.2064616 1.40652e-7 0 1 -1 -2.9246e-6 0 -1.70065e-6 -1 2.31201e-6 0 -1 0 6.51735e-7 -1 7.30206e-7 -1.36725e-6 -1 -1.91068e-6 6.40529e-7 -1 -3.03275e-7 7.47038e-7 -1 -5.62355e-7 1.00608e-6 -1 1.68715e-6 -1.46231e-6 -1 -1.99164e-6 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1.37293e-7 -1 1.60166e-7 0 -1 0 0 -1 3.54431e-7 0 -1 0 0 -1 2.26443e-7 -5.6264e-7 -1 0 0 -1 0 2.49617e-7 -1 0 0 -1 0 0 -1 0 4.48039e-7 -1 5.09341e-7 -2.63854e-7 -1 0 4.37079e-7 -1 0 -4.06651e-7 -1 0 2.29588e-7 -1 5.69544e-7 0 -1 0 -2.4069e-7 -1 3.73178e-7 0 -1 4.14273e-7 0 -1 0 0 -1 1.37189e-7 0 -1 0 1.83275e-6 -1 -1.41934e-6 -1.71328e-7 -1 0 -1.89789e-7 -1 -6.93926e-7 6.94293e-7 -1 2.92089e-6 1.84894e-7 -1 -4.802e-7 4.02724e-7 -1 -2.21016e-6 0 -1 -1.35567e-7 -4.48066e-7 -1 -5.86769e-7 -9.25239e-7 -1 2.78225e-6 1 0 2.10034e-7 0 -8.96729e-6 -1 -5.67645e-7 1 -2.14495e-6 1.05754e-6 1 1.19418e-6 1.2192e-6 1 -1.28323e-6 -8.4968e-7 1 1.7886e-6 6.74843e-7 1 6.59049e-7 -5.2197e-7 1 0 1.23626e-7 1 0 -5.17986e-7 1 5.62355e-7 0 1 -1.39085e-7 0 1 -1.301e-7 3.00725e-7 1 0 4.05264e-7 1 0 9.44219e-7 1 -5.8652e-7 7.32604e-7 1 -6.86705e-7 2.05287e-7 1 0 -1.32146e-6 1 -6.40664e-7 -6.21222e-7 1 4.50814e-7 4.93527e-7 1 -2.71231e-7 1.05734e-6 1 4.51083e-7 8.43061e-7 1 3.62309e-7 0 1 0 0 1 -2.54671e-7 -4.99234e-7 1 -6.30088e-7 0 1 0 0 1 5.92202e-7 4.48603e-7 1 -1.21027e-6 5.27711e-7 1 5.60599e-7 -4.11366e-7 1 -5.65789e-7 0 1 0 0 1 6.51063e-7 0 1 -5.97083e-7 0 1 0 8.04275e-7 1 1.46335e-6 1.27787e-6 1 -3.37421e-7 8.64686e-7 1 -1.77987e-6 -1.7219e-7 1 -1.53889e-6 0 1 8.54067e-7 1.42626e-7 1 9.60403e-7 -2.92164e-7 1 1.93388e-6 7.95925e-7 1 0 -8.55035e-7 1 -2.68235e-6 2.80469e-7 1 5.42269e-7 0 1 1.39112e-6 -1 -1.98032e-6 0 -1.84912e-7 0 1 1 2.33552e-6 0 0.05628144 1.49299e-6 -0.998415 0.1700982 0 -0.9854272 0.2877005 1.83311e-6 -0.9577205 0.411174 1.79669e-6 -0.9115568 0.5415688 0 -0.8406564 0.677082 -6.59112e-6 -0.7359077 0.8100491 2.37597e-6 -0.5863622 0.9233176 0 -0.3840374 0.9909003 0 -0.1345977 0.05740696 0 0.9983509 0.1734334 3.05552e-6 0.9848456 0.2929963 0 0.9561136 0.4180241 0 0.908436 0.5492108 -2.74142e-6 0.835684 0.6843631 0 0.7291414 0.8155521 0 0.5786838 0.9259904 -1.83887e-6 0.3775475 0.991252 0 0.1319832 -0.05627518 0 -0.9984154 -0.1701086 -1.46052e-6 -0.9854254 -0.2877048 0 -0.9577192 -0.4111776 0 -0.9115552 -0.5415547 0 -0.8406656 -0.5415782 -5.79904e-7 -0.8406504 -0.5415646 0 -0.8406592 -0.6770725 0 -0.7359163 -0.8100597 -8.40943e-7 -0.5863475 -0.9233122 -1.27048e-6 -0.3840506 -0.9909021 -1.98278e-6 -0.1345849 -0.05740737 0 0.9983509 -0.173434 0 0.9848456 -0.2929974 0 0.9561133 -0.41802 0 0.9084379 -0.5491979 0 0.8356925 -0.6843639 0 0.7291407 -0.8155586 0 0.5786747 -0.9259859 -1.249e-6 0.3775582 -0.991253 -1.94434e-6 0.1319757 0 1.49455e-6 -1 0.04619568 0.9989325 0 0.1410092 0.9900083 0 0.2434225 0.9699203 0 0.3595672 0.9331192 0 0.4965986 0.8679803 0 0.6599715 0.7512907 0 0.8399556 0.5426552 0 0.978698 0.2053056 0 0.9786998 -0.2052971 0 0.8399519 -0.5426608 0 0.6599648 -0.7512966 0 0.4966011 -0.8679789 0 0.3595672 -0.9331192 0 0.2434237 -0.9699201 0 0.1410086 -0.9900084 0 0.04619604 -0.9989325 0 -0.04619586 -0.9989325 0 -0.2434231 -0.9699203 0 -0.3595672 -0.9331192 0 -0.6599681 -0.7512936 0 -0.8399574 -0.5426524 0 -0.9786998 -0.2052971 0 -0.9786998 0.2052971 0 -0.8399538 0.542658 0 -0.6599665 0.7512952 0 -0.3595672 0.9331192 0 -0.2434237 0.9699201 0 -4.98155e-6 0 -1 -6.68299e-6 0 -1 1.61257e-5 0 -1 -1.64417e-5 0 -1 8.14323e-6 0 -1 3.89208e-6 0 -1 -3.89208e-6 0 -1 4.98155e-6 0 -1 -1.61258e-5 0 -1 1.64418e-5 0 -1 6.68299e-6 0 -1 -0.04619586 0.9989325 0 -7.78416e-6 0 1 1.01248e-5 0 1 7.78416e-6 0 1 -1.01248e-5 0 1 -1 0 0 -1 7.69657e-7 0 1 -4.06904e-7 0 1 1.86275e-6 0 -1.12211e-6 0 -1 2.18922e-6 0 -1 1.56308e-6 -0.6168267 -0.787099 0 -0.6168264 -0.7870993 -1.90279e-6 -0.6168264 -0.7870993 0 -0.6168207 -0.7871038 0 0.3212496 0.9469946 0 0.7851824 0.6192645 0 0.9784547 0.2064616 - - - - - - - - - - 0.5007404 0.830685 0.5076314 0.8354339 0.5073733 0.8360697 0.500065 0.824156 0.4859077 0.8155372 0.5002436 0.815845 0.4853675 0.8396666 0.4784291 0.8363548 0.4785733 0.8356276 0.4999471 0.8490186 0.4853675 0.8396666 0.5002809 0.8402333 0.5006669 0.7961355 0.4861779 0.8029572 0.486331 0.7958275 0.4969882 0.8290002 0.4888546 0.8285199 0.4857291 0.8238483 0.5002809 0.8402333 0.4853675 0.8396666 0.4969598 0.8395383 0.5004198 0.8076414 0.4861779 0.8029572 0.5005137 0.8032652 0.4860346 0.8096311 0.5002436 0.815845 0.4859077 0.8155372 0.4860346 0.8096311 0.5003852 0.8092535 0.5003704 0.809939 0.4860492 0.8089455 0.5004017 0.8084828 0.5003852 0.8092535 0.4860659 0.8081748 0.5004198 0.8076414 0.5004017 0.8084828 0.4945167 0.8322377 0.4979584 0.8310282 0.4969598 0.8395383 0.4945167 0.8322377 0.4888546 0.8285199 0.4969882 0.8290002 0.4914219 0.8327345 0.4876618 0.8308692 0.4888546 0.8285199 0.4914219 0.8327345 0.4969598 0.8395383 0.4885352 0.8392466 0.8921794 0.8188005 0.9731254 0.8133014 0.8947296 0.8155754 0.8947296 0.8155754 0.8843776 0.6857315 0.8921794 0.8188005 0.2754488 0.06576979 0.2906534 0.0761187 0.3287903 0.0761187 0.3287901 0.169075 0.2906534 0.169075 0.2754489 0.1735655 0.9731254 0.8133014 0.9799084 0.6857315 0.9765109 0.6886113 0.9765109 0.6886113 0.8843776 0.6857315 0.8880929 0.6893728 0.9564946 0.7000287 0.9588335 0.7002387 0.9765109 0.6886113 0.9572245 0.8089081 0.9140732 0.8099195 0.9731254 0.8133014 0.2927002 0.0928024 0.2885748 0.1510023 0.2902469 0.1505628 0.3244653 0.09002608 0.2983357 0.08762753 0.2984142 0.08920431 0.3294562 0.09377902 0.3322029 0.1511779 0.3310532 0.09343248 0.3249723 0.1563245 0.3258356 0.1544823 0.324769 0.1546205 0.3261861 0.1561411 0.3268509 0.1542433 0.3258356 0.1544823 0.3273678 0.1558468 0.327791 0.153877 0.3268509 0.1542433 0.328529 0.1554509 0.3286319 0.1534525 0.327791 0.153877 0.329343 0.1529655 0.3295677 0.1548765 0.3304386 0.1542012 0.3311147 0.153471 0.329343 0.1529655 0.3304386 0.1542012 0.3316528 0.1527283 0.3298951 0.1524841 0.3311147 0.153471 0.3319883 0.151939 0.3302908 0.1519594 0.3316528 0.1527283 0.3306484 0.1507698 0.3319883 0.151939 0.3322029 0.1511779 0.3246645 0.08854556 0.3254154 0.09016066 0.3257231 0.08871042 0.3257231 0.08871042 0.3263039 0.09038907 0.3267757 0.08897137 0.3263039 0.09038907 0.3277873 0.08935672 0.3267757 0.08897137 0.3277873 0.08935672 0.327825 0.09109687 0.3286674 0.08989942 0.327825 0.09109687 0.3294321 0.09049677 0.3286674 0.08989942 0.3284206 0.09155541 0.3300576 0.09117478 0.3294321 0.09049677 0.3288856 0.09205555 0.3305279 0.09190595 0.3300576 0.09117478 0.3292186 0.09258925 0.3308496 0.09266239 0.3305279 0.09190595 0.3294073 0.09315419 0.3310532 0.09343248 0.3308496 0.09266239 0.2950702 0.1545408 0.2959271 0.1563245 0.296113 0.154658 0.2950702 0.1545408 0.2935646 0.1558846 0.2947442 0.1561484 0.2940824 0.1542893 0.2924082 0.1554722 0.2935646 0.1558846 0.2923479 0.1534936 0.2924082 0.1554722 0.2931682 0.1539248 0.2911306 0.154683 0.2921109 0.1533271 0.2905337 0.1542284 0.2897739 0.1534824 0.2916386 0.1529688 0.2910822 0.1524038 0.2891993 0.1526696 0.2910822 0.1524038 0.2906611 0.1518073 0.2887998 0.1518319 0.2906611 0.1518073 0.290382 0.1511945 0.2887998 0.1518319 0.2902469 0.1505628 0.2885748 0.1510023 0.2974165 0.0892378 0.2983357 0.08762753 0.2972151 0.08770042 0.2964681 0.0893864 0.2972151 0.08770042 0.2961078 0.08788305 0.2964681 0.0893864 0.295009 0.08816683 0.2955926 0.08964717 0.2948026 0.09000319 0.295009 0.08816683 0.2940127 0.0886439 0.2931138 0.08921176 0.2948026 0.09000319 0.2940127 0.0886439 0.2923485 0.08990609 0.2941394 0.0904535 0.2931138 0.08921176 0.2923485 0.08990609 0.2931835 0.0915476 0.2936068 0.09097713 0.2917989 0.09070253 0.2928786 0.09215772 0.2931835 0.0915476 0.291114 0.09227442 0.2928786 0.09215772 0.2914117 0.09149652 0.296113 0.154658 0.3249723 0.1563245 0.324769 0.1546205 0.8095047 0.4018982 0.8377692 0.3736336 0.8095047 0.3736336 0.8095047 0.4301629 0.8377692 0.4018982 0.8095047 0.4018982 0.8095047 0.4584275 0.8377692 0.4301629 0.8095047 0.4301629 0.8095047 0.4866921 0.8377692 0.4584275 0.8095047 0.4584275 0.7812401 0.4584275 0.8095047 0.4301629 0.7812401 0.4301629 0.8377692 0.4584275 0.866034 0.4301629 0.8377692 0.4301629 0.6963178 0.1215696 0.7016612 0.2070655 0.7016612 0.1215696 0.6909742 0.1215696 0.6963178 0.2070655 0.6963178 0.1215696 0.6856308 0.1215696 0.6909742 0.2070655 0.6909742 0.1215696 0.6802873 0.1215696 0.6856308 0.2070655 0.6856308 0.1215696 0.6749436 0.1215696 0.6802873 0.2070655 0.6802873 0.1215696 0.6696003 0.1215696 0.6749438 0.2070655 0.6749436 0.1215696 0.6642567 0.1215696 0.6696003 0.2070655 0.6696003 0.1215696 0.6589133 0.1215696 0.6642568 0.2070655 0.6642567 0.1215696 0.6535698 0.1215696 0.6589133 0.2070655 0.6589133 0.1215696 0.6482263 0.1215696 0.6535698 0.2070655 0.6535698 0.1215696 0.6428828 0.1215696 0.6482263 0.2070655 0.6482263 0.1215696 0.6375393 0.1215696 0.6428828 0.2070655 0.6428828 0.1215696 0.6321957 0.1215696 0.6375393 0.2070655 0.6375393 0.1215696 0.6268524 0.1215696 0.6321959 0.2070655 0.6321957 0.1215696 0.6215088 0.1215696 0.6268524 0.2070655 0.6268524 0.1215696 0.6161653 0.1215696 0.621509 0.2070655 0.6215088 0.1215696 0.6108217 0.1215696 0.6161653 0.2070655 0.6161653 0.1215696 0.6054783 0.1215696 0.6108219 0.2070655 0.6108217 0.1215696 0.6001348 0.1215696 0.6054783 0.2070655 0.6054783 0.1215696 0.5947914 0.1215696 0.6001348 0.2070655 0.6001348 0.1215696 0.5894477 0.1215696 0.5947914 0.2070655 0.5947914 0.1215696 0.5841044 0.1215696 0.5894477 0.2070655 0.5894477 0.1215696 0.5787608 0.1215696 0.5841044 0.2070655 0.5841044 0.1215696 0.5734174 0.1215696 0.5787608 0.2070655 0.5787608 0.1215696 0.5680738 0.1215696 0.5734174 0.2070655 0.5734174 0.1215696 0.5627304 0.1215696 0.5680738 0.2070655 0.5680738 0.1215696 0.5573868 0.1215696 0.5627304 0.2070655 0.5627304 0.1215696 0.5520434 0.1215696 0.5573868 0.2070655 0.5573868 0.1215696 0.5466999 0.1215696 0.5520434 0.2070655 0.5520434 0.1215696 0.5413563 0.1215696 0.5466999 0.2070655 0.5466999 0.1215696 0.6677758 0.9787821 0.6699202 0.9773492 0.6489841 0.9633601 0.5360129 0.1215696 0.5413563 0.2070655 0.5413563 0.1215696 0.5306695 0.1215696 0.5360129 0.2070655 0.5360129 0.1215696 0.68311 0.9770907 0.6812863 0.975267 0.7040461 0.9707398 0.5124125 0.8091965 0.5121636 0.8098093 0.5188053 0.8143863 0.5331016 0.8289863 0.5194563 0.820679 0.5192843 0.8286894 0.5339991 0.8145766 0.5404065 0.8102129 0.5401706 0.8096225 0.5336221 0.8057296 0.51957 0.7967161 0.5192483 0.8051835 0.5328411 0.841111 0.5188763 0.8476861 0.5326935 0.8479827 0.5224218 0.8160102 0.5194563 0.820679 0.5332735 0.8209759 0.5224492 0.8058534 0.5305691 0.8061345 0.5336221 0.8057296 0.5328411 0.841111 0.5191144 0.8365963 0.5190238 0.8408142 0.5192843 0.8286894 0.5329793 0.8346786 0.5331016 0.8289863 0.5191478 0.8350425 0.5329793 0.8346786 0.5191619 0.8343817 0.5191318 0.8357854 0.5329651 0.8353394 0.5191478 0.8350425 0.5191144 0.8365963 0.5329492 0.8360822 0.5191318 0.8357854 0.5214868 0.8140555 0.524804 0.8128898 0.5224492 0.8058534 0.5302612 0.8164731 0.524804 0.8128898 0.5224218 0.8160102 0.5314108 0.8142089 0.5277867 0.812411 0.5302612 0.8164731 0.5224492 0.8058534 0.5277867 0.812411 0.5305691 0.8061345 0.5080288 0.8374975 0.5113428 0.8403623 0.506676 0.8457612 0.506676 0.8457612 0.5002809 0.8402333 0.5080288 0.8374975 0.5002809 0.8402333 0.5007404 0.830685 0.5073733 0.8360697 0.5080288 0.8374975 0.5002809 0.8402333 0.5075191 0.8368272 0.5007404 0.830685 0.5052038 0.8255214 0.5076314 0.8354339 0.5052038 0.8255214 0.5114973 0.8309615 0.5076314 0.8354339 0.5075191 0.8368272 0.5002809 0.8402333 0.5073733 0.8360697 0.500065 0.824156 0.4857291 0.8238483 0.4859077 0.8155372 0.4783285 0.8350152 0.4746369 0.8306964 0.4807141 0.8255014 0.4807141 0.8255014 0.4849764 0.8304876 0.4783285 0.8350152 0.4849764 0.8304876 0.4853675 0.8396666 0.4785733 0.8356276 0.4783285 0.8350152 0.4849764 0.8304876 0.4785733 0.8356276 0.4853675 0.8396666 0.4791922 0.8449453 0.4779358 0.8369964 0.4791922 0.8449453 0.4747356 0.8397319 0.4779358 0.8369964 0.4853675 0.8396666 0.4779358 0.8369964 0.4784291 0.8363548 0.4999471 0.8490186 0.4850336 0.8484517 0.4853675 0.8396666 0.5006669 0.7961355 0.5005137 0.8032652 0.4861779 0.8029572 0.4888546 0.8285199 0.4876618 0.8308692 0.4849764 0.8304876 0.500065 0.824156 0.5007404 0.830685 0.4969882 0.8290002 0.5007404 0.830685 0.4979584 0.8310282 0.4969882 0.8290002 0.4888546 0.8285199 0.4849764 0.8304876 0.4857291 0.8238483 0.500065 0.824156 0.4969882 0.8290002 0.4857291 0.8238483 0.4979584 0.8310282 0.5007404 0.830685 0.4969598 0.8395383 0.5007404 0.830685 0.5002809 0.8402333 0.4969598 0.8395383 0.4853675 0.8396666 0.4849764 0.8304876 0.4885352 0.8392466 0.4849764 0.8304876 0.4876618 0.8308692 0.4885352 0.8392466 0.4853675 0.8396666 0.4885352 0.8392466 0.4969598 0.8395383 0.5004198 0.8076414 0.4860839 0.8073334 0.4861779 0.8029572 0.4860346 0.8096311 0.5003704 0.809939 0.5002436 0.815845 0.4860346 0.8096311 0.4860492 0.8089455 0.5003852 0.8092535 0.4860492 0.8089455 0.4860659 0.8081748 0.5004017 0.8084828 0.4860659 0.8081748 0.4860839 0.8073334 0.5004198 0.8076414 0.4945167 0.8322377 0.4969882 0.8290002 0.4979584 0.8310282 0.4945167 0.8322377 0.4914219 0.8327345 0.4888546 0.8285199 0.4914219 0.8327345 0.4885352 0.8392466 0.4876618 0.8308692 0.4914219 0.8327345 0.4945167 0.8322377 0.4969598 0.8395383 0.8921794 0.8188005 0.97556 0.8156581 0.9731254 0.8133014 0.8947296 0.8155754 0.8880929 0.6893728 0.8843776 0.6857315 0.2754489 0.1735655 0.2848749 0.1675887 0.2841488 0.1671209 0.2754489 0.1735655 0.2841488 0.1671209 0.2833 0.1663399 0.3361436 0.1663399 0.3352947 0.1671209 0.3475242 0.1735655 0.336769 0.1654759 0.3361436 0.1663399 0.3475242 0.1735655 0.2754489 0.1735655 0.2833 0.1663399 0.2826745 0.1654758 0.2754489 0.1735655 0.2826745 0.1654758 0.2822915 0.1645549 0.3371521 0.1645549 0.336769 0.1654759 0.3475242 0.1735655 0.3372811 0.163605 0.3371521 0.1645549 0.3475242 0.1735655 0.2754489 0.1735655 0.2822915 0.1645549 0.2821625 0.163605 0.2754489 0.1735655 0.2821625 0.163605 0.2821625 0.08169877 0.3372811 0.163605 0.3475242 0.1735655 0.3372811 0.08169883 0.3475242 0.1735655 0.3475243 0.06576985 0.3372811 0.08169883 0.2754488 0.06576979 0.2754489 0.1735655 0.2821625 0.08169877 0.2754488 0.06576979 0.2821625 0.08169877 0.2822915 0.08072978 0.3371522 0.08072978 0.3372811 0.08169883 0.3475243 0.06576985 0.3367691 0.07979029 0.3371522 0.08072978 0.3475243 0.06576985 0.2754488 0.06576979 0.2822915 0.08072978 0.2826745 0.07979023 0.2754488 0.06576979 0.2826745 0.07979023 0.2833 0.0789088 0.3361436 0.0789088 0.3367691 0.07979029 0.3475243 0.06576985 0.3352947 0.07811206 0.3361436 0.0789088 0.3475243 0.06576985 0.2754488 0.06576979 0.2833 0.0789088 0.2841489 0.078112 0.2754488 0.06576979 0.2841489 0.078112 0.2851956 0.0774241 0.334248 0.0774241 0.3352947 0.07811206 0.3475243 0.06576985 0.3330356 0.07686626 0.334248 0.0774241 0.3475243 0.06576985 0.2754488 0.06576979 0.2851956 0.0774241 0.286408 0.0768662 0.2754488 0.06576979 0.286408 0.0768662 0.2877493 0.07645523 0.3316944 0.07645523 0.3330356 0.07686626 0.3475243 0.06576985 0.3302648 0.07620346 0.3316944 0.07645523 0.3475243 0.06576985 0.3475243 0.06576985 0.2754488 0.06576979 0.3287903 0.0761187 0.2754488 0.06576979 0.2877493 0.07645523 0.2891788 0.07620346 0.2754488 0.06576979 0.2891788 0.07620346 0.2906534 0.0761187 0.3287903 0.0761187 0.3302648 0.07620346 0.3475243 0.06576985 0.3475242 0.1735655 0.3352947 0.1671209 0.334248 0.1677953 0.3475242 0.1735655 0.334248 0.1677953 0.3330356 0.1683421 0.2851956 0.1677953 0.2848749 0.1675887 0.2754489 0.1735655 0.286408 0.1683421 0.2851956 0.1677953 0.2754489 0.1735655 0.3475242 0.1735655 0.3330356 0.1683421 0.3316943 0.168745 0.3475242 0.1735655 0.3316943 0.168745 0.3302648 0.1689918 0.2877492 0.168745 0.286408 0.1683421 0.2754489 0.1735655 0.2891788 0.1689918 0.2877492 0.168745 0.2754489 0.1735655 0.2754489 0.1735655 0.3475242 0.1735655 0.3287901 0.169075 0.3475242 0.1735655 0.3302648 0.1689918 0.3287901 0.169075 0.2906534 0.169075 0.2891788 0.1689918 0.2754489 0.1735655 0.9731254 0.8133014 0.97556 0.8156581 0.9799084 0.6857315 0.9765109 0.6886113 0.9799084 0.6857315 0.8843776 0.6857315 0.8947296 0.8155754 0.9060197 0.8079622 0.9049687 0.8071094 0.8947296 0.8155754 0.9049687 0.8071094 0.904169 0.8061326 0.9649806 0.8065456 0.9641435 0.8070634 0.9731254 0.8133014 0.9659811 0.8057043 0.9649806 0.8065456 0.9731254 0.8133014 0.8947296 0.8155754 0.904169 0.8061326 0.9036445 0.805044 0.8947296 0.8155754 0.9036445 0.805044 0.9034231 0.8038603 0.9667551 0.8047402 0.9659811 0.8057043 0.9731254 0.8133014 0.9672793 0.8036478 0.9667551 0.8047402 0.9731254 0.8133014 0.8880929 0.6893728 0.8947296 0.8155754 0.8984242 0.7081357 0.8947296 0.8155754 0.9034231 0.8038603 0.8984242 0.7081357 0.9675149 0.802425 0.9672793 0.8036478 0.9731254 0.8133014 0.9689385 0.7080152 0.9675149 0.802425 0.9731254 0.8133014 0.8880929 0.6893728 0.8984242 0.7081357 0.8986919 0.7068122 0.8880929 0.6893728 0.8986919 0.7068122 0.8992735 0.7055537 0.9689385 0.7080152 0.9731254 0.8133014 0.9765109 0.6886113 0.9687156 0.7065795 0.9689385 0.7080152 0.9765109 0.6886113 0.8880929 0.6893728 0.8992735 0.7055537 0.9001449 0.704392 0.8880929 0.6893728 0.9001449 0.704392 0.9012826 0.7033532 0.9681384 0.7052429 0.9687156 0.7065795 0.9765109 0.6886113 0.9672423 0.704029 0.9681384 0.7052429 0.9765109 0.6886113 0.8880929 0.6893728 0.9012826 0.7033532 0.9026654 0.7024595 0.8880929 0.6893728 0.9026654 0.7024595 0.9042732 0.701732 0.9660572 0.702952 0.9672423 0.704029 0.9765109 0.6886113 0.9646071 0.7020233 0.9660572 0.702952 0.9765109 0.6886113 0.8880929 0.6893728 0.9042732 0.701732 0.9060864 0.701192 0.8880929 0.6893728 0.9060864 0.701192 0.9080862 0.7008622 0.9629101 0.7012534 0.9646071 0.7020233 0.9765109 0.6886113 0.9609804 0.7006535 0.9629101 0.7012534 0.9765109 0.6886113 0.9765109 0.6886113 0.8880929 0.6893728 0.9102566 0.7007664 0.8880929 0.6893728 0.9080862 0.7008622 0.9102566 0.7007664 0.9588335 0.7002387 0.9609804 0.7006535 0.9765109 0.6886113 0.9765109 0.6886113 0.9102566 0.7007664 0.9564946 0.7000287 0.9072996 0.8086799 0.9060197 0.8079622 0.8947296 0.8155754 0.9731254 0.8133014 0.9641435 0.8070634 0.9637351 0.8073241 0.9731254 0.8133014 0.9637351 0.8073241 0.9623251 0.8079389 0.908782 0.8092501 0.9072996 0.8086799 0.8947296 0.8155754 0.9104339 0.8096583 0.908782 0.8092501 0.8947296 0.8155754 0.9731254 0.8133014 0.9623251 0.8079389 0.9607431 0.8084216 0.9731254 0.8133014 0.9607431 0.8084216 0.959027 0.8087527 0.912214 0.8098873 0.9104339 0.8096583 0.8947296 0.8155754 0.9140732 0.8099195 0.912214 0.8098873 0.8947296 0.8155754 0.8947296 0.8155754 0.9731254 0.8133014 0.9140732 0.8099195 0.9731254 0.8133014 0.959027 0.8087527 0.9572245 0.8089081 0.2927002 0.0928024 0.291114 0.09227442 0.2885748 0.1510023 0.3244653 0.09002608 0.3246645 0.08854556 0.2983357 0.08762753 0.3294562 0.09377902 0.3306484 0.1507698 0.3322029 0.1511779 0.3249723 0.1563245 0.3261861 0.1561411 0.3258356 0.1544823 0.3261861 0.1561411 0.3273678 0.1558468 0.3268509 0.1542433 0.3273678 0.1558468 0.328529 0.1554509 0.327791 0.153877 0.328529 0.1554509 0.3295677 0.1548765 0.3286319 0.1534525 0.329343 0.1529655 0.3286319 0.1534525 0.3295677 0.1548765 0.3311147 0.153471 0.3298951 0.1524841 0.329343 0.1529655 0.3316528 0.1527283 0.3302908 0.1519594 0.3298951 0.1524841 0.3319883 0.151939 0.3305361 0.1513991 0.3302908 0.1519594 0.3306484 0.1507698 0.3305361 0.1513991 0.3319883 0.151939 0.3246645 0.08854556 0.3244653 0.09002608 0.3254154 0.09016066 0.3257231 0.08871042 0.3254154 0.09016066 0.3263039 0.09038907 0.3263039 0.09038907 0.3271165 0.09070974 0.3277873 0.08935672 0.3277873 0.08935672 0.3271165 0.09070974 0.327825 0.09109687 0.327825 0.09109687 0.3284206 0.09155541 0.3294321 0.09049677 0.3284206 0.09155541 0.3288856 0.09205555 0.3300576 0.09117478 0.3288856 0.09205555 0.3292186 0.09258925 0.3305279 0.09190595 0.3292186 0.09258925 0.3294073 0.09315419 0.3308496 0.09266239 0.3294073 0.09315419 0.3294562 0.09377902 0.3310532 0.09343248 0.2950702 0.1545408 0.2947442 0.1561484 0.2959271 0.1563245 0.2950702 0.1545408 0.2940824 0.1542893 0.2935646 0.1558846 0.2940824 0.1542893 0.2931682 0.1539248 0.2924082 0.1554722 0.2923479 0.1534936 0.2913896 0.1548652 0.2924082 0.1554722 0.2911306 0.154683 0.2913896 0.1548652 0.2923479 0.1534936 0.2923479 0.1534936 0.2921109 0.1533271 0.2911306 0.154683 0.2921109 0.1533271 0.2916386 0.1529688 0.2905337 0.1542284 0.2897739 0.1534824 0.2905337 0.1542284 0.2916386 0.1529688 0.2891993 0.1526696 0.2897739 0.1534824 0.2910822 0.1524038 0.2887998 0.1518319 0.2891993 0.1526696 0.2906611 0.1518073 0.2887998 0.1518319 0.290382 0.1511945 0.2902469 0.1505628 0.2974165 0.0892378 0.2984142 0.08920431 0.2983357 0.08762753 0.2964681 0.0893864 0.2974165 0.0892378 0.2972151 0.08770042 0.2964681 0.0893864 0.2961078 0.08788305 0.295009 0.08816683 0.2948026 0.09000319 0.2955926 0.08964717 0.295009 0.08816683 0.2931138 0.08921176 0.2941394 0.0904535 0.2948026 0.09000319 0.2923485 0.08990609 0.2936068 0.09097713 0.2941394 0.0904535 0.2923485 0.08990609 0.2917989 0.09070253 0.2931835 0.0915476 0.2917989 0.09070253 0.2914117 0.09149652 0.2928786 0.09215772 0.291114 0.09227442 0.2927002 0.0928024 0.2928786 0.09215772 0.296113 0.154658 0.2959271 0.1563245 0.3249723 0.1563245 0.8095047 0.4018982 0.8377692 0.4018982 0.8377692 0.3736336 0.8095047 0.4301629 0.8377692 0.4301629 0.8377692 0.4018982 0.8095047 0.4584275 0.8377692 0.4584275 0.8377692 0.4301629 0.8095047 0.4866921 0.8377692 0.4866921 0.8377692 0.4584275 0.7812401 0.4584275 0.8095047 0.4584275 0.8095047 0.4301629 0.8377692 0.4584275 0.866034 0.4584275 0.866034 0.4301629 0.6963178 0.1215696 0.6963178 0.2070655 0.7016612 0.2070655 0.6909742 0.1215696 0.6909742 0.2070655 0.6963178 0.2070655 0.6856308 0.1215696 0.6856308 0.2070655 0.6909742 0.2070655 0.6802873 0.1215696 0.6802873 0.2070655 0.6856308 0.2070655 0.6749436 0.1215696 0.6749438 0.2070655 0.6802873 0.2070655 0.6696003 0.1215696 0.6696003 0.2070655 0.6749438 0.2070655 0.6642567 0.1215696 0.6642568 0.2070655 0.6696003 0.2070655 0.6589133 0.1215696 0.6589133 0.2070655 0.6642568 0.2070655 0.6535698 0.1215696 0.6535698 0.2070655 0.6589133 0.2070655 0.6482263 0.1215696 0.6482263 0.2070655 0.6535698 0.2070655 0.6428828 0.1215696 0.6428828 0.2070655 0.6482263 0.2070655 0.6375393 0.1215696 0.6375393 0.2070655 0.6428828 0.2070655 0.6321957 0.1215696 0.6321959 0.2070655 0.6375393 0.2070655 0.6268524 0.1215696 0.6268524 0.2070655 0.6321959 0.2070655 0.6215088 0.1215696 0.621509 0.2070655 0.6268524 0.2070655 0.6161653 0.1215696 0.6161653 0.2070655 0.621509 0.2070655 0.6108217 0.1215696 0.6108219 0.2070655 0.6161653 0.2070655 0.6054783 0.1215696 0.6054783 0.2070655 0.6108219 0.2070655 0.6001348 0.1215696 0.6001348 0.2070655 0.6054783 0.2070655 0.5947914 0.1215696 0.5947914 0.2070655 0.6001348 0.2070655 0.5894477 0.1215696 0.5894477 0.2070655 0.5947914 0.2070655 0.5841044 0.1215696 0.5841044 0.2070655 0.5894477 0.2070655 0.5787608 0.1215696 0.5787608 0.2070655 0.5841044 0.2070655 0.5734174 0.1215696 0.5734174 0.2070655 0.5787608 0.2070655 0.5680738 0.1215696 0.5680738 0.2070655 0.5734174 0.2070655 0.5627304 0.1215696 0.5627304 0.2070655 0.5680738 0.2070655 0.5573868 0.1215696 0.5573868 0.2070655 0.5627304 0.2070655 0.5520434 0.1215696 0.5520434 0.2070655 0.5573868 0.2070655 0.5466999 0.1215696 0.5466999 0.2070655 0.5520434 0.2070655 0.5413563 0.1215696 0.5413563 0.2070655 0.5466999 0.2070655 0.6717439 0.9755256 0.6731768 0.9733811 0.6532276 0.9570093 0.6731768 0.9733811 0.6741637 0.9709984 0.655372 0.9555764 0.6741637 0.9709984 0.6746669 0.9684689 0.6577548 0.9545894 0.6746669 0.9684689 0.6746669 0.9658898 0.6602844 0.9540863 0.6746669 0.9658898 0.6741638 0.9633601 0.6628635 0.9540863 0.6741638 0.9633601 0.6731768 0.9609774 0.665393 0.9545894 0.6731768 0.9609774 0.6717439 0.958833 0.6677758 0.9555764 0.6717439 0.958833 0.6699202 0.9570093 0.6677758 0.9555764 0.6677758 0.9555764 0.665393 0.9545894 0.6731768 0.9609774 0.665393 0.9545894 0.6628635 0.9540863 0.6741638 0.9633601 0.6628635 0.9540863 0.6602844 0.9540863 0.6746669 0.9658898 0.6602844 0.9540863 0.6577548 0.9545894 0.6746669 0.9684689 0.6577548 0.9545894 0.655372 0.9555764 0.6741637 0.9709984 0.655372 0.9555764 0.6532276 0.9570093 0.6731768 0.9733811 0.6532276 0.9570093 0.6514039 0.9588329 0.6717439 0.9755256 0.6514039 0.9588329 0.6499711 0.9609774 0.6717439 0.9755256 0.6499711 0.9609774 0.6489841 0.9633601 0.6699202 0.9773492 0.6717439 0.9755256 0.6499711 0.9609774 0.6699202 0.9773492 0.6489841 0.9633601 0.648481 0.9658898 0.6677758 0.9787821 0.648481 0.9658898 0.648481 0.9684689 0.665393 0.9797691 0.6677758 0.9787821 0.648481 0.9658898 0.665393 0.9797691 0.648481 0.9684689 0.6489841 0.9709984 0.6628635 0.9802722 0.6489841 0.9709984 0.6499711 0.9733811 0.6602844 0.9802722 0.6628635 0.9802722 0.6489841 0.9709984 0.6602844 0.9802722 0.6499711 0.9733811 0.6514039 0.9755256 0.655372 0.9787821 0.6514039 0.9755256 0.6532276 0.9773492 0.655372 0.9787821 0.655372 0.9787821 0.6577548 0.9797691 0.6499711 0.9733811 0.6577548 0.9797691 0.6602844 0.9802722 0.6499711 0.9733811 0.6628635 0.9802722 0.665393 0.9797691 0.648481 0.9684689 0.5360129 0.1215696 0.5360129 0.2070655 0.5413563 0.2070655 0.5306695 0.1215696 0.5306695 0.2070655 0.5360129 0.2070655 0.6798534 0.9731225 0.6788665 0.9707398 0.7040461 0.9631017 0.6788665 0.9707398 0.6783633 0.9682103 0.7030592 0.9607189 0.6783633 0.9682103 0.6783633 0.9656312 0.7030592 0.9607189 0.6783633 0.9656312 0.6788665 0.9631017 0.7016263 0.9585745 0.7030592 0.9607189 0.6783633 0.9656312 0.7016263 0.9585745 0.6788665 0.9631017 0.6798534 0.9607189 0.6976582 0.9553179 0.6798534 0.9607189 0.6812863 0.9585745 0.6952754 0.9543309 0.6812863 0.9585745 0.68311 0.9567507 0.6952754 0.9543309 0.68311 0.9567507 0.6852545 0.9553179 0.6927459 0.9538277 0.6952754 0.9543309 0.68311 0.9567507 0.6927459 0.9538277 0.6852545 0.9553179 0.6876372 0.9543309 0.6901668 0.9538277 0.6901668 0.9538277 0.6927459 0.9538277 0.6852545 0.9553179 0.6952754 0.9543309 0.6976582 0.9553179 0.6798534 0.9607189 0.6976582 0.9553179 0.6998026 0.9567507 0.6788665 0.9631017 0.6998026 0.9567507 0.7016263 0.9585745 0.6788665 0.9631017 0.7030592 0.9607189 0.7040461 0.9631017 0.6788665 0.9707398 0.7040461 0.9631017 0.7045493 0.9656312 0.6798534 0.9731225 0.7045493 0.9656312 0.7045493 0.9682103 0.6798534 0.9731225 0.7045493 0.9682103 0.7040461 0.9707398 0.6812863 0.975267 0.6798534 0.9731225 0.7045493 0.9682103 0.6812863 0.975267 0.7040461 0.9707398 0.7030592 0.9731225 0.6852545 0.9785236 0.7030592 0.9731225 0.7016263 0.975267 0.6876372 0.9795105 0.7016263 0.975267 0.6998026 0.9770907 0.6876372 0.9795105 0.6998026 0.9770907 0.6976582 0.9785236 0.6901668 0.9800137 0.6876372 0.9795105 0.6998026 0.9770907 0.6901668 0.9800137 0.6976582 0.9785236 0.6952754 0.9795105 0.6927459 0.9800137 0.6927459 0.9800137 0.6901668 0.9800137 0.6976582 0.9785236 0.6876372 0.9795105 0.6852545 0.9785236 0.7030592 0.9731225 0.6852545 0.9785236 0.68311 0.9770907 0.7040461 0.9707398 0.5130846 0.7998557 0.5085866 0.8050592 0.5117807 0.8078202 0.5130846 0.7998557 0.5117807 0.8078202 0.5192483 0.8051835 0.5117807 0.8078202 0.512272 0.8084664 0.5192483 0.8051835 0.5188053 0.8143863 0.5192483 0.8051835 0.5124125 0.8091965 0.5084376 0.8141199 0.5145035 0.8193631 0.5121636 0.8098093 0.5145035 0.8193631 0.5188053 0.8143863 0.5121636 0.8098093 0.5192483 0.8051835 0.512272 0.8084664 0.5124125 0.8091965 0.5331016 0.8289863 0.5332735 0.8209759 0.5194563 0.820679 0.5407851 0.8083032 0.5438694 0.8056666 0.539574 0.8006418 0.539574 0.8006418 0.5336221 0.8057296 0.5407851 0.8083032 0.5336221 0.8057296 0.5339991 0.8145766 0.5401706 0.8096225 0.5407851 0.8083032 0.5336221 0.8057296 0.5403095 0.8089217 0.5339991 0.8145766 0.5381072 0.8193824 0.5404065 0.8102129 0.5381072 0.8193824 0.5439646 0.8143755 0.5404065 0.8102129 0.5403095 0.8089217 0.5336221 0.8057296 0.5401706 0.8096225 0.5336221 0.8057296 0.5339439 0.7972623 0.51957 0.7967161 0.5328411 0.841111 0.5190238 0.8408142 0.5188763 0.8476861 0.5339991 0.8145766 0.5314108 0.8142089 0.5302612 0.8164731 0.5224218 0.8160102 0.5214868 0.8140555 0.5188053 0.8143863 0.5332735 0.8209759 0.5339991 0.8145766 0.5302612 0.8164731 0.5224218 0.8160102 0.5188053 0.8143863 0.5194563 0.820679 0.5332735 0.8209759 0.5302612 0.8164731 0.5224218 0.8160102 0.5192483 0.8051835 0.5188053 0.8143863 0.5224492 0.8058534 0.5188053 0.8143863 0.5214868 0.8140555 0.5224492 0.8058534 0.5314108 0.8142089 0.5339991 0.8145766 0.5305691 0.8061345 0.5339991 0.8145766 0.5336221 0.8057296 0.5305691 0.8061345 0.5192483 0.8051835 0.5224492 0.8058534 0.5336221 0.8057296 0.5328411 0.841111 0.5329317 0.836893 0.5191144 0.8365963 0.5192843 0.8286894 0.5191619 0.8343817 0.5329793 0.8346786 0.5191478 0.8350425 0.5329651 0.8353394 0.5329793 0.8346786 0.5191318 0.8357854 0.5329492 0.8360822 0.5329651 0.8353394 0.5191144 0.8365963 0.5329317 0.836893 0.5329492 0.8360822 0.5214868 0.8140555 0.5224218 0.8160102 0.524804 0.8128898 0.5302612 0.8164731 0.5277867 0.812411 0.524804 0.8128898 0.5314108 0.8142089 0.5305691 0.8061345 0.5277867 0.812411 0.5224492 0.8058534 0.524804 0.8128898 0.5277867 0.812411 - - - - - - - - - - - - - - -

5 0 0 14 0 1 15 0 2 1 1 3 16 1 4 13 1 5 9 2 6 19 2 7 21 2 8 0 3 9 9 3 10 6 3 11 0 4 12 17 4 13 3 4 14 25 5 15 22 5 16 4 5 17 6 6 18 9 6 19 26 6 20 11 1 21 17 1 22 10 1 23 20 4 24 13 4 25 16 4 26 20 7 27 15 7 28 14 7 29 21 8 30 12 8 31 15 8 32 19 9 33 11 9 34 12 9 35 2 10 36 23 10 37 26 10 38 2 3 39 22 3 40 25 3 41 7 11 42 24 11 43 22 11 44 7 5 45 26 5 46 27 5 47 28 12 48 32 12 49 29 12 50 29 13 51 30 13 52 28 13 53 33 14 54 47 14 55 46 14 56 54 15 57 55 15 58 31 15 59 32 16 60 33 16 61 34 16 62 34 17 63 30 17 64 35 17 65 85 18 66 87 18 67 34 18 68 92 19 69 91 19 70 32 19 71 114 20 72 37 20 73 117 20 74 84 5 75 47 5 76 85 5 77 90 21 78 75 21 79 72 21 80 54 22 81 95 22 82 91 22 83 56 23 84 94 23 85 95 23 86 64 24 87 97 24 88 94 24 89 61 25 90 101 25 91 97 25 92 98 26 93 60 26 94 76 26 95 68 27 96 98 27 97 76 27 98 67 28 99 116 28 100 68 28 101 74 29 102 105 29 103 67 29 104 115 30 105 74 30 106 75 30 107 46 31 108 86 31 109 48 31 110 48 32 111 82 32 112 50 32 113 82 33 114 43 33 115 50 33 116 43 34 117 79 34 118 49 34 119 79 35 120 39 35 121 49 35 122 80 36 123 71 36 124 39 36 125 78 37 126 70 37 127 71 37 128 81 38 129 73 38 130 70 38 131 77 39 132 72 39 133 73 39 134 96 40 135 55 40 136 92 40 137 96 41 138 58 41 139 57 41 140 93 42 141 59 42 142 58 42 143 102 43 144 59 43 145 103 43 146 62 44 147 100 44 148 65 44 149 66 45 150 99 45 151 104 45 152 69 46 153 104 46 154 106 46 155 36 47 156 106 47 157 108 47 158 36 48 159 117 48 160 37 48 161 87 49 162 47 49 163 45 49 164 83 50 165 45 50 166 51 50 167 83 51 168 44 51 169 89 51 170 111 52 171 44 52 172 52 52 173 40 53 174 111 53 175 52 53 176 41 54 177 112 54 178 40 54 179 41 55 180 109 55 181 113 55 182 38 56 183 110 56 184 109 56 185 53 57 186 110 57 187 42 57 188 92 58 189 54 58 190 91 58 191 120 11 192 119 11 193 118 11 194 124 1 195 121 1 196 120 1 197 122 10 198 125 10 199 124 10 200 118 3 201 123 3 202 122 3 203 118 5 204 124 5 205 120 5 206 123 4 207 121 4 208 125 4 209 205 11 312 204 11 313 195 11 314 206 1 315 191 1 316 203 1 317 198 91 318 210 91 319 211 91 320 199 3 321 190 3 322 196 3 323 207 5 324 190 5 325 193 5 326 215 4 327 191 4 328 194 4 329 216 92 330 217 92 331 199 92 332 207 1 333 201 1 334 200 1 335 203 5 336 210 5 337 206 5 338 205 93 339 210 93 340 204 93 341 202 94 342 211 94 343 205 94 344 201 95 345 209 95 346 202 95 347 213 10 348 192 10 349 216 10 350 212 3 351 192 3 352 215 3 353 214 11 354 197 11 355 212 11 356 216 4 357 197 4 358 217 4 359 11 11 360 10 11 361 0 11 362 0 96 363 6 96 364 11 96 365 6 11 366 5 11 367 15 11 368 11 11 369 6 11 370 12 11 371 5 11 372 1 11 373 14 11 374 1 11 375 13 11 376 14 11 377 12 11 378 6 11 379 15 11 380 1 1 381 4 1 382 16 1 383 20 10 384 16 10 385 4 10 386 4 10 387 8 10 388 20 10 389 8 97 390 9 97 391 21 97 392 20 10 393 8 10 394 21 10 395 9 10 396 3 10 397 18 10 398 3 10 399 17 10 400 18 10 401 9 98 402 18 98 403 19 98 404 0 3 405 3 3 406 9 3 407 0 4 408 10 4 409 17 4 410 22 5 411 24 5 412 8 5 413 1 5 414 5 5 415 25 5 416 5 5 417 23 5 418 25 5 419 22 5 420 8 5 421 4 5 422 1 5 423 25 5 424 4 5 425 23 99 426 5 99 427 26 99 428 5 100 429 6 100 430 26 100 431 9 101 432 8 101 433 27 101 434 8 102 435 24 102 436 27 102 437 9 103 438 27 103 439 26 103 440 11 1 441 18 1 442 17 1 443 20 4 444 14 4 445 13 4 446 20 104 447 21 104 448 15 104 449 21 105 450 19 105 451 12 105 452 19 106 453 18 106 454 11 106 455 2 10 456 25 10 457 23 10 458 2 3 459 7 3 460 22 3 461 7 11 462 27 11 463 24 11 464 7 5 465 2 5 466 26 5 467 28 107 468 31 107 469 32 107 470 29 108 471 35 108 472 30 108 473 31 109 474 62 109 475 65 109 476 31 110 477 65 110 478 66 110 479 68 111 480 76 111 481 28 111 482 67 112 483 68 112 484 28 112 485 31 113 486 66 113 487 69 113 488 31 114 489 69 114 490 36 114 491 74 115 492 67 115 493 28 115 494 75 116 495 74 116 496 28 116 497 31 117 498 36 117 499 37 117 500 31 118 501 37 118 502 53 118 503 75 119 504 28 119 505 72 119 506 28 120 507 30 120 508 72 120 509 33 121 510 31 121 511 53 121 512 33 122 513 53 122 514 42 122 515 73 123 516 72 123 517 30 123 518 70 124 519 73 124 520 30 124 521 33 125 522 42 125 523 38 125 524 33 126 525 38 126 526 41 126 527 71 127 528 70 127 529 30 127 530 39 128 531 71 128 532 30 128 533 33 129 534 41 129 535 40 129 536 33 130 537 40 130 538 52 130 539 49 131 540 39 131 541 30 131 542 43 132 543 49 132 544 30 132 545 33 133 546 52 133 547 44 133 548 33 134 549 44 134 550 51 134 551 50 135 552 43 135 553 30 135 554 48 136 555 50 136 556 30 136 557 30 137 558 33 137 559 46 137 560 33 138 561 51 138 562 45 138 563 33 139 564 45 139 565 47 139 566 46 140 567 48 140 568 30 140 569 28 141 570 76 141 571 60 141 572 28 142 573 60 142 574 61 142 575 63 143 576 62 143 577 31 143 578 59 144 579 63 144 580 31 144 581 28 145 582 61 145 583 64 145 584 28 146 585 64 146 586 56 146 587 58 147 588 59 147 589 31 147 590 57 148 591 58 148 592 31 148 593 31 149 594 28 149 595 54 149 596 28 150 597 56 150 598 54 150 599 55 151 600 57 151 601 31 151 602 32 152 603 31 152 604 33 152 605 34 153 606 33 153 607 30 153 608 29 154 609 98 154 610 116 154 611 29 155 612 116 155 613 105 155 614 99 156 615 100 156 616 32 156 617 104 157 618 99 157 619 32 157 620 29 158 621 105 158 622 107 158 623 29 159 624 107 159 625 115 159 626 106 160 627 104 160 628 32 160 629 108 161 630 106 161 631 32 161 632 35 162 633 29 162 634 90 162 635 29 163 636 115 163 637 90 163 638 117 164 639 108 164 640 32 164 641 114 165 642 117 165 643 32 165 644 35 166 645 90 166 646 77 166 647 35 167 648 77 167 649 81 167 650 114 168 651 32 168 652 34 168 653 110 169 654 114 169 655 34 169 656 35 170 657 81 170 658 78 170 659 35 171 660 78 171 661 80 171 662 109 172 663 110 172 664 34 172 665 113 173 666 109 173 667 34 173 668 35 174 669 80 174 670 79 174 671 35 175 672 79 175 673 88 175 674 112 176 675 113 176 676 34 176 677 111 177 678 112 177 679 34 177 680 35 178 681 88 178 682 82 178 683 35 179 684 82 179 685 86 179 686 89 180 687 111 180 688 34 180 689 83 181 690 89 181 691 34 181 692 34 182 693 35 182 694 84 182 695 35 183 696 86 183 697 84 183 698 87 184 699 83 184 700 34 184 701 34 185 702 84 185 703 85 185 704 101 186 705 98 186 706 29 186 707 32 187 708 100 187 709 102 187 710 32 188 711 102 188 712 103 188 713 97 189 714 101 189 715 29 189 716 94 190 717 97 190 718 29 190 719 32 191 720 103 191 721 93 191 722 32 192 723 93 192 724 96 192 725 95 193 726 94 193 727 29 193 728 91 194 729 95 194 730 29 194 731 29 195 732 32 195 733 91 195 734 32 196 735 96 196 736 92 196 737 114 197 738 53 197 739 37 197 740 84 198 741 46 198 742 47 198 743 90 199 744 115 199 745 75 199 746 54 200 747 56 200 748 95 200 749 56 201 750 64 201 751 94 201 752 64 202 753 61 202 754 97 202 755 61 203 756 60 203 757 101 203 758 98 204 759 101 204 760 60 204 761 68 205 762 116 205 763 98 205 764 67 206 765 105 206 766 116 206 767 74 207 768 107 207 769 105 207 770 115 208 771 107 208 772 74 208 773 46 209 774 84 209 775 86 209 776 48 210 777 86 210 778 82 210 779 82 211 780 88 211 781 43 211 782 43 212 783 88 212 784 79 212 785 79 213 786 80 213 787 39 213 788 80 214 789 78 214 790 71 214 791 78 215 792 81 215 793 70 215 794 81 216 795 77 216 796 73 216 797 77 217 798 90 217 799 72 217 800 96 218 801 57 218 802 55 218 803 96 219 804 93 219 805 58 219 806 93 220 807 103 220 808 59 220 809 102 221 810 63 221 811 59 221 812 62 222 813 63 222 814 102 222 815 102 223 816 100 223 817 62 223 818 100 224 819 99 224 820 65 224 821 66 225 822 65 225 823 99 225 824 69 226 825 66 226 826 104 226 827 36 227 828 69 227 829 106 227 830 36 228 831 108 228 832 117 228 833 87 229 834 85 229 835 47 229 836 83 230 837 87 230 838 45 230 839 83 231 840 51 231 841 44 231 842 111 232 843 89 232 844 44 232 845 40 233 846 112 233 847 111 233 848 41 234 849 113 234 850 112 234 851 41 235 852 38 235 853 109 235 854 38 236 855 42 236 856 110 236 857 53 237 858 114 237 859 110 237 860 92 238 861 55 238 862 54 238 863 120 11 864 121 11 865 119 11 866 124 1 867 125 1 868 121 1 869 122 10 870 123 10 871 125 10 872 118 3 873 119 3 874 123 3 875 118 5 876 122 5 877 124 5 878 123 4 879 119 4 880 121 4 881 190 11 1152 200 11 1153 201 11 1154 190 11 1155 201 11 1156 196 11 1157 201 11 1158 202 11 1159 196 11 1160 195 282 1161 196 282 1162 205 282 1163 203 11 1164 191 11 1165 204 11 1166 191 11 1167 195 11 1168 204 11 1169 196 283 1170 202 283 1171 205 283 1172 206 1 1173 194 1 1174 191 1 1175 208 10 1176 207 10 1177 193 10 1178 193 284 1179 199 284 1180 208 284 1181 199 10 1182 198 10 1183 211 10 1184 208 285 1185 199 285 1186 209 285 1187 198 10 1188 194 10 1189 210 10 1190 194 10 1191 206 10 1192 210 10 1193 209 10 1194 199 10 1195 211 10 1196 199 3 1197 193 3 1198 190 3 1199 207 5 1200 200 5 1201 190 5 1202 198 4 1203 214 4 1204 212 4 1205 215 4 1206 213 4 1207 195 4 1208 194 286 1209 198 286 1210 212 286 1211 215 287 1212 195 287 1213 191 287 1214 194 4 1215 212 4 1216 215 4 1217 196 288 1218 195 288 1219 216 288 1220 195 289 1221 213 289 1222 216 289 1223 214 289 1224 198 289 1225 217 289 1226 198 290 1227 199 290 1228 217 290 1229 196 291 1230 216 291 1231 199 291 1232 207 1 1233 208 1 1234 201 1 1235 203 5 1236 204 5 1237 210 5 1238 205 292 1239 211 292 1240 210 292 1241 202 293 1242 209 293 1243 211 293 1244 201 294 1245 208 294 1246 209 294 1247 213 10 1248 215 10 1249 192 10 1250 212 3 1251 197 3 1252 192 3 1253 214 11 1254 217 11 1255 197 11 1256 216 4 1257 192 4 1258 197 4 1259

-
- - - - -

128 59 210 127 59 211 126 59 212 130 60 213 129 60 214 128 60 215 132 61 216 131 61 217 130 61 218 134 62 219 133 62 220 132 62 221 136 63 222 135 63 223 134 63 224 138 64 225 137 64 226 136 64 227 140 65 228 139 65 229 138 65 230 142 66 231 141 66 232 140 66 233 144 67 234 143 67 235 142 67 236 146 68 237 145 68 238 144 68 239 148 69 240 147 69 241 146 69 242 150 70 243 149 70 244 148 70 245 152 71 246 151 71 247 150 71 248 154 72 249 153 72 250 152 72 251 156 73 252 155 73 253 154 73 254 158 74 255 157 74 256 156 74 257 160 75 258 159 75 259 158 75 260 162 76 261 161 76 262 160 76 263 164 77 264 163 77 265 162 77 266 166 78 267 165 78 268 164 78 269 168 79 270 167 79 271 166 79 272 170 80 273 169 80 274 168 80 275 172 81 276 171 81 277 170 81 278 174 82 279 173 82 280 172 82 281 176 83 282 175 83 283 174 83 284 178 84 285 177 84 286 176 84 287 180 85 288 179 85 289 178 85 290 182 86 291 181 86 292 180 86 293 184 87 294 183 87 295 182 87 296 186 88 297 185 88 298 184 88 299 187 4 300 189 4 301 163 4 302 188 89 303 187 89 304 186 89 305 126 90 306 189 90 307 188 90 308 132 5 309 130 5 310 152 5 311 128 239 882 129 239 883 127 239 884 130 240 885 131 240 886 129 240 887 132 241 888 133 241 889 131 241 890 134 242 891 135 242 892 133 242 893 136 243 894 137 243 895 135 243 896 138 244 897 139 244 898 137 244 899 140 245 900 141 245 901 139 245 902 142 246 903 143 246 904 141 246 905 144 247 906 145 247 907 143 247 908 146 248 909 147 248 910 145 248 911 148 249 912 149 249 913 147 249 914 150 250 915 151 250 916 149 250 917 152 251 918 153 251 919 151 251 920 154 252 921 155 252 922 153 252 923 156 253 924 157 253 925 155 253 926 158 254 927 159 254 928 157 254 929 160 255 930 161 255 931 159 255 932 162 76 933 163 76 934 161 76 935 164 256 936 165 256 937 163 256 938 166 257 939 167 257 940 165 257 941 168 79 942 169 79 943 167 79 944 170 258 945 171 258 946 169 258 947 172 259 948 173 259 949 171 259 950 174 260 951 175 260 952 173 260 953 176 261 954 177 261 955 175 261 956 178 262 957 179 262 958 177 262 959 180 263 960 181 263 961 179 263 962 182 86 963 183 86 964 181 86 965 184 264 966 185 264 967 183 264 968 186 265 969 187 265 970 185 265 971 127 4 972 129 4 973 157 4 974 129 4 975 131 4 976 155 4 977 131 266 978 133 266 979 153 266 980 133 267 981 135 267 982 151 267 983 135 4 984 137 4 985 149 4 986 137 4 987 139 4 988 147 4 989 139 268 990 141 268 991 145 268 992 141 4 993 143 4 994 145 4 995 145 269 996 147 269 997 139 269 998 147 4 999 149 4 1000 137 4 1001 149 270 1002 151 270 1003 135 270 1004 151 4 1005 153 4 1006 133 4 1007 153 4 1008 155 4 1009 131 4 1010 155 271 1011 157 271 1012 129 271 1013 157 4 1014 159 4 1015 127 4 1016 159 4 1017 161 4 1018 127 4 1019 161 272 1020 163 272 1021 189 272 1022 127 4 1023 161 4 1024 189 4 1025 163 4 1026 165 4 1027 187 4 1028 165 4 1029 167 4 1030 185 4 1031 187 273 1032 165 273 1033 185 273 1034 167 4 1035 169 4 1036 183 4 1037 169 4 1038 171 4 1039 181 4 1040 183 4 1041 169 4 1042 181 4 1043 171 274 1044 173 274 1045 177 274 1046 173 4 1047 175 4 1048 177 4 1049 177 275 1050 179 275 1051 171 275 1052 179 4 1053 181 4 1054 171 4 1055 183 276 1056 185 276 1057 167 276 1058 188 89 1059 189 89 1060 187 89 1061 126 277 1062 127 277 1063 189 277 1064 128 5 1065 126 5 1066 158 5 1067 126 5 1068 188 5 1069 160 5 1070 188 278 1071 186 278 1072 160 278 1073 186 5 1074 184 5 1075 162 5 1076 160 5 1077 186 5 1078 162 5 1079 184 5 1080 182 5 1081 166 5 1082 182 5 1083 180 5 1084 168 5 1085 180 5 1086 178 5 1087 168 5 1088 178 5 1089 176 5 1090 170 5 1091 168 279 1092 178 279 1093 170 279 1094 176 5 1095 174 5 1096 172 5 1097 172 5 1098 170 5 1099 176 5 1100 168 5 1101 166 5 1102 182 5 1103 166 5 1104 164 5 1105 184 5 1106 164 5 1107 162 5 1108 184 5 1109 160 5 1110 158 5 1111 126 5 1112 158 5 1113 156 5 1114 128 5 1115 156 280 1116 154 280 1117 128 280 1118 154 5 1119 152 5 1120 130 5 1121 128 5 1122 154 5 1123 130 5 1124 152 5 1125 150 5 1126 134 5 1127 150 5 1128 148 5 1129 136 5 1130 148 5 1131 146 5 1132 136 5 1133 146 5 1134 144 5 1135 138 5 1136 136 281 1137 146 281 1138 138 281 1139 144 5 1140 142 5 1141 140 5 1142 140 5 1143 138 5 1144 144 5 1145 136 5 1146 134 5 1147 150 5 1148 134 5 1149 132 5 1150 152 5 1151

-
-
-
- - - - 0.4768833 -0.182 -0.02099996 0.4768833 -0.182 -0.03599995 0.4768833 -0.163 -0.02099996 0.4768833 -0.12 -0.03599995 0.4768833 -0.163 0.06199997 -0.6931167 -0.163 0.06199997 -0.6931167 -0.163 -0.02099996 -0.6931167 -0.12 -0.03599995 -0.6931167 -0.182 -0.02099996 -0.6931167 -0.182 -0.03599995 -0.3831167 0.12 0 0.4768833 0.12 0 0.4768833 0.06086635 0 -0.3831167 0.06086635 0 -0.3831167 0.12 0.03999996 -0.3831167 0.07999998 0.03992241 -0.4031167 -0.07999998 0.03992241 -0.4031167 -0.07999998 -0.0770775 -0.5201167 -0.04999995 0.03992241 0.4768833 0.12 0.06199997 0.4768833 0.07230395 -0.01899999 0.4768833 -0.07230395 -0.01899999 0.4768833 -0.12 0 0.4768833 -0.06086635 0 -0.6931167 0.12 0.06199997 -0.3831167 -0.12 0 -0.3831167 -0.12 0.03999996 -0.3831167 -0.06086635 0 -0.6931167 0.12 0.03999996 -0.6931167 -0.12 0.03999996 -0.3831167 0.07230395 -0.01899999 -0.3831167 -0.07230395 -0.01899999 -0.5201167 -0.04999995 -0.0770775 -0.5201167 0.04999995 -0.0770775 -0.5201167 0.04999995 0.03992241 -0.4031167 -0.04999995 -0.0770775 -0.4031167 -0.04999995 0.03992241 -0.3831167 -0.07999998 0.03992241 -0.4031167 0.04999995 -0.0770775 -0.4031167 0.07999998 -0.0770775 -0.3831167 0.07999998 -0.0770775 -0.3831167 -0.07999998 -0.0770775 -0.4031167 0.07999998 0.03992241 -0.4031167 0.04999995 0.03992241 -0.6477565 -0.04503262 -0.05730056 -0.6477565 -0.04503262 0.02706873 -0.6477565 0.04490411 -0.05730056 -0.6477565 0.04490411 0.02706873 -0.5217171 -0.04503262 -0.05730056 -0.5217171 -0.04503262 0.02706873 -0.5217171 0.04490411 -0.05730056 -0.5217171 0.04490411 0.02706873 - - - - - - - - - - -1 0 0 0 0 1 4.65662e-7 0 -1 1 0 0 0 0 -1 0 -1 0 0 0.8567444 0.5157412 0 1 0 0 -0.8567448 0.5157407 -4.65662e-7 0 1 -5.82077e-7 0 -1 1 1.20326e-6 0 1 -5.21895e-7 0 0 0.8567448 0.5157407 -1 5.21895e-7 0 0 0 1 - - - - - - - - - - 0.1273891 0.5797688 0.128252 0.529305 0.1240918 0.5748056 0.124274 0.6114798 0.1240533 0.6037358 0.1280928 0.6490937 0.1571237 0.6430846 0.1571237 0.6578835 0.1522609 0.6650724 0.01497727 0.6715419 0.01728707 0.529305 0.01728707 0.6715419 0.1245401 0.5669167 0.124274 0.6114798 0.128252 0.6263719 0.1358497 0.6654209 0.1283124 0.6726098 0.1358497 0.6506218 0.07650792 0.529305 0.06931912 0.6338551 0.06931912 0.529305 0.1283124 0.5981486 0.1574891 0.6358352 0.1283124 0.6358352 0.1110454 0.6715419 0.1185828 0.529305 0.1185828 0.6715419 0.02737748 0.529305 0.0617817 0.6715419 0.02737742 0.6715419 0.1263321 0.5858806 0.1245401 0.5669167 0.1273891 0.5797688 0.01728707 0.6715419 0.02737748 0.529305 0.02737742 0.6715419 0.1185828 0.6715419 0.1204063 0.529305 0.1204063 0.6715419 0.09678405 0.6338551 0.07920402 0.529305 0.09678393 0.529305 0.1066689 0.529305 0.09948009 0.6338551 0.09948009 0.529305 0.07650792 0.529305 0.07920402 0.6338551 0.07650792 0.6338551 0.1252553 0.5949124 0.1271823 0.5987811 0.124274 0.6114798 0.06931912 0.529305 0.06931912 0.6338551 0.06445628 0.6338551 0.09678393 0.529305 0.09948009 0.6338551 0.09678405 0.6338551 0.1421102 0.6382055 0.149526 0.6434329 0.1402866 0.6434329 0.1263321 0.5858806 0.1252553 0.5949124 0.1253279 0.5835347 0.128252 0.529305 0.1204667 0.5722844 0.1240918 0.5748056 0.128252 0.6263719 0.1204667 0.5722844 0.1281952 0.5520679 0.1240533 0.6037358 0.128252 0.6263719 0.1280928 0.6490937 0.1273891 0.5797688 0.1204667 0.5722844 0.1271823 0.5987811 0.1066689 0.6338551 0.1110454 0.529305 0.1110454 0.6715419 0.162704 0.529305 0.1455082 0.5465008 0.1455082 0.529305 0.162704 0.5465008 0.1455082 0.5636966 0.1455082 0.5465008 0.162704 0.5636966 0.1455082 0.5808924 0.1455082 0.5636966 0.162704 0.5808924 0.1455082 0.5980882 0.1455082 0.5808924 0.1455082 0.5636966 0.1283124 0.5808924 0.1283124 0.5636966 0.1798997 0.5636966 0.162704 0.5808924 0.162704 0.5636966 0.1273891 0.5797688 0.1245401 0.5669167 0.128252 0.529305 0.124274 0.6114798 0.1271823 0.5987811 0.1240533 0.6037358 0.1522609 0.6358957 0.1571237 0.6358957 0.1571237 0.6430846 0.1571237 0.6430846 0.1594336 0.6416941 0.1594336 0.6592741 0.1571237 0.6578835 0.1571237 0.6650724 0.1522609 0.6650724 0.1571237 0.6430846 0.1594336 0.6592741 0.1571237 0.6578835 0.1522609 0.6650724 0.1522609 0.6358957 0.1571237 0.6430846 0.01497727 0.6715419 0.01497727 0.529305 0.01728707 0.529305 0.128252 0.6263719 0.1281952 0.5520679 0.1245401 0.5669167 0.1281952 0.5520679 0.128252 0.529305 0.1245401 0.5669167 0.1245401 0.5669167 0.1253279 0.5835347 0.1252553 0.5949124 0.124274 0.6114798 0.1280928 0.6490937 0.128252 0.6263719 0.1245401 0.5669167 0.1252553 0.5949124 0.124274 0.6114798 0.1384027 0.6382055 0.1384027 0.6358957 0.1402263 0.6358957 0.1402263 0.6358957 0.1402263 0.6434329 0.1384027 0.6382055 0.1402263 0.6434329 0.1358497 0.6434329 0.1384027 0.6382055 0.1358497 0.6506218 0.1381595 0.6492314 0.1381595 0.6668115 0.1358497 0.6506218 0.1381595 0.6668115 0.1358497 0.6654209 0.1283124 0.6382055 0.1384027 0.6382055 0.1358497 0.6434329 0.1283124 0.6382055 0.1358497 0.6434329 0.1358497 0.6506218 0.1358497 0.6726098 0.1283124 0.6726098 0.1358497 0.6654209 0.1283124 0.6726098 0.1283124 0.6382055 0.1358497 0.6506218 0.07650792 0.529305 0.07650792 0.6338551 0.06931912 0.6338551 0.1283124 0.5981486 0.1574891 0.5981486 0.1574891 0.6358352 0.1110454 0.6715419 0.1110454 0.529305 0.1185828 0.529305 0.02737748 0.529305 0.0617817 0.529305 0.0617817 0.6715419 0.1263321 0.5858806 0.1253279 0.5835347 0.1245401 0.5669167 0.01728707 0.6715419 0.01728707 0.529305 0.02737748 0.529305 0.1185828 0.6715419 0.1185828 0.529305 0.1204063 0.529305 0.09678405 0.6338551 0.07920402 0.6338551 0.07920402 0.529305 0.1066689 0.529305 0.1066689 0.6338551 0.09948009 0.6338551 0.07650792 0.529305 0.07920402 0.529305 0.07920402 0.6338551 0.1252553 0.5949124 0.1262703 0.5926182 0.1271823 0.5987811 0.06445628 0.6715419 0.0617817 0.6715419 0.06445628 0.6338551 0.0617817 0.6715419 0.0617817 0.529305 0.06445628 0.6338551 0.0617817 0.529305 0.06931912 0.529305 0.06445628 0.6338551 0.09678393 0.529305 0.09948009 0.529305 0.09948009 0.6338551 0.1402866 0.6358957 0.1421102 0.6358957 0.1421102 0.6382055 0.1522005 0.6382055 0.1522005 0.6726098 0.149526 0.6434329 0.1522005 0.6726098 0.149526 0.6726098 0.149526 0.6434329 0.1402866 0.6434329 0.1402866 0.6358957 0.1421102 0.6382055 0.1421102 0.6382055 0.1522005 0.6382055 0.149526 0.6434329 0.1263321 0.5858806 0.1262703 0.5926182 0.1252553 0.5949124 0.128252 0.529305 0.1281952 0.5520679 0.1204667 0.5722844 0.128252 0.6263719 0.1205573 0.6062074 0.1204667 0.5722844 0.1240533 0.6037358 0.1205573 0.6062074 0.128252 0.6263719 0.1273891 0.5797688 0.1240918 0.5748056 0.1204667 0.5722844 0.1204667 0.5722844 0.1205573 0.6062074 0.1271823 0.5987811 0.1205573 0.6062074 0.1240533 0.6037358 0.1271823 0.5987811 0.1271823 0.5987811 0.1262703 0.5926182 0.1263321 0.5858806 0.1271823 0.5987811 0.1263321 0.5858806 0.1273891 0.5797688 0.1066689 0.6338551 0.1066689 0.529305 0.1110454 0.529305 0.1110454 0.6715419 0.1018061 0.6715419 0.1066689 0.6338551 0.1018061 0.6715419 0.1018061 0.6338551 0.1066689 0.6338551 0.162704 0.529305 0.162704 0.5465008 0.1455082 0.5465008 0.162704 0.5465008 0.162704 0.5636966 0.1455082 0.5636966 0.162704 0.5636966 0.162704 0.5808924 0.1455082 0.5808924 0.162704 0.5808924 0.162704 0.5980882 0.1455082 0.5980882 0.1455082 0.5636966 0.1455082 0.5808924 0.1283124 0.5808924 0.1798997 0.5636966 0.1798997 0.5808924 0.162704 0.5808924 - - - - - - - - - - - - - - -

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

-
-
-
- - - - 0.14 -0.12 0.006999969 0.2 -0.12 0.006999969 0.2 -0.12 0.07499998 -0.1999999 -0.12 0.07499998 -0.1999999 -0.12 0.006999969 -0.14 -0.12 0.006999969 -0.14 -0.12 -0.02499997 0.14 -0.12 -0.02499997 -0.1999999 0.12 0.07499998 0.2 0.12 0.07499998 0.14 0.12 0.006999969 0.2 0.12 0.006999969 -0.1999999 0.12 0.006999969 -0.14 0.12 0.006999969 -0.14 0.12 -0.02499997 0.14 0.12 -0.02499997 - - - - - - - - - - 0 0 -1 1 0 0 -1 0 0 0 -1 0 0 1 0 0 0 1 0 -1 0 - - - - - - - - - - -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 -0.002114355 0.003757476 - - - - - - - - - - - - - - -

13 0 0 4 0 1 12 0 2 10 1 3 7 1 4 15 1 5 14 2 6 5 2 7 13 2 8 12 2 9 3 2 10 8 2 11 0 3 12 2 3 13 5 3 14 9 4 15 10 4 16 13 4 17 11 0 18 0 0 19 10 0 20 9 1 21 1 1 22 11 1 23 8 5 24 2 5 25 9 5 26 15 0 27 6 0 28 14 0 29 13 0 30 5 0 31 4 0 32 10 1 33 0 1 34 7 1 35 14 2 36 6 2 37 5 2 38 12 2 39 4 2 40 3 2 41 0 3 42 1 3 43 2 3 44 2 6 45 3 6 46 5 6 47 3 3 48 4 3 49 5 3 50 5 3 51 6 3 52 7 3 53 5 3 54 7 3 55 0 3 56 12 4 57 8 4 58 13 4 59 8 4 60 9 4 61 13 4 62 9 4 63 11 4 64 10 4 65 10 4 66 15 4 67 14 4 68 10 4 69 14 4 70 13 4 71 11 0 72 1 0 73 0 0 74 9 1 75 2 1 76 1 1 77 8 5 78 3 5 79 2 5 80 15 0 81 7 0 82 6 0 83

-
-
-
- - - - 0.07000005 -0.05599999 -0.11355 0.07000005 -0.05599999 -0.3284698 0.1249999 -0.05599999 -0.11355 0.1249999 -0.05599999 -0.3284698 -0.1250001 -0.05599999 -0.11355 -0.1250001 -0.05599999 -0.3284698 -0.06999999 -0.05599999 -0.11355 -0.06999999 -0.05599999 -0.3284698 0.07000005 -0.334 -0.11355 0.07000005 -0.334 -0.28055 0.07000005 -0.1259999 -0.28055 0.07000005 -0.05599999 -0.32855 -0.06999999 -0.334 -0.28055 -0.06999999 -0.334 -0.11355 -0.06999999 -0.1259999 -0.28055 -0.06999999 -0.05599999 -0.32855 0.03999984 -0.364 -0.28055 0.03999984 -0.364 -0.11355 0 -0.364 -0.28055 -0.04000002 -0.364 -0.11355 -0.04000002 -0.364 -0.28055 -0.1250001 -0.03099989 -0.02846974 -0.1250001 -0.03099989 -0.11055 0.1249999 -0.03099989 -0.02846974 0.1249999 -0.03099989 -0.11055 0.1249999 0.02599996 -0.3284698 -0.1250001 0.02599996 -0.3284698 -0.1250001 0.02599996 -0.02846974 0.1249999 0.02599996 -0.02846974 0.004890561 -0.3638003 -0.28055 0.05899155 -0.3149542 -0.28055 0.05968821 -0.3101094 -0.28055 0.05998742 -0.3052238 -0.28055 0.01690399 -0.2464304 -0.28055 0.01215517 -0.2452442 -0.28055 -0.0598877 -0.3003303 -0.28055 -0.05938917 -0.2954611 -0.28055 -0.05849558 -0.2906487 -0.28055 -0.0599876 -0.3052238 -0.28055 -0.05968815 -0.3101094 -0.28055 -0.05899149 -0.3149542 -0.28055 -0.04690986 -0.3414093 -0.28055 -0.04370456 -0.3451085 -0.28055 -0.04020839 -0.348534 -0.28055 0.04370462 -0.3451085 -0.28055 0.04690992 -0.3414093 -0.28055 0.04980289 -0.3374612 -0.28055 0.0523647 -0.3332906 -0.28055 0.05457794 -0.3289249 -0.28055 0.05642783 -0.3243933 -0.28055 0.05790245 -0.3197261 -0.28055 0.03035271 -0.2522436 -0.28055 0.02603304 -0.2499418 -0.28055 0.02154004 -0.2479998 -0.28055 -0.05351573 -0.2768697 -0.28055 -0.0555492 -0.281322 -0.28055 -0.05721265 -0.2859252 -0.28055 -0.05790239 -0.3197261 -0.28055 -0.05642801 -0.3243933 -0.28055 -0.05457788 -0.3289249 -0.28055 -0.05236464 -0.3332906 -0.28055 -0.04980307 -0.3374612 -0.28055 -0.03644472 -0.3516632 -0.28055 -0.03243833 -0.3544752 -0.28055 -0.02821618 -0.3569512 -0.28055 -0.02380639 -0.359075 -0.28055 -0.01923805 -0.3608321 -0.28055 -0.01454168 -0.3622111 -0.28055 -0.009748518 -0.3632027 -0.28055 -0.004890501 -0.3638003 -0.28055 0.009748578 -0.3632027 -0.28055 0.01454174 -0.3622111 -0.28055 0.01923811 -0.3608321 -0.28055 0.02380645 -0.359075 -0.28055 0.02821624 -0.3569512 -0.28055 0.03243839 -0.3544752 -0.28055 0.03644478 -0.3516632 -0.28055 0.04020845 -0.348534 -0.28055 0.05988752 -0.3003303 -0.28055 0.05938923 -0.2954611 -0.28055 0.05849564 -0.2906487 -0.28055 0.05721271 -0.2859252 -0.28055 0.05554902 -0.281322 -0.28055 0.05351579 -0.2768697 -0.28055 0.05112636 -0.2725979 -0.28055 0.0483967 -0.2685351 -0.28055 0.04534494 -0.2647083 -0.28055 0.04199135 -0.261143 -0.28055 0.03835856 -0.2578629 -0.28055 0.0344702 -0.2548899 -0.28055 0.00732553 -0.2444489 -0.28055 0.002447247 -0.2440499 -0.28055 -0.002447187 -0.2440499 -0.28055 -0.007325708 -0.2444489 -0.28055 -0.01215535 -0.2452442 -0.28055 -0.01690393 -0.2464304 -0.28055 -0.04199153 -0.261143 -0.28055 -0.04534488 -0.2647083 -0.28055 -0.02154022 -0.2479998 -0.28055 -0.02603298 -0.2499418 -0.28055 -0.03035265 -0.2522436 -0.28055 -0.03447014 -0.2548899 -0.28055 -0.0383585 -0.2578629 -0.28055 -0.04839664 -0.2685351 -0.28055 -0.0511263 -0.2725979 -0.28055 0.004890561 -0.3638003 -0.30115 0.009748578 -0.3632027 -0.30115 0.01454174 -0.3622111 -0.30115 0.01923811 -0.3608321 -0.30115 0.02380645 -0.359075 -0.30115 0.02821624 -0.3569512 -0.30115 0.03243839 -0.3544752 -0.30115 0.03644478 -0.3516632 -0.30115 0.04020845 -0.348534 -0.30115 0.04370462 -0.3451085 -0.30115 0.04690992 -0.3414093 -0.30115 0.04980289 -0.3374612 -0.30115 0.0523647 -0.3332906 -0.30115 0.05457794 -0.3289249 -0.30115 0.05642783 -0.3243933 -0.30115 0.05790245 -0.3197261 -0.30115 0.05899155 -0.3149542 -0.30115 0.05968821 -0.3101094 -0.30115 0.05998742 -0.3052238 -0.30115 0.05988752 -0.3003303 -0.30115 0.05938923 -0.2954611 -0.30115 0.05849564 -0.2906487 -0.30115 0.05721271 -0.2859252 -0.30115 0.05554902 -0.281322 -0.30115 0.05351579 -0.2768697 -0.30115 0.05112636 -0.2725979 -0.30115 0.0483967 -0.2685351 -0.30115 0.04534494 -0.2647083 -0.30115 0.04199135 -0.261143 -0.30115 0.03835856 -0.2578629 -0.30115 0.0344702 -0.2548899 -0.30115 0.03035271 -0.2522436 -0.30115 0.02603304 -0.2499418 -0.30115 0.02154004 -0.2479998 -0.30115 0.01690399 -0.2464304 -0.30115 0.01215517 -0.2452442 -0.30115 0.00732553 -0.2444489 -0.30115 0.002447247 -0.2440499 -0.30115 -0.002447187 -0.2440499 -0.30115 -0.007325708 -0.2444489 -0.30115 -0.01215535 -0.2452442 -0.30115 -0.01690393 -0.2464304 -0.30115 -0.02154022 -0.2479998 -0.30115 -0.02603298 -0.2499418 -0.30115 -0.03035265 -0.2522436 -0.30115 -0.03447014 -0.2548899 -0.30115 -0.0383585 -0.2578629 -0.30115 -0.04199153 -0.261143 -0.30115 -0.04534488 -0.2647083 -0.30115 -0.04839664 -0.2685351 -0.30115 -0.0511263 -0.2725979 -0.30115 -0.05351573 -0.2768697 -0.30115 -0.0555492 -0.281322 -0.30115 -0.05721265 -0.2859252 -0.30115 -0.05849558 -0.2906487 -0.30115 -0.05938917 -0.2954611 -0.30115 -0.0598877 -0.3003303 -0.30115 -0.0599876 -0.3052238 -0.30115 -0.05968815 -0.3101094 -0.30115 -0.05899149 -0.3149542 -0.30115 -0.05790239 -0.3197261 -0.30115 -0.05642801 -0.3243933 -0.30115 -0.05457788 -0.3289249 -0.30115 -0.05236464 -0.3332906 -0.30115 -0.04980307 -0.3374612 -0.30115 -0.04690986 -0.3414093 -0.30115 -0.04370456 -0.3451085 -0.30115 -0.04020839 -0.348534 -0.30115 -0.03644472 -0.3516632 -0.30115 -0.03243833 -0.3544752 -0.30115 -0.02821618 -0.3569512 -0.30115 -0.02380639 -0.359075 -0.30115 -0.01923805 -0.3608321 -0.30115 -0.01454168 -0.3622111 -0.30115 -0.009748518 -0.3632027 -0.30115 -0.004890501 -0.3638003 -0.30115 0 -0.364 -0.30115 -0.0407527 -0.3172413 -0.30115 -0.04184037 -0.3132464 -0.30115 -0.04253751 -0.309165 -0.30115 -0.04283744 -0.3050354 -0.30115 -0.0427373 -0.3008962 -0.30115 -0.04223829 -0.2967858 -0.30115 -0.0142222 -0.263579 -0.30115 -0.01025468 -0.2623952 -0.30115 -0.006191313 -0.2615997 -0.30115 -0.002070248 -0.2612 -0.30115 0.002070069 -0.2612 -0.30115 0.006191372 -0.2615997 -0.30115 0.01025474 -0.2623952 -0.30115 -0.04134494 -0.292743 -0.30115 -0.04006534 -0.2888051 -0.30115 -0.03841191 -0.2850092 -0.30115 -0.03639966 -0.2813906 -0.30115 -0.03404766 -0.2779831 -0.30115 -0.03137761 -0.2748184 -0.30115 0.01225268 -0.3450608 -0.30115 0.008232474 -0.3460517 -0.30115 0.004135489 -0.3466499 -0.30115 0 -0.3468499 -0.30115 -0.004135668 -0.3466499 -0.30115 -0.008232653 -0.3460517 -0.30115 0.04184043 -0.3132464 -0.30115 0.04075276 -0.3172413 -0.30115 0.03928458 -0.3211128 -0.30115 0.03744947 -0.3248243 -0.30115 0.03526484 -0.3283415 -0.30115 0.03275096 -0.3316314 -0.30115 -0.01225286 -0.3450608 -0.30115 -0.0161584 -0.3436866 -0.30115 -0.01991325 -0.3419417 -0.30115 -0.02348238 -0.3398427 -0.30115 -0.02683192 -0.337409 -0.30115 -0.02993112 -0.3346634 -0.30115 0.02993118 -0.3346634 -0.30115 0.02683198 -0.337409 -0.30115 0.0234822 -0.3398427 -0.30115 0.01991331 -0.3419417 -0.30115 0.01615846 -0.3436866 -0.30115 0.04134476 -0.292743 -0.30115 0.04223835 -0.2967858 -0.30115 0.04273736 -0.3008962 -0.30115 0.0428375 -0.3050354 -0.30115 0.04253756 -0.309165 -0.30115 0.02841484 -0.2719263 -0.30115 0.03137767 -0.2748184 -0.30115 0.03404772 -0.2779831 -0.30115 0.03639972 -0.2813906 -0.30115 0.03841173 -0.2850092 -0.30115 0.0400654 -0.2888051 -0.30115 0.01422226 -0.263579 -0.30115 0.01805698 -0.2651404 -0.30115 0.02172315 -0.2670646 -0.30115 0.02518665 -0.2693336 -0.30115 -0.02841478 -0.2719263 -0.30115 -0.02518659 -0.2693336 -0.30115 -0.02172333 -0.2670646 -0.30115 -0.01805692 -0.2651404 -0.30115 -0.0327509 -0.3316314 -0.30115 -0.03526479 -0.3283415 -0.30115 -0.03744941 -0.3248243 -0.30115 -0.03928452 -0.3211128 -0.30115 0 -0.26115 -0.34555 -0.002070248 -0.2612 -0.34555 -0.006191313 -0.2615997 -0.34555 -0.01025468 -0.2623952 -0.34555 -0.0142222 -0.263579 -0.34555 -0.01805692 -0.2651404 -0.34555 -0.02172333 -0.2670646 -0.34555 -0.02518659 -0.2693336 -0.34555 -0.02841478 -0.2719263 -0.34555 -0.03137761 -0.2748184 -0.34555 -0.03404766 -0.2779831 -0.34555 -0.03639966 -0.2813906 -0.34555 -0.03841191 -0.2850092 -0.34555 -0.04006534 -0.2888051 -0.34555 -0.04134494 -0.292743 -0.34555 -0.04223829 -0.2967858 -0.34555 -0.0427373 -0.3008962 -0.34555 -0.04283744 -0.3050354 -0.34555 -0.04253751 -0.309165 -0.34555 -0.04184037 -0.3132464 -0.34555 -0.0407527 -0.3172413 -0.34555 -0.03928452 -0.3211128 -0.34555 -0.03744941 -0.3248243 -0.34555 -0.03526479 -0.3283415 -0.34555 -0.0327509 -0.3316314 -0.34555 -0.02993112 -0.3346634 -0.34555 -0.02683192 -0.337409 -0.34555 -0.02348238 -0.3398427 -0.34555 -0.01991325 -0.3419417 -0.34555 -0.0161584 -0.3436866 -0.34555 -0.01225286 -0.3450608 -0.34555 -0.008232653 -0.3460517 -0.34555 -0.004135668 -0.3466499 -0.34555 0 -0.3468499 -0.34555 0.004135489 -0.3466499 -0.34555 0.008232474 -0.3460517 -0.34555 0.01225268 -0.3450608 -0.34555 0.01615846 -0.3436866 -0.34555 0.01991331 -0.3419417 -0.34555 0.0234822 -0.3398427 -0.34555 0.02683198 -0.337409 -0.34555 0.02993118 -0.3346634 -0.34555 0.03275096 -0.3316314 -0.34555 0.03526484 -0.3283415 -0.34555 0.03744947 -0.3248243 -0.34555 0.03928458 -0.3211128 -0.34555 0.04075276 -0.3172413 -0.34555 0.04184043 -0.3132464 -0.34555 0.04253756 -0.309165 -0.34555 0.0428375 -0.3050354 -0.34555 0.04273736 -0.3008962 -0.34555 0.04223835 -0.2967858 -0.34555 0.04134476 -0.292743 -0.34555 0.0400654 -0.2888051 -0.34555 0.03841173 -0.2850092 -0.34555 0.03639972 -0.2813906 -0.34555 0.03404772 -0.2779831 -0.34555 0.03137767 -0.2748184 -0.34555 0.02841484 -0.2719263 -0.34555 0.02518665 -0.2693336 -0.34555 0.02172315 -0.2670646 -0.34555 0.01805698 -0.2651404 -0.34555 0.01422226 -0.263579 -0.34555 0.01025474 -0.2623952 -0.34555 0.006191372 -0.2615997 -0.34555 0.002070069 -0.2612 -0.34555 0 -0.2789999 -0.34555 -0.003133356 -0.2791971 -0.34555 -0.01204377 -0.2820923 -0.34555 -0.009203016 -0.2807555 -0.34555 -0.0062173 -0.2797854 -0.34555 0.003133177 -0.2791971 -0.34555 0.006217122 -0.2797854 -0.34555 0.009203076 -0.2807555 -0.34555 0.01204383 -0.2820923 -0.34555 0.01469457 -0.2837745 -0.34555 0.01711356 -0.2857758 -0.34555 -0.003133356 -0.3288028 -0.34555 -0.0062173 -0.3282145 -0.34555 -0.009203016 -0.3272444 -0.34555 -0.01204377 -0.3259076 -0.34555 -0.01469451 -0.3242254 -0.34555 0.02495062 -0.3055698 -0.34555 0.02455723 -0.3086845 -0.34555 0.02377641 -0.3117254 -0.34555 0.02262055 -0.3146445 -0.34555 0.02262055 -0.2933555 -0.34555 0.02377641 -0.2962746 -0.34555 0.02455723 -0.2993155 -0.34555 0.02495062 -0.3024302 -0.34555 0.01711356 -0.3222241 -0.34555 0.01469457 -0.3242254 -0.34555 0.01204383 -0.3259076 -0.34555 0.009203076 -0.3272444 -0.34555 0.006217122 -0.3282145 -0.34555 0.02110826 -0.3173956 -0.34555 0.01926267 -0.3199356 -0.34555 -0.01926285 -0.2880644 -0.34555 -0.01711374 -0.2857758 -0.34555 -0.01469451 -0.2837745 -0.34555 -0.02377635 -0.2962746 -0.34555 -0.02262073 -0.2933555 -0.34555 -0.02110821 -0.2906042 -0.34555 -0.02455717 -0.3086845 -0.34555 -0.02495056 -0.3055698 -0.34555 -0.02495056 -0.3024302 -0.34555 -0.02455717 -0.2993155 -0.34555 -0.01711374 -0.3222241 -0.34555 -0.01926285 -0.3199356 -0.34555 -0.02110821 -0.3173956 -0.34555 0.003133177 -0.3288028 -0.34555 0 -0.329 -0.34555 0.01926267 -0.2880644 -0.34555 0.02110826 -0.2906042 -0.34555 -0.02262073 -0.3146445 -0.34555 -0.02377635 -0.3117254 -0.34555 0.003133177 -0.3288028 -0.35325 0.006217122 -0.3282145 -0.35325 0.009203076 -0.3272444 -0.35325 0.01204383 -0.3259076 -0.35325 0.01469457 -0.3242254 -0.35325 0.01711356 -0.3222241 -0.35325 0.01926267 -0.3199356 -0.35325 0.02110826 -0.3173956 -0.35325 0.02262055 -0.3146445 -0.35325 0.02377641 -0.3117254 -0.35325 0.02455723 -0.3086845 -0.35325 0.02495062 -0.3055698 -0.35325 0.02495062 -0.3024302 -0.35325 0.02455723 -0.2993155 -0.35325 0.02377641 -0.2962746 -0.35325 0.02262055 -0.2933555 -0.35325 0.02110826 -0.2906042 -0.35325 0.01926267 -0.2880644 -0.35325 0.01711356 -0.2857758 -0.35325 0.01469457 -0.2837745 -0.35325 0.01204383 -0.2820923 -0.35325 0.009203076 -0.2807555 -0.35325 0.006217122 -0.2797854 -0.35325 0.003133177 -0.2791971 -0.35325 0 -0.2789999 -0.35325 -0.003133356 -0.2791971 -0.35325 -0.0062173 -0.2797854 -0.35325 -0.009203016 -0.2807555 -0.35325 -0.01204377 -0.2820923 -0.35325 -0.01469451 -0.2837745 -0.35325 -0.01711374 -0.2857758 -0.35325 -0.01926285 -0.2880644 -0.35325 -0.02110821 -0.2906042 -0.35325 -0.02262073 -0.2933555 -0.35325 -0.02377635 -0.2962746 -0.35325 -0.02455717 -0.2993155 -0.35325 -0.02495056 -0.3024302 -0.35325 -0.02495056 -0.3055698 -0.35325 -0.02455717 -0.3086845 -0.35325 -0.02377635 -0.3117254 -0.35325 -0.02262073 -0.3146445 -0.35325 -0.02110821 -0.3173956 -0.35325 -0.01926285 -0.3199356 -0.35325 -0.01711374 -0.3222241 -0.35325 -0.01469451 -0.3242254 -0.35325 -0.01204377 -0.3259076 -0.35325 -0.009203016 -0.3272444 -0.35325 -0.0062173 -0.3282145 -0.35325 -0.003133356 -0.3288028 -0.35325 0 -0.329 -0.35325 0.1374999 -0.03699994 -0.11355 -0.1374999 -0.03699994 -0.11355 0.1374999 -0.03699994 0.27945 0.1374999 -0.3835 -0.11355 0.1374999 -0.3835 0.27945 0.1075 -0.4135 -0.11355 0.1075 -0.4135 0.27945 -0.1074999 -0.4135 -0.11355 -0.1074999 -0.4135 0.27945 -0.1374999 -0.3835 -0.11355 -0.1374999 -0.3835 0.27945 -0.1374999 -0.03699994 0.27945 - - - - - - - - - - -0.9510486 0.3090415 0 0.2817397 -0.9594909 0 -0.8229848 0.5680636 0 0.3089991 0.9510624 0 0 -0.1191444 0.992877 0.916783 0.3993859 0 0 1 0 0.8229848 0.5680636 0 -0.5877962 -0.8090091 0 0.9535371 -0.3012758 0 0.8494702 -0.5276367 0 0.9997917 0.02041083 0 -0.3319224 -0.9433068 0 0.1921225 0.9813711 0 0.6261862 0.7796736 0 0.5744825 -0.818517 0 0.7284038 0.6851481 0 0 -1 0 0.5069645 -0.861967 0 -0.964878 -0.2626985 0 -0.06280398 -0.9980259 0 0.964878 -0.2626985 0 -0.09653842 0.9953293 0 -0.8762954 -0.4817744 0 0.2859315 0.9582501 0 0.989819 -0.142332 0 0.6074011 0.7943953 0 -0.92979 0.3680906 0 0.909639 0.4154 0 -0.2817396 -0.959491 0 -0.5358185 0.8443333 0 -0.8739597 0.4859983 0 -0.8727456 0.4881753 0 -0.9927111 0.1205182 0 0.9921182 0.1253054 0 -0.3589951 -0.9333394 0 0.5358185 0.8443333 0 -0.5358182 -0.8443334 0 -0.6393225 -0.7689388 0 -0.9831935 0.1825667 0 -0.5480244 0.8364624 0 0.8739845 0.4859538 0 0.1873827 -0.9822871 0 0.9857239 -0.1683703 0 -0.1220921 -0.9925188 0 0.929764 0.3681561 0 0.04079371 -0.9991676 0 0.7289722 0.6845434 0 -1 0 0 -0.670129 0.7422448 0 -0.2393096 -0.9709434 0 0.1624714 0.9867133 0 -0.92979 -0.3680906 0 0.7289728 -0.6845428 0 -0.08151364 0.9966722 0 -0.7818385 0.6234812 0 -0.9857239 -0.1683703 0 0.6393219 -0.7689391 0 0.7818385 0.6234812 0 0.9831935 0.1825667 0 0.8727456 0.4881753 0 0.9650388 0.2621071 0 -0.9921182 0.1253054 0 0.8066303 -0.5910564 0 0.8763363 0.4816999 0 0.9258306 -0.377939 0 1.63864e-6 0 -1 0.9981299 -0.06112927 0 -0.4702671 0.8825241 0 0.976433 0.2158209 0 0.1220921 -0.9925188 0 -0.7289722 -0.6845434 0 -0.9921181 -0.1253066 0 0.1444759 -0.9895083 0 0.9921182 -0.1253054 0 0.6631191 -0.7485139 0 0.5358182 -0.8443334 0 -0.8090131 0.5877907 0 -0.3206305 0.9472044 0 -0.4338957 -0.9009631 0 0.04831194 -0.9988323 0 -0.3771118 0.9261679 0 -0.8066066 -0.5910887 0 -0.1921225 0.9813711 0 -0.4647006 0.885468 0 0.3319044 -0.9433131 0 -0.9535511 -0.3012318 0 0.06280398 -0.9980259 0 0.670153 0.742223 0 -0.5069392 -0.8619818 0 0.7945854 -0.6071527 0 0.9510653 0.30899 0 0.4338957 -0.9009631 0 -0.9997917 0.02041083 0 -0.6074017 0.7943949 0 -0.04079574 -0.9991676 0 0.9297644 -0.3681551 0 -0.728428 0.6851224 0 0.377112 0.9261677 0 -0.8494702 -0.5276367 0 1 0 0 -0.9350209 -0.3545929 0 -0.9947995 0.1018535 0 -0.048312 -0.9988324 0 0.6998491 -0.7142907 0 -0.764306 0.6448538 0 0.8964166 -0.4432125 0 -0.0241205 0.9997091 0 -0.6985185 0.715592 0 -0.1624714 0.9867133 0 0.6985185 0.715592 0 0.8520909 -0.5233938 0 0.5479983 0.8364795 0 -0.732266 -0.6810188 0 -0.1444759 -0.9895083 0 0.707104 -0.7071096 0 -0.9096206 0.41544 0 0.9948046 0.1018032 0 -0.9168043 0.399337 0 -0.9981269 -0.06117755 0 0.94046 0.3399044 0 0 0 -1 0.8919298 -0.4521741 0 -0.9749312 -0.2225066 0 -0.2859315 0.9582501 0 0.54065 0.8412477 0 0.6374467 0.7704946 0 -0.9404755 0.3398616 0 0.732266 -0.6810188 0 0.8089765 0.5878411 0 0.8089904 -0.587822 0 0.5877691 -0.8090289 0 -0.5406495 0.841248 0 0.7557559 -0.6548537 0 -0.4257948 -0.9048198 0 -0.5744825 -0.818517 0 0.6374467 -0.7704946 0 0.06280398 0.9980259 0 -0.9258128 -0.3779825 0 -0.6261862 0.7796736 0 0.8763268 -0.4817171 0 0.0241205 0.9997091 0 0 0.9999994 0.001125931 -0.3967775 0.9179148 0 -0.1873827 -0.982287 0 0.308999 -0.9510625 0 0.764306 0.6448538 0 -0.7945847 -0.6071534 0 -0.8964161 -0.4432136 0 0.9350214 -0.3545917 0 0.2423525 0.9701883 0 0.4647243 0.8854554 0 0.3967599 0.9179225 0 -0.8090259 -0.5877732 0 0.4214174 -0.9068668 0 0.830053 0.5576845 0 -1.03582e-6 0 -1 -0.830053 0.5576845 0 0.3589951 -0.9333394 0 0 0 1 -0.3090214 0.9510552 0 -1 0 0 -0.9973729 -0.07243818 0 0.9685797 0.2487037 0 0.9749312 -0.2225066 0 -0.8919298 -0.4521741 0 -0.7071068 -0.7071068 0 -0.6374092 -0.7705256 0 -0.9764453 0.2157653 0 -0.8521136 -0.5233569 0 0.997373 -0.07243692 0 -0.2025845 -0.9792648 0 -0.7557559 -0.6548537 0 0.4257948 -0.9048198 0 0.9685797 -0.2487037 0 -0.9685797 -0.2487037 0 -0.6998491 -0.7142907 0 -0.96858 0.2487026 0 0.1873826 0.982287 0 -0.505878 -0.862605 0 -0.6631185 -0.7485145 0 -0.7289728 0.6845428 0 -0.9997075 0.02418434 0 -0.3090215 -0.9510551 0 -0.9650388 0.2621071 0 -0.6374094 0.7705253 0 0.08151757 0.9966719 0 0.505878 -0.862605 0 -0.4257951 0.9048197 0 0.9997075 0.02418565 0 -0.989819 -0.142332 0 -0.2423639 0.9701855 0 4.22069e-6 0 -1 0.2393096 -0.9709434 0 0.2025845 -0.9792648 0 0.4257951 0.9048197 0 0.9927111 0.1205194 0 -0.1873826 0.9822871 0 -0.4214174 -0.9068668 0 -0.06280398 0.9980259 0 0.4702667 0.8825245 0 -8.18566e-7 0 -1 0.09653294 0.9953298 0 -0.8763043 0.4817581 0 0.3206454 0.9471994 0 0 -0.5655286 -0.8247287 0.7071067 -0.7071069 0 -0.7071067 -0.7071069 0 -0.9510487 0.3090412 0 0.2817386 -0.9594912 0 -0.8229857 0.5680621 0 0.3089947 0.9510639 0 0 -0.1191444 0.992877 0 -0.1191444 0.992877 0.9167836 0.3993844 0 0.8229857 0.5680621 0 -0.5877972 -0.8090084 0 0.9535367 -0.3012772 0 0.84947 -0.527637 0 0.9997918 0.02040863 0 0.1921226 0.981371 0 0.626186 0.7796739 0 0.5744817 -0.8185176 0 0.7284021 0.6851499 0 0.5069652 -0.8619666 0 -0.9648781 -0.2626981 0 -0.06280398 -0.9980259 0 0.9648781 -0.2626981 0 -0.09653872 0.9953293 0 -0.8762931 -0.4817785 0 0.2859317 0.9582501 0 0.9898189 -0.1423323 0 -0.9297913 0.3680874 0 0.9096385 0.4154008 0 -0.2817386 -0.9594912 0 -0.5358148 0.8443356 0 -0.873961 0.4859963 0 -0.872745 0.4881764 0 -0.9927111 0.1205192 0 0.5358148 0.8443356 0 -0.5358151 -0.8443354 0 -0.6393212 -0.76894 0 -0.9831934 0.1825671 0 -0.5480254 0.8364618 0 0.8739851 0.4859527 0 0.1873815 -0.9822873 0 0.9857237 -0.1683715 0 -0.1220918 -0.9925189 0 0.9297657 0.3681519 0 0.04079377 -0.9991676 0 0.7289683 0.6845476 0 -0.6701283 0.7422454 0 -0.2393099 -0.9709433 0 0.1624711 0.9867133 0 -0.9297913 -0.3680874 0 0.7289676 -0.6845482 0 -0.08151352 0.9966723 0 -0.7818369 0.623483 0 -0.9857237 -0.1683715 0 0.6393212 -0.76894 0 0.7818369 0.623483 0 0.9831934 0.1825671 0 0.872745 0.4881764 0 0.9650385 0.2621083 0 -0.9921181 0.1253066 0 0.8066281 -0.5910593 0 0.8763347 0.4817028 0 0.9258291 -0.3779426 0 1.63482e-6 0 -1 1.39087e-6 0 -1 -6.95263e-7 0 -1 1.38937e-6 0 -1 0 0 -1 8.18566e-7 0 -1 -3.27204e-6 0 -1 0.9981299 -0.06112939 0 -0.4702653 0.8825251 0 0.9764331 0.2158203 0 0.1220918 -0.9925189 0 -0.7289683 -0.6845476 0 -0.9921182 -0.1253054 0 0.1444761 -0.9895084 0 0.6631192 -0.7485139 0 0.5358151 -0.8443354 0 -0.8090109 0.5877938 0 -0.32063 0.9472046 0 -0.4338948 -0.9009636 0 0.048312 -0.9988323 0 -0.3771121 0.9261677 0 -0.8066045 -0.5910916 0 -0.1921226 0.9813709 0 -0.4647011 0.8854677 0 -0.9535506 -0.3012331 0 0.06280398 -0.9980259 0 0.670153 0.7422231 0 -0.5069403 -0.8619813 0 0.9510658 0.3089885 0 0.4338948 -0.9009636 0 -0.9997918 0.02040863 0 -0.6074011 0.7943953 0 -0.04079568 -0.9991675 0 0.9297654 -0.3681529 0 -0.7284269 0.6851236 0 0.3771121 0.9261677 0 -0.84947 -0.527637 0 1 -3.2678e-7 0 -0.9350214 -0.3545913 0 -0.9947996 0.1018514 0 -0.048312 -0.9988323 0 0.699848 -0.7142919 0 -0.7643066 0.6448532 0 0.8964166 -0.4432126 0 -0.6985179 0.7155926 0 -0.1624711 0.9867133 0 0.8520913 -0.5233932 0 0.5479987 0.8364792 0 -0.7322669 -0.6810178 0 -0.1444761 -0.9895083 0 0.707104 -0.7071096 0 -0.9096202 0.415441 0 0.9948046 0.1018034 0 -0.9168044 0.3993365 0 -0.9981268 -0.06117999 0 0.9404602 0.3399039 0 -3.00402e-6 0 -1 -1.32584e-6 0 -1 -1.72119e-6 0 -1 1.97976e-6 0 -1 2.96373e-6 0 -1 2.67563e-6 0 -1 -2.28473e-6 0 -1 -4.96981e-6 0 -1 4.36357e-6 0 -1 0.8919293 -0.4521751 0 -0.974931 -0.2225076 0 -0.2859318 0.95825 0 0.5406492 0.8412482 0 -0.9404749 0.339863 0 0.7322663 -0.6810185 0 0.8089754 0.5878426 0 0.8089881 -0.5878251 0 0.5877701 -0.809028 0 -0.5406492 0.8412482 0 -0.4257912 -0.9048216 0 -0.5744811 -0.8185179 0 0.06280398 0.9980259 0 -0.9258129 -0.3779821 0 -0.6261866 0.7796733 0 0.8763251 -0.4817202 0 -0.3967778 0.9179148 0 -0.1873815 -0.9822872 0 0.3089947 -0.9510638 0 0.7643066 0.6448532 0 -0.7945854 -0.6071527 0 -0.8964171 -0.4432115 0 0.935021 -0.3545925 0 0.2423518 0.9701884 0 -4.14601e-6 0 -1 -1.26068e-5 0 -1 1.26236e-5 0 -1 1.03815e-6 0 -1 -1.26236e-5 0 -1 1.26068e-5 0 -1 1.26359e-5 0 -1 1.6596e-5 0 -1 -7.25076e-6 0 -1 -1.03815e-6 0 -1 -1.03726e-5 0 -1 0.4647248 0.8854552 0 0.3967603 0.9179223 0 -0.8090248 -0.5877746 0 0.8300505 0.5576882 0 3.15406e-6 0 -1 -6.30795e-6 0 -1 -1.26295e-5 0 -1 6.21664e-6 0 -1 1.03583e-6 0 -1 -3.15173e-6 0 -1 1.26288e-5 0 -1 3.15398e-6 0 -1 -1.57703e-6 0 -1 -3.94865e-7 0 -1 4.14601e-6 0 -1 -6.31473e-6 0 -1 4.14436e-6 0 -1 -1.26237e-5 0 -1 4.14623e-6 0 -1 -2.07214e-6 0 -1 -4.14601e-6 0 -1 -1.57586e-6 0 -1 -4.15273e-6 0 -1 3.15916e-6 0 -1 4.73604e-6 0 -1 -3.15179e-6 0 -1 6.31187e-6 0 -1 -4.14424e-6 0 -1 4.14424e-6 0 -1 4.15273e-6 0 -1 2.07203e-6 0 -1 -7.26696e-6 0 -1 -0.8300505 0.5576882 0 0.358995 -0.9333395 0 -0.3090171 0.9510565 0 -0.9973731 -0.0724368 0 0.968579 0.2487061 0 0.974931 -0.2225076 0 -0.8919293 -0.4521751 0 -0.7071068 -0.7071067 0 -0.6374094 -0.7705253 0 -0.9764451 0.215766 0 -0.852113 -0.5233579 0 0.9973729 -0.07243812 0 -0.2025846 -0.9792648 0 -0.7557563 -0.654853 0 0.4257912 -0.9048216 0 0.968579 -0.2487061 0 -0.9685794 -0.2487049 0 -0.6998474 -0.7142925 0 -0.968579 0.2487061 0 0.1873816 0.9822872 0 -0.5058772 -0.8626055 0 -0.6631198 -0.7485133 0 -0.7289676 0.6845482 0 -0.9997075 0.02418559 0 -0.309017 -0.9510565 0 -0.9650391 0.2621061 0 -0.6374092 0.7705256 0 0.08151745 0.9966719 0 0.5058772 -0.8626055 0 -0.4257909 0.9048216 0 0.9997075 0.02418434 0 -0.9898189 -0.1423323 0 -0.2423634 0.9701856 0 1.32584e-6 0 -1 -1.61876e-5 0 -1 1.72122e-6 0 -1 -2.67566e-6 0 -1 5.73946e-5 0 -1 -1.12039e-4 0 -1 2.28476e-6 0 -1 2.07483e-6 0 -1 -1.97976e-6 0 -1 -1.97519e-6 0 -1 2.80546e-5 0 -1 -4.36361e-6 0 -1 4.96993e-6 0 -1 -2.96373e-6 0 -1 3.00387e-6 0 -1 -3.1775e-6 0 -1 3.49585e-6 0 -1 1.61892e-5 0 -1 -5.04809e-6 0 -1 -4.30333e-5 0 -1 1.1204e-4 0 -1 -1.57807e-5 0 -1 1.43312e-6 0 -1 7.3497e-6 0 -1 5.40324e-6 0 -1 -6.3476e-6 0 -1 -1.34934e-6 0 -1 8.41951e-7 0 -1 -4.19468e-6 0 -1 0.2393099 -0.9709433 0 0.2025845 -0.9792648 0 0.4257909 0.9048216 0 0.9927111 0.120518 0 -0.1873815 0.9822873 0 -0.4214177 -0.9068667 0 -0.06280398 0.9980259 0 0.4702653 0.8825251 0 9.42951e-5 0 -1 1.88513e-4 0 -1 9.42596e-5 0 -1 -2.35627e-5 0 -1 -9.42063e-5 0 -1 -6.36664e-5 0 -1 -1.88513e-4 0 -1 -9.41974e-5 0 -1 -6.31552e-5 0 -1 9.42329e-5 0 -1 4.71209e-5 0 -1 3.15796e-5 0 -1 -4.71032e-5 0 -1 -9.42152e-5 0 -1 -3.24641e-5 0 -1 7.15239e-5 0 -1 -4.76832e-5 0 -1 5.1835e-6 0 -1 -2.14862e-6 0 -1 3.30751e-6 0 -1 1.11271e-5 0 -1 1.1123e-5 0 -1 -4.90908e-6 0 -1 -1.11107e-5 0 -1 1.30941e-5 0 -1 3.27014e-6 0 -1 8.99598e-6 0 -1 -1.30851e-5 0 -1 1.11107e-5 0 -1 -5.56149e-6 0 -1 -5.56353e-6 0 -1 1.63473e-6 0 -1 3.27669e-6 0 -1 2.77982e-6 0 -1 -1.39079e-6 0 -1 1.39081e-6 0 -1 6.95024e-7 0 -1 0 0 -1 -1.63861e-6 0 -1 -1.63486e-6 0 -1 5.54902e-6 0 -1 6.54802e-6 0 -1 1.11057e-5 0 -1 -8.17748e-6 0 -1 1.30862e-5 0 -1 -1.11273e-5 0 -1 1.11268e-5 0 -1 -6.53905e-6 0 -1 -5.55278e-6 0 -1 8.19044e-6 0 -1 5.55926e-6 0 -1 1.3084e-5 0 -1 5.55469e-6 0 -1 -2.77451e-6 0 -1 -3.3004e-6 0 -1 3.27238e-6 0 -1 6.34177e-6 0 -1 3.26967e-6 0 -1 -3.27242e-6 0 -1 4.90932e-6 0 -1 -9.82055e-6 0 -1 -1.6391e-6 0 -1 -4.90477e-6 0 -1 4.90403e-6 0 -1 6.53905e-6 0 -1 -1.63473e-6 0 -1 -3.274e-6 0 -1 3.26944e-6 0 -1 -1.30862e-5 0 -1 -8.19001e-6 0 -1 3.27204e-6 0 -1 -1.63471e-6 0 -1 0.09653317 0.9953298 0 -0.8763032 0.4817602 0 0.3206447 0.9471997 0 -1 0 0 0 -0.5655286 -0.8247288 0.7071069 -0.7071067 0 -0.7071069 -0.7071067 0 - - - - - - - - - - 0.2690766 0.7602443 0.2741281 0.7611926 0.2740678 0.7614139 0.2810737 0.7751497 0.2789908 0.7716562 0.2797521 0.7714221 0.2698519 0.7581998 0.2744332 0.7605761 0.2743114 0.7607717 0.2766808 0.760586 0.2767212 0.7609833 0.2765989 0.7609483 0.2944679 0.8976456 0.3093212 0.9046915 0.2564226 0.8971281 0.2830656 0.7585365 0.2785688 0.7610405 0.2784734 0.7608321 0.3068308 0.5893464 0.2405185 0.6721856 0.238913 0.5906843 0.2822929 0.7572955 0.2783583 0.7606337 0.2782241 0.7604471 0.2725973 0.7681599 0.2749758 0.763827 0.2751637 0.7639513 0.2905865 0.7660331 0.2861081 0.7654781 0.2863917 0.7646754 0.2828412 0.7654592 0.2783471 0.7632217 0.2784628 0.7630268 0.2912544 0.7611389 0.286825 0.7621439 0.2868249 0.7612802 0.2745059 0.7689449 0.27557 0.7641434 0.275785 0.7642094 0.2773066 0.7544504 0.2768836 0.7596057 0.2766561 0.7595654 0.2807115 0.7557716 0.2779047 0.7601168 0.2777225 0.7599761 0.2847921 0.773194 0.2818989 0.7703975 0.282562 0.7699541 0.2868462 0.7511213 0.2842975 0.7549355 0.2836986 0.7542991 0.2767093 0.7760908 0.2852745 0.7756404 0.287454 0.8138352 0.2804482 0.7679679 0.277527 0.7639828 0.2777183 0.7638636 0.2694282 0.7645066 0.2740945 0.7625453 0.2741647 0.7627616 0.2764197 0.7633102 0.2762815 0.7629395 0.2764085 0.7629439 0.2836304 0.7634797 0.2786362 0.7626078 0.2786918 0.762387 0.2750959 0.7545062 0.2761723 0.7595527 0.2759431 0.7595871 0.2752406 0.7627229 0.2754775 0.7624081 0.275542 0.762516 0.3093212 0.9046915 0.2410798 0.9260728 0.2413831 0.9037673 0.2780351 0.754576 0.2771058 0.7596678 0.2768836 0.7596057 0.2911301 0.7636198 0.2866069 0.7638478 0.2867518 0.7630018 0.284935 0.7495188 0.283048 0.753714 0.2823501 0.7531844 0.2750477 0.7615668 0.2754466 0.7615489 0.2754038 0.7616692 0.2897421 0.7551426 0.2861006 0.7579016 0.2857455 0.7571071 0.2733517 0.7756586 0.2734621 0.7715781 0.2742335 0.7717748 0.2755238 0.7608516 0.2758592 0.7610719 0.2757538 0.7611448 0.2695258 0.7588557 0.2743114 0.7607717 0.2742096 0.7609779 0.2626964 0.755736 0.2671613 0.7567671 0.2667756 0.7575502 0.2689105 0.7616877 0.274029 0.7616397 0.2740122 0.761868 0.2777245 0.7616401 0.2773828 0.7618425 0.2773631 0.761717 0.272302 0.7753511 0.2727093 0.7713254 0.2734621 0.7715781 0.2770085 0.7607043 0.2769475 0.7610984 0.2768381 0.7610337 0.2757549 0.7631672 0.2758095 0.7627782 0.2759186 0.7628407 0.2684929 0.7735803 0.2699279 0.7697854 0.2705855 0.7702478 0.2614825 0.7605615 0.2660289 0.7600488 0.2659233 0.760912 0.2717522 0.7559806 0.2750906 0.7599352 0.2749034 0.7600709 0.2827098 0.7578976 0.2784734 0.7608321 0.2783583 0.7606337 0.2767584 0.7632565 0.2765346 0.7629322 0.2766578 0.762905 0.2837612 0.7627731 0.2786918 0.762387 0.2787261 0.7621617 0.2755621 0.7760357 0.27502 0.7719126 0.275817 0.7719888 0.2776098 0.7613133 0.2773276 0.7615949 0.2772782 0.7614774 0.2766191 0.7720015 0.2778511 0.7759834 0.2767093 0.7760908 0.2772951 0.7609011 0.2771372 0.7612668 0.2770478 0.7611767 0.1777017 0.750389 0.1721973 0.8039242 0.1658931 0.8040312 0.2654212 0.7515816 0.2693191 0.7540295 0.2686949 0.7546449 0.2751793 0.769086 0.275785 0.7642094 0.2760051 0.7642548 0.277955 0.7468559 0.2783252 0.7514938 0.2774522 0.7513651 0.2751516 0.7625757 0.2754263 0.7622928 0.2754775 0.7624081 0.2774597 0.7627819 0.2770868 0.7626494 0.2771699 0.7625534 0.2741435 0.7469215 0.2756878 0.7513307 0.2748096 0.7514257 0.2638853 0.7535471 0.2681247 0.7553095 0.2676124 0.7560185 0.2691957 0.7638285 0.2740454 0.7623229 0.2740945 0.7625453 0.2856755 0.7725847 0.282562 0.7699541 0.283196 0.7694607 0.3782616 0.7458982 0.3717355 0.8020083 0.3643841 0.7477795 0.2876939 0.7520342 0.2848408 0.755619 0.2842975 0.7549355 0.2909666 0.7586578 0.2867518 0.7604175 0.2866062 0.7595624 0.2558992 0.6941683 0.2939339 0.6934571 0.2559 0.6942063 0.2891463 0.7540518 0.2857455 0.7571071 0.2853249 0.7563444 0.2906549 0.7574529 0.2866062 0.7595624 0.2863889 0.7587215 0.2749966 0.7619097 0.2753767 0.7617936 0.2753658 0.7619203 0.2882384 0.7702778 0.2843608 0.7683218 0.2848799 0.7676767 0.2775226 0.7611631 0.2772782 0.7614774 0.2772144 0.7613676 0.2901545 0.7671871 0.285759 0.76625 0.2861081 0.7654781 0.2838216 0.7620546 0.2838119 0.7613316 0.2868249 0.7612802 0.2912442 0.7623832 0.2867518 0.7630018 0.286825 0.7621439 0.2682889 0.749168 0.2714726 0.7525211 0.2707123 0.7529633 0.2835778 0.7599003 0.2786971 0.7614795 0.2786436 0.7612571 0.2789637 0.7757861 0.2774196 0.7719483 0.2782119 0.7718325 0.2754697 0.7629777 0.2756198 0.7626147 0.2757095 0.7627024 0.275032 0.7622531 0.27537 0.7620469 0.2753902 0.7621718 0.2779148 0.7690188 0.2766774 0.7642639 0.2768987 0.7642242 0.2777541 0.7619846 0.2773739 0.7620949 0.2773864 0.761969 0.2815386 0.7671093 0.2778974 0.7637267 0.2780631 0.7635732 0.2772158 0.7630243 0.2768884 0.7628048 0.2769926 0.7627335 0.2751831 0.7612464 0.2755752 0.7613275 0.2755047 0.7614347 0.270505 0.7479817 0.2730935 0.7518337 0.2722682 0.7521436 0.2712953 0.7749782 0.2719776 0.7710191 0.2727093 0.7713254 0.2772361 0.7691304 0.2764533 0.7642824 0.2766774 0.7642639 0.272996 0.7551917 0.2754999 0.7597203 0.2752901 0.759818 0.2657599 0.7716833 0.2681552 0.7680865 0.2687069 0.7687048 0.2743735 0.754664 0.2759431 0.7595871 0.2757181 0.759643 0.2723544 0.7555558 0.2752901 0.759818 0.2750906 0.7599352 0.2792276 0.76861 0.2771154 0.7641639 0.2773255 0.7640833 0.2628254 0.7678383 0.2664894 0.7651605 0.2668139 0.76595 0.2764085 0.7629439 0.2765908 0.7632939 0.2764197 0.7633102 0.2859246 0.7502809 0.2836986 0.7542991 0.283048 0.753714 0.2732105 0.7684787 0.2751637 0.7639513 0.2753623 0.7640569 0.2824581 0.7660529 0.2782135 0.7634045 0.2783471 0.7632217 0.2833563 0.7592061 0.2786436 0.7612571 0.2785688 0.7610405 0.2830035 0.7742604 0.2804922 0.7711328 0.2812088 0.7707914 0.2615105 0.7630626 0.2658907 0.7617796 0.2659316 0.7626451 0.2663075 0.7506996 0.2699931 0.7534676 0.2693191 0.7540295 0.2767093 0.7760908 0.275817 0.7719888 0.2766191 0.7720015 0.2776972 0.7623248 0.2773017 0.7623367 0.2773455 0.7622181 0.264612 0.752533 0.2686949 0.7546449 0.2681247 0.7553095 0.2787466 0.7547736 0.277321 0.7597506 0.2771058 0.7596678 0.2704947 0.7663442 0.2743654 0.7631677 0.2744938 0.7633542 0.4092137 0.8187897 0.3948314 0.8207395 0.3920238 0.8000288 0.2697251 0.7651557 0.2741647 0.7627616 0.2742553 0.7629697 0.2614446 0.761814 0.2659233 0.760912 0.2658907 0.7617796 0.2765502 0.7691782 0.2762285 0.7642791 0.2764533 0.7642824 0.2865573 0.7719084 0.283196 0.7694607 0.2837973 0.7689168 0.270241 0.757578 0.2745733 0.760393 0.2744332 0.7605761 0.2831674 0.7648292 0.2784628 0.7630268 0.2785595 0.7628216 0.2762992 0.759545 0.2761723 0.7595527 0.2758301 0.7544226 0.2706905 0.7569971 0.2747306 0.7602242 0.2745733 0.760393 0.2728987 0.7471747 0.2748096 0.7514257 0.2739426 0.7515938 0.2812889 0.7562271 0.2780724 0.7602744 0.2779047 0.7601168 0.2889728 0.7693212 0.2848799 0.7676767 0.2853481 0.7669852 0.2993318 0.8126704 0.2936534 0.770011 0.3467861 0.7629384 0.2800911 0.7553752 0.2777225 0.7599761 0.2775272 0.7598538 0.2714659 0.7673552 0.2746392 0.7635273 0.2748004 0.7636853 0.2758627 0.7691641 0.2760051 0.7642548 0.2762285 0.7642791 0.2852745 0.7756404 0.2993318 0.8126704 0.287454 0.8138352 0.2622414 0.7568964 0.2667756 0.7575502 0.2664567 0.7583618 0.2911617 0.7598946 0.2868249 0.7612802 0.2867518 0.7604175 0.2692666 0.7595394 0.2742096 0.7609779 0.2741281 0.7611926 0.2616807 0.7642992 0.2659316 0.7626451 0.2660462 0.7635013 0.290246 0.7562787 0.2863889 0.7587215 0.2861006 0.7579016 0.2681406 0.7760329 0.2675807 0.7730188 0.2684929 0.7735803 0.2896152 0.7682876 0.2853481 0.7669852 0.285759 0.76625 0.262337 0.7666989 0.2662327 0.7643419 0.2664894 0.7651605 0.2736712 0.7548934 0.2757181 0.759643 0.2754999 0.7597203 0.2838837 0.7488406 0.2823501 0.7531844 0.2816099 0.7527141 0.277158 0.7607938 0.2770478 0.7611767 0.2769475 0.7610984 0.261883 0.758091 0.2664567 0.7583618 0.2662072 0.7591968 0.2820222 0.7666042 0.2780631 0.7635732 0.2782135 0.7634045 0.2774172 0.761025 0.2772144 0.7613676 0.2771372 0.7612668 0.2775576 0.7626399 0.2771699 0.7625534 0.2772428 0.7624492 0.2810123 0.7675648 0.2777183 0.7638636 0.2778974 0.7637267 0.2672655 0.7498931 0.2707123 0.7529633 0.2699931 0.7534676 0.287426 0.7711521 0.2837973 0.7689168 0.2843608 0.7683218 0.2759131 0.7632336 0.2759186 0.7628407 0.2760346 0.762889 0.2694036 0.7740886 0.2705855 0.7702478 0.2712693 0.7706589 0.2773452 0.7629107 0.2769926 0.7627335 0.2770868 0.7626494 0.2763328 0.7605545 0.2764728 0.7609292 0.2763451 0.7609262 0.2634205 0.768918 0.2668139 0.76595 0.2672027 0.7667048 0.2711957 0.7564628 0.2749034 0.7600709 0.2747306 0.7602242 0.2776373 0.7624868 0.2772428 0.7624492 0.2773017 0.7623367 0.2765684 0.7543987 0.2764259 0.7595467 0.2762992 0.759545 0.2765684 0.7543987 0.2762992 0.759545 0.2758301 0.7544226 0.269371 0.7485293 0.2722682 0.7521436 0.2714726 0.7525211 0.276248 0.7633057 0.2761562 0.7629222 0.2762815 0.7629395 0.27692 0.7631984 0.2766578 0.762905 0.2767763 0.7628623 0.2818177 0.7567368 0.2782241 0.7604471 0.2780724 0.7602744 0.2939332 0.693419 0.2558992 0.6941683 0.2405185 0.6721856 0.2709577 0.7668739 0.2744938 0.7633542 0.2746392 0.7635273 0.2700825 0.7657697 0.2742553 0.7629697 0.2743654 0.7631677 0.2834317 0.7641673 0.2785595 0.7628216 0.2786362 0.7626078 0.2792054 0.7470543 0.2791833 0.7516951 0.2783252 0.7514938 0.2770085 0.7607043 0.2768485 0.7606347 0.277321 0.7597506 0.2794342 0.755041 0.2775272 0.7598538 0.277321 0.7597506 0.1914018 0.7517976 0.1721973 0.8039242 0.1777017 0.750389 0.2816244 0.7477546 0.2808313 0.7523077 0.2800206 0.7519671 0.2753472 0.7628575 0.275542 0.762516 0.2756198 0.7626147 0.2798515 0.7683161 0.2773255 0.7640833 0.277527 0.7639828 0.2884622 0.7530133 0.2853249 0.7563444 0.2848408 0.755619 0.2760051 0.7642548 0.2760783 0.7632802 0.276248 0.7633057 0.2632455 0.7546171 0.2676124 0.7560185 0.2671613 0.7567671 0.2820615 0.7747304 0.2797521 0.7714221 0.2804922 0.7711328 0.3090177 0.926997 0.240869 0.9415627 0.2410798 0.9260728 0.2758229 0.7606709 0.2760927 0.7609678 0.2759727 0.7610123 0.2750035 0.7620826 0.2753658 0.7619203 0.27537 0.7620469 0.2690307 0.7631278 0.2740179 0.7620964 0.2740454 0.7623229 0.2776775 0.7614732 0.2773631 0.761717 0.2773276 0.7615949 0.2909113 0.7648399 0.2863917 0.7646754 0.2866069 0.7638478 0.2641166 0.7699241 0.2672027 0.7667048 0.2676516 0.7674193 0.2594227 0.7708541 0.2657138 0.8135393 0.2551456 0.8124527 0.2756063 0.7630815 0.2757095 0.7627024 0.2758095 0.7627782 0.2689576 0.7609627 0.2740678 0.7614139 0.274029 0.7616397 0.2649012 0.7708474 0.2676516 0.7674193 0.2681552 0.7680865 0.2838216 0.7620546 0.2787261 0.7621617 0.2787386 0.7619341 0.2744405 0.7758895 0.2742335 0.7717748 0.27502 0.7719126 0.2666662 0.7723912 0.2687069 0.7687048 0.2693001 0.7692711 0.2770734 0.7631207 0.2767763 0.7628623 0.2768884 0.7628048 0.2777364 0.7621566 0.2773455 0.7622181 0.2773739 0.7620949 0.2750818 0.7624182 0.2753902 0.7621718 0.2754263 0.7622928 0.2675807 0.7730188 0.2693001 0.7692711 0.2699279 0.7697854 0.2777501 0.7618116 0.2773864 0.761969 0.2773828 0.7618425 0.2750113 0.7617368 0.2754038 0.7616692 0.2753767 0.7617936 0.2765079 0.760559 0.2765989 0.7609483 0.2764728 0.7609292 0.2703317 0.7745539 0.2712693 0.7706589 0.2719776 0.7710191 0.2720142 0.7677846 0.2748004 0.7636853 0.2749758 0.763827 0.2752796 0.761101 0.2756587 0.7612305 0.2755752 0.7613275 0.2689355 0.7624117 0.2740122 0.761868 0.2740179 0.7620964 0.2760783 0.7632802 0.2760346 0.762889 0.2761562 0.7629222 0.2616235 0.7593126 0.2662072 0.7591968 0.2660289 0.7600488 0.2753937 0.7609687 0.2757538 0.7611448 0.2756587 0.7612305 0.2766875 0.7467613 0.2774522 0.7513651 0.2765708 0.7513099 0.2839077 0.7737493 0.2812088 0.7707914 0.2818989 0.7703975 0.2756675 0.7607519 0.2759727 0.7610123 0.2758592 0.7610719 0.2838119 0.7613316 0.2787386 0.7619341 0.278729 0.7617059 0.2619559 0.7655148 0.2660462 0.7635013 0.2662327 0.7643419 0.2716833 0.747529 0.2739426 0.7515938 0.2730935 0.7518337 0.2943882 0.7165156 0.2859246 0.7502809 0.284935 0.7495188 0.2785804 0.7688449 0.2768987 0.7642242 0.2771154 0.7641639 0.2800399 0.7755053 0.2782119 0.7718325 0.2789908 0.7716562 0.2768485 0.7606347 0.2768381 0.7610337 0.2767212 0.7609833 0.2837304 0.760611 0.278729 0.7617059 0.2786971 0.7614795 0.2759874 0.7606104 0.2762175 0.7609389 0.2760927 0.7609678 0.273848 0.7687419 0.2753623 0.7640569 0.27557 0.7641434 0.2754104 0.7467718 0.2765708 0.7513099 0.2756878 0.7513307 0.2761583 0.7605713 0.2763451 0.7609262 0.2762175 0.7609389 0.2827778 0.7482511 0.2816099 0.7527141 0.2808313 0.7523077 0.2771699 0.7625534 0.2762815 0.7629395 0.2755047 0.7614347 0.2689355 0.7624117 0.2690307 0.7631278 0.2660462 0.7635013 0.2765684 0.7543987 0.2766561 0.7595654 0.2764259 0.7595467 0.2751052 0.7614025 0.2755047 0.7614347 0.2754466 0.7615489 0.2804312 0.7473547 0.2800206 0.7519671 0.2791833 0.7516951 0.2076111 0.7655269 0.2551456 0.8124527 0.1858975 0.8053328 0.2943882 0.7165156 0.2559 0.6942063 0.2939339 0.6934571 0.1320422 0.8356735 0.1262516 0.8415833 0.08432489 0.8420109 0.1305715 0.6914646 0.07772582 0.7686499 0.07694429 0.6920117 0.2020955 0.8408099 0.1353068 0.9181372 0.1345251 0.8414989 0.1345251 0.8414989 0.1270332 0.9182216 0.1262516 0.8415833 0.1262516 0.8415833 0.08510655 0.9186492 0.08432489 0.8420109 0.08432489 0.8420109 0.076833 0.9187335 0.07605141 0.8420953 0.07605141 0.8420953 0.009262621 0.9194228 0.008481025 0.8427844 0.08510655 0.9186492 0.1270332 0.9182216 0.1329432 0.9240122 0.2690766 0.7602443 0.2692666 0.7595394 0.2741281 0.7611926 0.2810737 0.7751497 0.2800399 0.7755053 0.2789908 0.7716562 0.2698519 0.7581998 0.270241 0.757578 0.2744332 0.7605761 0.2766808 0.760586 0.2768485 0.7606347 0.2767212 0.7609833 0.2944679 0.8976456 0.3094143 0.8978489 0.3093212 0.9046915 0.3093212 0.9046915 0.2413831 0.9037673 0.2564226 0.8971281 0.2413831 0.9037673 0.2414762 0.8969247 0.2564226 0.8971281 0.2564226 0.8971281 0.2574504 0.8215809 0.2954957 0.8220986 0.2574504 0.8215809 0.2657138 0.8135393 0.287454 0.8138352 0.287454 0.8138352 0.2954957 0.8220986 0.2574504 0.8215809 0.2954957 0.8220986 0.2944679 0.8976456 0.2564226 0.8971281 0.2830656 0.7585365 0.2833563 0.7592061 0.2785688 0.7610405 0.3068308 0.5893464 0.3084363 0.6708478 0.2405185 0.6721856 0.2822929 0.7572955 0.2827098 0.7578976 0.2783583 0.7606337 0.2725973 0.7681599 0.2720142 0.7677846 0.2749758 0.763827 0.2905865 0.7660331 0.2901545 0.7671871 0.2861081 0.7654781 0.2828412 0.7654592 0.2824581 0.7660529 0.2783471 0.7632217 0.2912544 0.7611389 0.2912442 0.7623832 0.286825 0.7621439 0.2745059 0.7689449 0.273848 0.7687419 0.27557 0.7641434 0.2773066 0.7544504 0.2780351 0.754576 0.2768836 0.7596057 0.2807115 0.7557716 0.2812889 0.7562271 0.2779047 0.7601168 0.2847921 0.773194 0.2839077 0.7737493 0.2818989 0.7703975 0.2868462 0.7511213 0.2876939 0.7520342 0.2842975 0.7549355 0.287454 0.8138352 0.2657138 0.8135393 0.2767093 0.7760908 0.2657138 0.8135393 0.2681406 0.7760329 0.2767093 0.7760908 0.2804482 0.7679679 0.2798515 0.7683161 0.277527 0.7639828 0.2694282 0.7645066 0.2691957 0.7638285 0.2740945 0.7625453 0.2764197 0.7633102 0.276248 0.7633057 0.2762815 0.7629395 0.2836304 0.7634797 0.2834317 0.7641673 0.2786362 0.7626078 0.2750959 0.7545062 0.2758301 0.7544226 0.2761723 0.7595527 0.2752406 0.7627229 0.2751516 0.7625757 0.2754775 0.7624081 0.3093212 0.9046915 0.3090177 0.926997 0.2410798 0.9260728 0.2780351 0.754576 0.2787466 0.7547736 0.2771058 0.7596678 0.2911301 0.7636198 0.2909113 0.7648399 0.2866069 0.7638478 0.284935 0.7495188 0.2859246 0.7502809 0.283048 0.753714 0.2750477 0.7615668 0.2751052 0.7614025 0.2754466 0.7615489 0.2897421 0.7551426 0.290246 0.7562787 0.2861006 0.7579016 0.2733517 0.7756586 0.272302 0.7753511 0.2734621 0.7715781 0.2755238 0.7608516 0.2756675 0.7607519 0.2758592 0.7610719 0.2695258 0.7588557 0.2698519 0.7581998 0.2743114 0.7607717 0.2626964 0.755736 0.2632455 0.7546171 0.2671613 0.7567671 0.2689105 0.7616877 0.2689576 0.7609627 0.274029 0.7616397 0.2777245 0.7616401 0.2777501 0.7618116 0.2773828 0.7618425 0.272302 0.7753511 0.2712953 0.7749782 0.2727093 0.7713254 0.2770085 0.7607043 0.277158 0.7607938 0.2769475 0.7610984 0.2757549 0.7631672 0.2756063 0.7630815 0.2758095 0.7627782 0.2684929 0.7735803 0.2675807 0.7730188 0.2699279 0.7697854 0.2614825 0.7605615 0.2616235 0.7593126 0.2660289 0.7600488 0.2717522 0.7559806 0.2723544 0.7555558 0.2750906 0.7599352 0.2827098 0.7578976 0.2830656 0.7585365 0.2784734 0.7608321 0.2767584 0.7632565 0.2765908 0.7632939 0.2765346 0.7629322 0.2837612 0.7627731 0.2836304 0.7634797 0.2786918 0.762387 0.2755621 0.7760357 0.2744405 0.7758895 0.27502 0.7719126 0.2776098 0.7613133 0.2776775 0.7614732 0.2773276 0.7615949 0.2766191 0.7720015 0.2774196 0.7719483 0.2778511 0.7759834 0.2772951 0.7609011 0.2774172 0.761025 0.2771372 0.7612668 0.1658931 0.8040312 0.1637909 0.8244769 0.1495926 0.8230171 0.1495926 0.8230171 0.157276 0.7482888 0.1658931 0.8040312 0.157276 0.7482888 0.1777017 0.750389 0.1658931 0.8040312 0.2654212 0.7515816 0.2663075 0.7506996 0.2693191 0.7540295 0.2751793 0.769086 0.2745059 0.7689449 0.275785 0.7642094 0.277955 0.7468559 0.2792054 0.7470543 0.2783252 0.7514938 0.2751516 0.7625757 0.2750818 0.7624182 0.2754263 0.7622928 0.2774597 0.7627819 0.2773452 0.7629107 0.2770868 0.7626494 0.2741435 0.7469215 0.2754104 0.7467718 0.2756878 0.7513307 0.2638853 0.7535471 0.264612 0.752533 0.2681247 0.7553095 0.2691957 0.7638285 0.2690307 0.7631278 0.2740454 0.7623229 0.2856755 0.7725847 0.2847921 0.773194 0.282562 0.7699541 0.3782616 0.7458982 0.3856131 0.800127 0.3717355 0.8020083 0.2876939 0.7520342 0.2884622 0.7530133 0.2848408 0.755619 0.2909666 0.7586578 0.2911617 0.7598946 0.2867518 0.7604175 0.2558992 0.6941683 0.2939332 0.693419 0.2939339 0.6934571 0.2891463 0.7540518 0.2897421 0.7551426 0.2857455 0.7571071 0.2906549 0.7574529 0.2909666 0.7586578 0.2866062 0.7595624 0.2749966 0.7619097 0.2750113 0.7617368 0.2753767 0.7617936 0.2882384 0.7702778 0.287426 0.7711521 0.2843608 0.7683218 0.2775226 0.7611631 0.2776098 0.7613133 0.2772782 0.7614774 0.2901545 0.7671871 0.2896152 0.7682876 0.285759 0.76625 0.2837304 0.760611 0.2835778 0.7599003 0.2866062 0.7595624 0.2835778 0.7599003 0.2861006 0.7579016 0.2863889 0.7587215 0.2863889 0.7587215 0.2866062 0.7595624 0.2835778 0.7599003 0.2866062 0.7595624 0.2867518 0.7604175 0.2837304 0.760611 0.2867518 0.7604175 0.2868249 0.7612802 0.2838119 0.7613316 0.2868249 0.7612802 0.286825 0.7621439 0.2838216 0.7620546 0.286825 0.7621439 0.2867518 0.7630018 0.2838216 0.7620546 0.2838216 0.7620546 0.2867518 0.7630018 0.2837612 0.7627731 0.2867518 0.7630018 0.2866069 0.7638478 0.2837612 0.7627731 0.2866069 0.7638478 0.2836304 0.7634797 0.2837612 0.7627731 0.2867518 0.7604175 0.2838119 0.7613316 0.2837304 0.760611 0.2912442 0.7623832 0.2911301 0.7636198 0.2867518 0.7630018 0.2682889 0.749168 0.269371 0.7485293 0.2714726 0.7525211 0.2835778 0.7599003 0.2837304 0.760611 0.2786971 0.7614795 0.2789637 0.7757861 0.2778511 0.7759834 0.2774196 0.7719483 0.2754697 0.7629777 0.2753472 0.7628575 0.2756198 0.7626147 0.275032 0.7622531 0.2750035 0.7620826 0.27537 0.7620469 0.2779148 0.7690188 0.2772361 0.7691304 0.2766774 0.7642639 0.2777541 0.7619846 0.2777364 0.7621566 0.2773739 0.7620949 0.2815386 0.7671093 0.2810123 0.7675648 0.2778974 0.7637267 0.2772158 0.7630243 0.2770734 0.7631207 0.2768884 0.7628048 0.2751831 0.7612464 0.2752796 0.761101 0.2755752 0.7613275 0.270505 0.7479817 0.2716833 0.747529 0.2730935 0.7518337 0.2712953 0.7749782 0.2703317 0.7745539 0.2719776 0.7710191 0.2772361 0.7691304 0.2765502 0.7691782 0.2764533 0.7642824 0.272996 0.7551917 0.2736712 0.7548934 0.2754999 0.7597203 0.2657599 0.7716833 0.2649012 0.7708474 0.2681552 0.7680865 0.2743735 0.754664 0.2750959 0.7545062 0.2759431 0.7595871 0.2723544 0.7555558 0.272996 0.7551917 0.2752901 0.759818 0.2792276 0.76861 0.2785804 0.7688449 0.2771154 0.7641639 0.2628254 0.7678383 0.262337 0.7666989 0.2664894 0.7651605 0.2764085 0.7629439 0.2765346 0.7629322 0.2765908 0.7632939 0.2859246 0.7502809 0.2868462 0.7511213 0.2836986 0.7542991 0.2732105 0.7684787 0.2725973 0.7681599 0.2751637 0.7639513 0.2824581 0.7660529 0.2820222 0.7666042 0.2782135 0.7634045 0.2833563 0.7592061 0.2835778 0.7599003 0.2786436 0.7612571 0.2830035 0.7742604 0.2820615 0.7747304 0.2804922 0.7711328 0.2615105 0.7630626 0.2614446 0.761814 0.2658907 0.7617796 0.2663075 0.7506996 0.2672655 0.7498931 0.2699931 0.7534676 0.2767093 0.7760908 0.2755621 0.7760357 0.275817 0.7719888 0.2776972 0.7623248 0.2776373 0.7624868 0.2773017 0.7623367 0.264612 0.752533 0.2654212 0.7515816 0.2686949 0.7546449 0.2787466 0.7547736 0.2794342 0.755041 0.277321 0.7597506 0.2704947 0.7663442 0.2700825 0.7657697 0.2743654 0.7631677 0.3856131 0.800127 0.3782616 0.7458982 0.3920238 0.8000288 0.3782616 0.7458982 0.398952 0.7430933 0.3920238 0.8000288 0.398952 0.7430933 0.4092137 0.8187897 0.3920238 0.8000288 0.2697251 0.7651557 0.2694282 0.7645066 0.2741647 0.7627616 0.2614446 0.761814 0.2614825 0.7605615 0.2659233 0.760912 0.2765502 0.7691782 0.2758627 0.7691641 0.2762285 0.7642791 0.2865573 0.7719084 0.2856755 0.7725847 0.283196 0.7694607 0.270241 0.757578 0.2706905 0.7569971 0.2745733 0.760393 0.2831674 0.7648292 0.2828412 0.7654592 0.2784628 0.7630268 0.2706905 0.7569971 0.2711957 0.7564628 0.2747306 0.7602242 0.2728987 0.7471747 0.2741435 0.7469215 0.2748096 0.7514257 0.2812889 0.7562271 0.2818177 0.7567368 0.2780724 0.7602744 0.2889728 0.7693212 0.2882384 0.7702778 0.2848799 0.7676767 0.3630351 0.7482969 0.3703457 0.8032177 0.3467861 0.7629384 0.3703457 0.8032177 0.2993318 0.8126704 0.3467861 0.7629384 0.2800911 0.7553752 0.2807115 0.7557716 0.2777225 0.7599761 0.2714659 0.7673552 0.2709577 0.7668739 0.2746392 0.7635273 0.2758627 0.7691641 0.2751793 0.769086 0.2760051 0.7642548 0.2852745 0.7756404 0.2936534 0.770011 0.2993318 0.8126704 0.2622414 0.7568964 0.2626964 0.755736 0.2667756 0.7575502 0.2911617 0.7598946 0.2912544 0.7611389 0.2868249 0.7612802 0.2692666 0.7595394 0.2695258 0.7588557 0.2742096 0.7609779 0.2616807 0.7642992 0.2615105 0.7630626 0.2659316 0.7626451 0.290246 0.7562787 0.2906549 0.7574529 0.2863889 0.7587215 0.2755621 0.7760357 0.2767093 0.7760908 0.2681406 0.7760329 0.2594227 0.7708541 0.262337 0.7666989 0.2628254 0.7678383 0.2594227 0.7708541 0.2628254 0.7678383 0.2634205 0.768918 0.2744405 0.7758895 0.2755621 0.7760357 0.2681406 0.7760329 0.2733517 0.7756586 0.2744405 0.7758895 0.2681406 0.7760329 0.2681406 0.7760329 0.2594227 0.7708541 0.2657599 0.7716833 0.2594227 0.7708541 0.2634205 0.768918 0.2641166 0.7699241 0.2594227 0.7708541 0.2641166 0.7699241 0.2649012 0.7708474 0.272302 0.7753511 0.2733517 0.7756586 0.2681406 0.7760329 0.2712953 0.7749782 0.272302 0.7753511 0.2681406 0.7760329 0.2594227 0.7708541 0.2649012 0.7708474 0.2657599 0.7716833 0.2703317 0.7745539 0.2712953 0.7749782 0.2681406 0.7760329 0.2694036 0.7740886 0.2703317 0.7745539 0.2681406 0.7760329 0.2681406 0.7760329 0.2657599 0.7716833 0.2666662 0.7723912 0.2681406 0.7760329 0.2666662 0.7723912 0.2675807 0.7730188 0.2684929 0.7735803 0.2694036 0.7740886 0.2681406 0.7760329 0.2896152 0.7682876 0.2889728 0.7693212 0.2853481 0.7669852 0.262337 0.7666989 0.2619559 0.7655148 0.2662327 0.7643419 0.2736712 0.7548934 0.2743735 0.754664 0.2757181 0.759643 0.2838837 0.7488406 0.284935 0.7495188 0.2823501 0.7531844 0.277158 0.7607938 0.2772951 0.7609011 0.2770478 0.7611767 0.261883 0.758091 0.2622414 0.7568964 0.2664567 0.7583618 0.2820222 0.7666042 0.2815386 0.7671093 0.2780631 0.7635732 0.2774172 0.761025 0.2775226 0.7611631 0.2772144 0.7613676 0.2775576 0.7626399 0.2774597 0.7627819 0.2771699 0.7625534 0.2810123 0.7675648 0.2804482 0.7679679 0.2777183 0.7638636 0.2672655 0.7498931 0.2682889 0.749168 0.2707123 0.7529633 0.287426 0.7711521 0.2865573 0.7719084 0.2837973 0.7689168 0.2759131 0.7632336 0.2757549 0.7631672 0.2759186 0.7628407 0.2694036 0.7740886 0.2684929 0.7735803 0.2705855 0.7702478 0.2773452 0.7629107 0.2772158 0.7630243 0.2769926 0.7627335 0.2763328 0.7605545 0.2765079 0.760559 0.2764728 0.7609292 0.2634205 0.768918 0.2628254 0.7678383 0.2668139 0.76595 0.2711957 0.7564628 0.2717522 0.7559806 0.2749034 0.7600709 0.2776373 0.7624868 0.2775576 0.7626399 0.2772428 0.7624492 0.269371 0.7485293 0.270505 0.7479817 0.2722682 0.7521436 0.276248 0.7633057 0.2760783 0.7632802 0.2761562 0.7629222 0.27692 0.7631984 0.2767584 0.7632565 0.2766578 0.762905 0.2818177 0.7567368 0.2822929 0.7572955 0.2782241 0.7604471 0.2558992 0.6941683 0.2409573 0.6944627 0.2405185 0.6721856 0.2405185 0.6721856 0.3084363 0.6708478 0.2939332 0.693419 0.3084363 0.6708478 0.3088751 0.6931248 0.2939332 0.693419 0.2709577 0.7668739 0.2704947 0.7663442 0.2744938 0.7633542 0.2700825 0.7657697 0.2697251 0.7651557 0.2742553 0.7629697 0.2834317 0.7641673 0.2831674 0.7648292 0.2785595 0.7628216 0.2792054 0.7470543 0.2804312 0.7473547 0.2791833 0.7516951 0.2775272 0.7598538 0.2777225 0.7599761 0.277158 0.7607938 0.2777225 0.7599761 0.2779047 0.7601168 0.277158 0.7607938 0.277158 0.7607938 0.2779047 0.7601168 0.2772951 0.7609011 0.2779047 0.7601168 0.2780724 0.7602744 0.2772951 0.7609011 0.2780724 0.7602744 0.2782241 0.7604471 0.2774172 0.761025 0.2772951 0.7609011 0.2780724 0.7602744 0.2774172 0.761025 0.2782241 0.7604471 0.2775226 0.7611631 0.2774172 0.761025 0.2771058 0.7596678 0.277321 0.7597506 0.2768485 0.7606347 0.277321 0.7597506 0.2775272 0.7598538 0.2770085 0.7607043 0.2771058 0.7596678 0.2768485 0.7606347 0.2766808 0.760586 0.2766561 0.7595654 0.2768836 0.7596057 0.2766808 0.760586 0.2768836 0.7596057 0.2771058 0.7596678 0.2766808 0.760586 0.2766561 0.7595654 0.2766808 0.760586 0.2765079 0.760559 0.2762992 0.759545 0.2764259 0.7595467 0.2763328 0.7605545 0.2764259 0.7595467 0.2766561 0.7595654 0.2765079 0.760559 0.2763328 0.7605545 0.2764259 0.7595467 0.2765079 0.760559 0.2759431 0.7595871 0.2761723 0.7595527 0.2761583 0.7605713 0.2761723 0.7595527 0.2762992 0.759545 0.2763328 0.7605545 0.2761583 0.7605713 0.2761723 0.7595527 0.2763328 0.7605545 0.2754999 0.7597203 0.2757181 0.759643 0.2759874 0.7606104 0.2757181 0.759643 0.2759431 0.7595871 0.2759874 0.7606104 0.2754999 0.7597203 0.2759874 0.7606104 0.2758229 0.7606709 0.2750906 0.7599352 0.2752901 0.759818 0.2756675 0.7607519 0.2752901 0.759818 0.2754999 0.7597203 0.2758229 0.7606709 0.2747306 0.7602242 0.2749034 0.7600709 0.2755238 0.7608516 0.2749034 0.7600709 0.2750906 0.7599352 0.2755238 0.7608516 0.2755238 0.7608516 0.2750906 0.7599352 0.2756675 0.7607519 0.2744332 0.7605761 0.2745733 0.760393 0.2752796 0.761101 0.2745733 0.760393 0.2747306 0.7602242 0.2753937 0.7609687 0.2753937 0.7609687 0.2747306 0.7602242 0.2755238 0.7608516 0.2753937 0.7609687 0.2752796 0.761101 0.2745733 0.760393 0.2752901 0.759818 0.2758229 0.7606709 0.2756675 0.7607519 0.2759431 0.7595871 0.2761583 0.7605713 0.2759874 0.7606104 0.2775272 0.7598538 0.277158 0.7607938 0.2770085 0.7607043 0.2794342 0.755041 0.2800911 0.7553752 0.2775272 0.7598538 0.1914018 0.7517976 0.1858975 0.8053328 0.1721973 0.8039242 0.2816244 0.7477546 0.2827778 0.7482511 0.2808313 0.7523077 0.2753472 0.7628575 0.2752406 0.7627229 0.275542 0.762516 0.2798515 0.7683161 0.2792276 0.76861 0.2773255 0.7640833 0.2884622 0.7530133 0.2891463 0.7540518 0.2853249 0.7563444 0.2786918 0.762387 0.2786362 0.7626078 0.2776972 0.7623248 0.2786362 0.7626078 0.2785595 0.7628216 0.2776972 0.7623248 0.2776972 0.7623248 0.2785595 0.7628216 0.2776373 0.7624868 0.2785595 0.7628216 0.2784628 0.7630268 0.2776373 0.7624868 0.2784628 0.7630268 0.2783471 0.7632217 0.2775576 0.7626399 0.2775576 0.7626399 0.2783471 0.7632217 0.2774597 0.7627819 0.2783471 0.7632217 0.2782135 0.7634045 0.2774597 0.7627819 0.2782135 0.7634045 0.2780631 0.7635732 0.2774597 0.7627819 0.2774597 0.7627819 0.2780631 0.7635732 0.2773452 0.7629107 0.2780631 0.7635732 0.2778974 0.7637267 0.2773452 0.7629107 0.2778974 0.7637267 0.2777183 0.7638636 0.2772158 0.7630243 0.2777183 0.7638636 0.277527 0.7639828 0.2770734 0.7631207 0.277527 0.7639828 0.2773255 0.7640833 0.27692 0.7631984 0.2777183 0.7638636 0.2770734 0.7631207 0.2772158 0.7630243 0.2773255 0.7640833 0.2771154 0.7641639 0.27692 0.7631984 0.2771154 0.7641639 0.2768987 0.7642242 0.2767584 0.7632565 0.2768987 0.7642242 0.2766774 0.7642639 0.2765908 0.7632939 0.2766774 0.7642639 0.2764533 0.7642824 0.2764197 0.7633102 0.2768987 0.7642242 0.2765908 0.7632939 0.2767584 0.7632565 0.2764533 0.7642824 0.2762285 0.7642791 0.2764197 0.7633102 0.2762285 0.7642791 0.2760051 0.7642548 0.276248 0.7633057 0.2764197 0.7633102 0.2762285 0.7642791 0.276248 0.7633057 0.2760051 0.7642548 0.275785 0.7642094 0.2760783 0.7632802 0.275785 0.7642094 0.27557 0.7641434 0.2759131 0.7632336 0.2759131 0.7632336 0.27557 0.7641434 0.2753623 0.7640569 0.2753623 0.7640569 0.2751637 0.7639513 0.2757549 0.7631672 0.2757549 0.7631672 0.2751637 0.7639513 0.2756063 0.7630815 0.2751637 0.7639513 0.2749758 0.763827 0.2756063 0.7630815 0.2749758 0.763827 0.2748004 0.7636853 0.2754697 0.7629777 0.2754697 0.7629777 0.2748004 0.7636853 0.2753472 0.7628575 0.2748004 0.7636853 0.2746392 0.7635273 0.2753472 0.7628575 0.2746392 0.7635273 0.2744938 0.7633542 0.2753472 0.7628575 0.2753472 0.7628575 0.2744938 0.7633542 0.2752406 0.7627229 0.2744938 0.7633542 0.2743654 0.7631677 0.2752406 0.7627229 0.2743654 0.7631677 0.2742553 0.7629697 0.2751516 0.7625757 0.2752406 0.7627229 0.2743654 0.7631677 0.2751516 0.7625757 0.2742553 0.7629697 0.2741647 0.7627616 0.2750818 0.7624182 0.2741647 0.7627616 0.2740945 0.7625453 0.2750818 0.7624182 0.2742553 0.7629697 0.2750818 0.7624182 0.2751516 0.7625757 0.2740945 0.7625453 0.2740454 0.7623229 0.275032 0.7622531 0.2740454 0.7623229 0.2740179 0.7620964 0.2750035 0.7620826 0.2740945 0.7625453 0.275032 0.7622531 0.2750818 0.7624182 0.2740179 0.7620964 0.2740122 0.761868 0.2749966 0.7619097 0.2740122 0.761868 0.274029 0.7616397 0.2749966 0.7619097 0.2740179 0.7620964 0.2749966 0.7619097 0.2750035 0.7620826 0.274029 0.7616397 0.2740678 0.7614139 0.2750113 0.7617368 0.2740678 0.7614139 0.2741281 0.7611926 0.2750477 0.7615668 0.2750477 0.7615668 0.2741281 0.7611926 0.2751052 0.7614025 0.2741281 0.7611926 0.2742096 0.7609779 0.2751052 0.7614025 0.2742096 0.7609779 0.2743114 0.7607717 0.2751831 0.7612464 0.2743114 0.7607717 0.2744332 0.7605761 0.2751831 0.7612464 0.2744332 0.7605761 0.2752796 0.761101 0.2751831 0.7612464 0.2742096 0.7609779 0.2751831 0.7612464 0.2751052 0.7614025 0.2778974 0.7637267 0.2772158 0.7630243 0.2773452 0.7629107 0.2787386 0.7619341 0.2787261 0.7621617 0.2777541 0.7619846 0.2787261 0.7621617 0.2786918 0.762387 0.2777364 0.7621566 0.2787386 0.7619341 0.2777541 0.7619846 0.2777501 0.7618116 0.2786971 0.7614795 0.278729 0.7617059 0.2777501 0.7618116 0.278729 0.7617059 0.2787386 0.7619341 0.2777501 0.7618116 0.2786971 0.7614795 0.2777501 0.7618116 0.2777245 0.7616401 0.2785688 0.7610405 0.2786436 0.7612571 0.2776775 0.7614732 0.2786436 0.7612571 0.2786971 0.7614795 0.2777245 0.7616401 0.2783583 0.7606337 0.2784734 0.7608321 0.2775226 0.7611631 0.2784734 0.7608321 0.2785688 0.7610405 0.2776098 0.7613133 0.2776098 0.7613133 0.2785688 0.7610405 0.2776775 0.7614732 0.2775226 0.7611631 0.2782241 0.7604471 0.2783583 0.7606337 0.2776098 0.7613133 0.2775226 0.7611631 0.2784734 0.7608321 0.2786436 0.7612571 0.2777245 0.7616401 0.2776775 0.7614732 0.2770734 0.7631207 0.277527 0.7639828 0.27692 0.7631984 0.275032 0.7622531 0.2740454 0.7623229 0.2750035 0.7620826 0.2740678 0.7614139 0.2750477 0.7615668 0.2750113 0.7617368 0.2777541 0.7619846 0.2787261 0.7621617 0.2777364 0.7621566 0.274029 0.7616397 0.2750113 0.7617368 0.2749966 0.7619097 0.2776972 0.7623248 0.2777364 0.7621566 0.2786918 0.762387 0.2775576 0.7626399 0.2776373 0.7624868 0.2784628 0.7630268 0.2749758 0.763827 0.2754697 0.7629777 0.2756063 0.7630815 0.2753623 0.7640569 0.2757549 0.7631672 0.2759131 0.7632336 0.27692 0.7631984 0.2771154 0.7641639 0.2767584 0.7632565 0.275785 0.7642094 0.2759131 0.7632336 0.2760783 0.7632802 0.2765908 0.7632939 0.2766774 0.7642639 0.2764197 0.7633102 0.2632455 0.7546171 0.2638853 0.7535471 0.2676124 0.7560185 0.2820615 0.7747304 0.2810737 0.7751497 0.2797521 0.7714221 0.3090177 0.926997 0.3088071 0.9424869 0.240869 0.9415627 0.2758229 0.7606709 0.2759874 0.7606104 0.2760927 0.7609678 0.2750035 0.7620826 0.2749966 0.7619097 0.2753658 0.7619203 0.2690307 0.7631278 0.2689355 0.7624117 0.2740179 0.7620964 0.2776775 0.7614732 0.2777245 0.7616401 0.2773631 0.761717 0.2909113 0.7648399 0.2905865 0.7660331 0.2863917 0.7646754 0.2641166 0.7699241 0.2634205 0.768918 0.2672027 0.7667048 0.2594227 0.7708541 0.2681406 0.7760329 0.2657138 0.8135393 0.2756063 0.7630815 0.2754697 0.7629777 0.2757095 0.7627024 0.2689576 0.7609627 0.2690766 0.7602443 0.2740678 0.7614139 0.2649012 0.7708474 0.2641166 0.7699241 0.2676516 0.7674193 0.2838216 0.7620546 0.2837612 0.7627731 0.2787261 0.7621617 0.2744405 0.7758895 0.2733517 0.7756586 0.2742335 0.7717748 0.2666662 0.7723912 0.2657599 0.7716833 0.2687069 0.7687048 0.2770734 0.7631207 0.27692 0.7631984 0.2767763 0.7628623 0.2777364 0.7621566 0.2776972 0.7623248 0.2773455 0.7622181 0.2750818 0.7624182 0.275032 0.7622531 0.2753902 0.7621718 0.2675807 0.7730188 0.2666662 0.7723912 0.2693001 0.7692711 0.2777501 0.7618116 0.2777541 0.7619846 0.2773864 0.761969 0.2750113 0.7617368 0.2750477 0.7615668 0.2754038 0.7616692 0.2765079 0.760559 0.2766808 0.760586 0.2765989 0.7609483 0.2703317 0.7745539 0.2694036 0.7740886 0.2712693 0.7706589 0.2720142 0.7677846 0.2714659 0.7673552 0.2748004 0.7636853 0.2752796 0.761101 0.2753937 0.7609687 0.2756587 0.7612305 0.2689355 0.7624117 0.2689105 0.7616877 0.2740122 0.761868 0.2760783 0.7632802 0.2759131 0.7632336 0.2760346 0.762889 0.2616235 0.7593126 0.261883 0.758091 0.2662072 0.7591968 0.2753937 0.7609687 0.2755238 0.7608516 0.2757538 0.7611448 0.2766875 0.7467613 0.277955 0.7468559 0.2774522 0.7513651 0.2839077 0.7737493 0.2830035 0.7742604 0.2812088 0.7707914 0.2756675 0.7607519 0.2758229 0.7606709 0.2759727 0.7610123 0.2838119 0.7613316 0.2838216 0.7620546 0.2787386 0.7619341 0.2619559 0.7655148 0.2616807 0.7642992 0.2660462 0.7635013 0.2716833 0.747529 0.2728987 0.7471747 0.2739426 0.7515938 0.2619559 0.7655148 0.262337 0.7666989 0.2594227 0.7708541 0.2852745 0.7756404 0.2767093 0.7760908 0.2778511 0.7759834 0.2852745 0.7756404 0.2778511 0.7759834 0.2789637 0.7757861 0.2616807 0.7642992 0.2619559 0.7655148 0.2594227 0.7708541 0.2615105 0.7630626 0.2616807 0.7642992 0.2594227 0.7708541 0.2852745 0.7756404 0.2789637 0.7757861 0.2800399 0.7755053 0.2852745 0.7756404 0.2800399 0.7755053 0.2810737 0.7751497 0.2615105 0.7630626 0.2594227 0.7708541 0.2614446 0.761814 0.2594227 0.7708541 0.2563543 0.7172648 0.2616235 0.7593126 0.2614446 0.761814 0.2594227 0.7708541 0.2614825 0.7605615 0.2614825 0.7605615 0.2594227 0.7708541 0.2616235 0.7593126 0.2852745 0.7756404 0.2810737 0.7751497 0.2820615 0.7747304 0.2852745 0.7756404 0.2820615 0.7747304 0.2830035 0.7742604 0.2936534 0.770011 0.2852745 0.7756404 0.287426 0.7711521 0.2852745 0.7756404 0.2830035 0.7742604 0.2839077 0.7737493 0.2852745 0.7756404 0.2839077 0.7737493 0.2847921 0.773194 0.261883 0.758091 0.2616235 0.7593126 0.2563543 0.7172648 0.2622414 0.7568964 0.261883 0.758091 0.2563543 0.7172648 0.2852745 0.7756404 0.2847921 0.773194 0.2856755 0.7725847 0.2852745 0.7756404 0.2856755 0.7725847 0.2865573 0.7719084 0.2626964 0.755736 0.2622414 0.7568964 0.2563543 0.7172648 0.2632455 0.7546171 0.2626964 0.755736 0.2563543 0.7172648 0.2852745 0.7756404 0.2865573 0.7719084 0.287426 0.7711521 0.2638853 0.7535471 0.2632455 0.7546171 0.2563543 0.7172648 0.264612 0.752533 0.2638853 0.7535471 0.2563543 0.7172648 0.2936534 0.770011 0.287426 0.7711521 0.2882384 0.7702778 0.2936534 0.770011 0.2882384 0.7702778 0.2889728 0.7693212 0.264612 0.752533 0.2563543 0.7172648 0.2654212 0.7515816 0.2563543 0.7172648 0.2943882 0.7165156 0.2754104 0.7467718 0.2654212 0.7515816 0.2563543 0.7172648 0.2663075 0.7506996 0.2663075 0.7506996 0.2563543 0.7172648 0.2672655 0.7498931 0.2936534 0.770011 0.2889728 0.7693212 0.2896152 0.7682876 0.2936534 0.770011 0.2896152 0.7682876 0.2901545 0.7671871 0.2672655 0.7498931 0.2563543 0.7172648 0.2682889 0.749168 0.2682889 0.749168 0.2563543 0.7172648 0.269371 0.7485293 0.2936534 0.770011 0.2901545 0.7671871 0.2905865 0.7660331 0.2936534 0.770011 0.2905865 0.7660331 0.2909113 0.7648399 0.269371 0.7485293 0.2563543 0.7172648 0.270505 0.7479817 0.270505 0.7479817 0.2563543 0.7172648 0.2716833 0.747529 0.2936534 0.770011 0.2909113 0.7648399 0.2911301 0.7636198 0.2936534 0.770011 0.2911301 0.7636198 0.2912442 0.7623832 0.2716833 0.747529 0.2563543 0.7172648 0.2728987 0.7471747 0.2728987 0.7471747 0.2563543 0.7172648 0.2741435 0.7469215 0.2943882 0.7165156 0.2936534 0.770011 0.2909666 0.7586578 0.2936534 0.770011 0.2912442 0.7623832 0.2912544 0.7611389 0.2936534 0.770011 0.2912544 0.7611389 0.2911617 0.7598946 0.2741435 0.7469215 0.2563543 0.7172648 0.2754104 0.7467718 0.2936534 0.770011 0.2911617 0.7598946 0.2909666 0.7586578 0.2766875 0.7467613 0.2754104 0.7467718 0.2943882 0.7165156 0.2943882 0.7165156 0.2909666 0.7586578 0.2906549 0.7574529 0.2943882 0.7165156 0.2906549 0.7574529 0.290246 0.7562787 0.277955 0.7468559 0.2766875 0.7467613 0.2943882 0.7165156 0.2792054 0.7470543 0.277955 0.7468559 0.2943882 0.7165156 0.2943882 0.7165156 0.290246 0.7562787 0.2897421 0.7551426 0.2943882 0.7165156 0.2897421 0.7551426 0.2891463 0.7540518 0.2804312 0.7473547 0.2792054 0.7470543 0.2943882 0.7165156 0.2816244 0.7477546 0.2804312 0.7473547 0.2943882 0.7165156 0.2943882 0.7165156 0.2891463 0.7540518 0.2884622 0.7530133 0.2943882 0.7165156 0.2884622 0.7530133 0.2876939 0.7520342 0.2827778 0.7482511 0.2816244 0.7477546 0.2943882 0.7165156 0.2838837 0.7488406 0.2827778 0.7482511 0.2943882 0.7165156 0.2943882 0.7165156 0.2876939 0.7520342 0.2868462 0.7511213 0.2943882 0.7165156 0.2868462 0.7511213 0.2859246 0.7502809 0.284935 0.7495188 0.2838837 0.7488406 0.2943882 0.7165156 0.2785804 0.7688449 0.2779148 0.7690188 0.2768987 0.7642242 0.2800399 0.7755053 0.2789637 0.7757861 0.2782119 0.7718325 0.2768485 0.7606347 0.2770085 0.7607043 0.2768381 0.7610337 0.2837304 0.760611 0.2838119 0.7613316 0.278729 0.7617059 0.2759874 0.7606104 0.2761583 0.7605713 0.2762175 0.7609389 0.273848 0.7687419 0.2732105 0.7684787 0.2753623 0.7640569 0.2754104 0.7467718 0.2766875 0.7467613 0.2765708 0.7513099 0.2761583 0.7605713 0.2763328 0.7605545 0.2763451 0.7609262 0.2827778 0.7482511 0.2838837 0.7488406 0.2816099 0.7527141 0.2770478 0.7611767 0.2771372 0.7612668 0.2772144 0.7613676 0.2772144 0.7613676 0.2772782 0.7614774 0.2770478 0.7611767 0.2772782 0.7614774 0.2773276 0.7615949 0.2770478 0.7611767 0.2773276 0.7615949 0.2773631 0.761717 0.2773828 0.7618425 0.2773828 0.7618425 0.2773864 0.761969 0.2773739 0.7620949 0.2773739 0.7620949 0.2773455 0.7622181 0.2773017 0.7623367 0.2773017 0.7623367 0.2772428 0.7624492 0.2771699 0.7625534 0.2771699 0.7625534 0.2770868 0.7626494 0.2769926 0.7627335 0.2769926 0.7627335 0.2768884 0.7628048 0.2771699 0.7625534 0.2768884 0.7628048 0.2767763 0.7628623 0.2771699 0.7625534 0.2767763 0.7628623 0.2766578 0.762905 0.2765346 0.7629322 0.2765346 0.7629322 0.2764085 0.7629439 0.2762815 0.7629395 0.2762815 0.7629395 0.2761562 0.7629222 0.2760346 0.762889 0.2760346 0.762889 0.2759186 0.7628407 0.2762815 0.7629395 0.2759186 0.7628407 0.2758095 0.7627782 0.2762815 0.7629395 0.2758095 0.7627782 0.2757095 0.7627024 0.2756198 0.7626147 0.2756198 0.7626147 0.275542 0.762516 0.2758095 0.7627782 0.275542 0.762516 0.2754775 0.7624081 0.2758095 0.7627782 0.2754775 0.7624081 0.2754263 0.7622928 0.2753658 0.7619203 0.2754263 0.7622928 0.2753902 0.7621718 0.2753658 0.7619203 0.2753902 0.7621718 0.27537 0.7620469 0.2753658 0.7619203 0.2753658 0.7619203 0.2753767 0.7617936 0.2754038 0.7616692 0.2754038 0.7616692 0.2754466 0.7615489 0.2755047 0.7614347 0.2755047 0.7614347 0.2755752 0.7613275 0.2758592 0.7610719 0.2755752 0.7613275 0.2756587 0.7612305 0.2758592 0.7610719 0.2756587 0.7612305 0.2757538 0.7611448 0.2758592 0.7610719 0.2758592 0.7610719 0.2759727 0.7610123 0.2760927 0.7609678 0.2760927 0.7609678 0.2762175 0.7609389 0.2758592 0.7610719 0.2762175 0.7609389 0.2763451 0.7609262 0.2758592 0.7610719 0.2763451 0.7609262 0.2764728 0.7609292 0.2768381 0.7610337 0.2764728 0.7609292 0.2765989 0.7609483 0.2768381 0.7610337 0.2765989 0.7609483 0.2767212 0.7609833 0.2768381 0.7610337 0.2768381 0.7610337 0.2769475 0.7610984 0.2770478 0.7611767 0.2773276 0.7615949 0.2773828 0.7618425 0.2771699 0.7625534 0.2773828 0.7618425 0.2773739 0.7620949 0.2771699 0.7625534 0.2773739 0.7620949 0.2773017 0.7623367 0.2771699 0.7625534 0.2767763 0.7628623 0.2765346 0.7629322 0.2771699 0.7625534 0.2765346 0.7629322 0.2762815 0.7629395 0.2771699 0.7625534 0.2753658 0.7619203 0.2754038 0.7616692 0.2755047 0.7614347 0.2768381 0.7610337 0.2770478 0.7611767 0.2763451 0.7609262 0.2770478 0.7611767 0.2773276 0.7615949 0.2763451 0.7609262 0.2762815 0.7629395 0.2758095 0.7627782 0.2754775 0.7624081 0.2754775 0.7624081 0.2753658 0.7619203 0.2762815 0.7629395 0.2753658 0.7619203 0.2755047 0.7614347 0.2762815 0.7629395 0.2755047 0.7614347 0.2758592 0.7610719 0.2773276 0.7615949 0.2758592 0.7610719 0.2763451 0.7609262 0.2773276 0.7615949 0.2773276 0.7615949 0.2771699 0.7625534 0.2755047 0.7614347 0.2837973 0.7689168 0.283196 0.7694607 0.2815386 0.7671093 0.283196 0.7694607 0.282562 0.7699541 0.2810123 0.7675648 0.282562 0.7699541 0.2818989 0.7703975 0.2804482 0.7679679 0.2818989 0.7703975 0.2812088 0.7707914 0.2798515 0.7683161 0.282562 0.7699541 0.2804482 0.7679679 0.2810123 0.7675648 0.2812088 0.7707914 0.2804922 0.7711328 0.2798515 0.7683161 0.2804922 0.7711328 0.2797521 0.7714221 0.2792276 0.76861 0.2798515 0.7683161 0.2804922 0.7711328 0.2792276 0.76861 0.2797521 0.7714221 0.2789908 0.7716562 0.2785804 0.7688449 0.2789908 0.7716562 0.2782119 0.7718325 0.2779148 0.7690188 0.2797521 0.7714221 0.2785804 0.7688449 0.2792276 0.76861 0.2782119 0.7718325 0.2774196 0.7719483 0.2772361 0.7691304 0.2774196 0.7719483 0.2766191 0.7720015 0.2765502 0.7691782 0.2782119 0.7718325 0.2772361 0.7691304 0.2779148 0.7690188 0.2766191 0.7720015 0.275817 0.7719888 0.2765502 0.7691782 0.275817 0.7719888 0.27502 0.7719126 0.2758627 0.7691641 0.2758627 0.7691641 0.27502 0.7719126 0.2751793 0.769086 0.27502 0.7719126 0.2742335 0.7717748 0.2751793 0.769086 0.2742335 0.7717748 0.2734621 0.7715781 0.2745059 0.7689449 0.2745059 0.7689449 0.2734621 0.7715781 0.273848 0.7687419 0.2734621 0.7715781 0.2727093 0.7713254 0.273848 0.7687419 0.2727093 0.7713254 0.2719776 0.7710191 0.2732105 0.7684787 0.2719776 0.7710191 0.2712693 0.7706589 0.2732105 0.7684787 0.2712693 0.7706589 0.2705855 0.7702478 0.2725973 0.7681599 0.2705855 0.7702478 0.2699279 0.7697854 0.2720142 0.7677846 0.2699279 0.7697854 0.2693001 0.7692711 0.2714659 0.7673552 0.2720142 0.7677846 0.2699279 0.7697854 0.2714659 0.7673552 0.2693001 0.7692711 0.2687069 0.7687048 0.2709577 0.7668739 0.2687069 0.7687048 0.2681552 0.7680865 0.2704947 0.7663442 0.2693001 0.7692711 0.2709577 0.7668739 0.2714659 0.7673552 0.2681552 0.7680865 0.2676516 0.7674193 0.2700825 0.7657697 0.2676516 0.7674193 0.2672027 0.7667048 0.2700825 0.7657697 0.2681552 0.7680865 0.2700825 0.7657697 0.2704947 0.7663442 0.2672027 0.7667048 0.2668139 0.76595 0.2697251 0.7651557 0.2668139 0.76595 0.2664894 0.7651605 0.2694282 0.7645066 0.2697251 0.7651557 0.2668139 0.76595 0.2694282 0.7645066 0.2664894 0.7651605 0.2662327 0.7643419 0.2691957 0.7638285 0.2662327 0.7643419 0.2660462 0.7635013 0.2690307 0.7631278 0.2660462 0.7635013 0.2659316 0.7626451 0.2689355 0.7624117 0.2659316 0.7626451 0.2658907 0.7617796 0.2689355 0.7624117 0.2689355 0.7624117 0.2658907 0.7617796 0.2689105 0.7616877 0.2658907 0.7617796 0.2659233 0.760912 0.2689105 0.7616877 0.2659233 0.760912 0.2660289 0.7600488 0.2689576 0.7609627 0.2689576 0.7609627 0.2660289 0.7600488 0.2690766 0.7602443 0.2660289 0.7600488 0.2662072 0.7591968 0.2690766 0.7602443 0.2662072 0.7591968 0.2664567 0.7583618 0.2692666 0.7595394 0.2664567 0.7583618 0.2667756 0.7575502 0.2695258 0.7588557 0.2667756 0.7575502 0.2671613 0.7567671 0.2698519 0.7581998 0.2695258 0.7588557 0.2667756 0.7575502 0.2698519 0.7581998 0.2671613 0.7567671 0.2676124 0.7560185 0.2698519 0.7581998 0.2676124 0.7560185 0.2681247 0.7553095 0.270241 0.757578 0.2698519 0.7581998 0.2676124 0.7560185 0.270241 0.757578 0.2681247 0.7553095 0.2686949 0.7546449 0.2706905 0.7569971 0.2686949 0.7546449 0.2693191 0.7540295 0.2711957 0.7564628 0.2681247 0.7553095 0.2706905 0.7569971 0.270241 0.757578 0.2693191 0.7540295 0.2699931 0.7534676 0.2717522 0.7559806 0.2699931 0.7534676 0.2707123 0.7529633 0.2723544 0.7555558 0.2693191 0.7540295 0.2717522 0.7559806 0.2711957 0.7564628 0.2707123 0.7529633 0.2714726 0.7525211 0.2723544 0.7555558 0.2714726 0.7525211 0.2722682 0.7521436 0.272996 0.7551917 0.272996 0.7551917 0.2722682 0.7521436 0.2736712 0.7548934 0.2722682 0.7521436 0.2730935 0.7518337 0.2736712 0.7548934 0.2730935 0.7518337 0.2739426 0.7515938 0.2743735 0.754664 0.2743735 0.754664 0.2739426 0.7515938 0.2750959 0.7545062 0.2739426 0.7515938 0.2748096 0.7514257 0.2750959 0.7545062 0.2748096 0.7514257 0.2756878 0.7513307 0.2758301 0.7544226 0.2756878 0.7513307 0.2765708 0.7513099 0.2765684 0.7543987 0.2765708 0.7513099 0.2774522 0.7513651 0.2765684 0.7543987 0.2765684 0.7543987 0.2774522 0.7513651 0.2773066 0.7544504 0.2774522 0.7513651 0.2783252 0.7514938 0.2773066 0.7544504 0.2783252 0.7514938 0.2791833 0.7516951 0.2780351 0.754576 0.2773066 0.7544504 0.2783252 0.7514938 0.2780351 0.754576 0.2791833 0.7516951 0.2800206 0.7519671 0.2787466 0.7547736 0.2800206 0.7519671 0.2808313 0.7523077 0.2794342 0.755041 0.2791833 0.7516951 0.2787466 0.7547736 0.2780351 0.754576 0.2808313 0.7523077 0.2816099 0.7527141 0.2800911 0.7553752 0.2816099 0.7527141 0.2823501 0.7531844 0.2800911 0.7553752 0.2808313 0.7523077 0.2800911 0.7553752 0.2794342 0.755041 0.2823501 0.7531844 0.283048 0.753714 0.2807115 0.7557716 0.283048 0.753714 0.2836986 0.7542991 0.2812889 0.7562271 0.2807115 0.7557716 0.283048 0.753714 0.2812889 0.7562271 0.2836986 0.7542991 0.2842975 0.7549355 0.2818177 0.7567368 0.2842975 0.7549355 0.2848408 0.755619 0.2822929 0.7572955 0.2848408 0.755619 0.2853249 0.7563444 0.2827098 0.7578976 0.2853249 0.7563444 0.2857455 0.7571071 0.2827098 0.7578976 0.2827098 0.7578976 0.2857455 0.7571071 0.2830656 0.7585365 0.2857455 0.7571071 0.2861006 0.7579016 0.2830656 0.7585365 0.2861006 0.7579016 0.2835778 0.7599003 0.2833563 0.7592061 0.2861006 0.7579016 0.2833563 0.7592061 0.2830656 0.7585365 0.2842975 0.7549355 0.2822929 0.7572955 0.2818177 0.7567368 0.2748096 0.7514257 0.2758301 0.7544226 0.2750959 0.7545062 0.2662072 0.7591968 0.2692666 0.7595394 0.2690766 0.7602443 0.2692666 0.7595394 0.2664567 0.7583618 0.2695258 0.7588557 0.2662327 0.7643419 0.2690307 0.7631278 0.2691957 0.7638285 0.2705855 0.7702478 0.2720142 0.7677846 0.2725973 0.7681599 0.2727093 0.7713254 0.2732105 0.7684787 0.273848 0.7687419 0.2712693 0.7706589 0.2725973 0.7681599 0.2732105 0.7684787 0.2843608 0.7683218 0.2837973 0.7689168 0.2820222 0.7666042 0.283196 0.7694607 0.2810123 0.7675648 0.2815386 0.7671093 0.2853481 0.7669852 0.2848799 0.7676767 0.2828412 0.7654592 0.2848799 0.7676767 0.2843608 0.7683218 0.2824581 0.7660529 0.2824581 0.7660529 0.2843608 0.7683218 0.2820222 0.7666042 0.2861081 0.7654781 0.285759 0.76625 0.2831674 0.7648292 0.285759 0.76625 0.2853481 0.7669852 0.2828412 0.7654592 0.2831674 0.7648292 0.285759 0.76625 0.2828412 0.7654592 0.2866069 0.7638478 0.2863917 0.7646754 0.2836304 0.7634797 0.2863917 0.7646754 0.2861081 0.7654781 0.2834317 0.7641673 0.2834317 0.7641673 0.2861081 0.7654781 0.2831674 0.7648292 0.2834317 0.7641673 0.2836304 0.7634797 0.2863917 0.7646754 0.2804482 0.7679679 0.2818989 0.7703975 0.2798515 0.7683161 0.2785804 0.7688449 0.2789908 0.7716562 0.2779148 0.7690188 0.2742335 0.7717748 0.2745059 0.7689449 0.2751793 0.769086 0.2706905 0.7569971 0.2686949 0.7546449 0.2711957 0.7564628 0.2730935 0.7518337 0.2743735 0.754664 0.2736712 0.7548934 0.2756878 0.7513307 0.2765684 0.7543987 0.2758301 0.7544226 0.2837973 0.7689168 0.2815386 0.7671093 0.2820222 0.7666042 0.2848408 0.755619 0.2827098 0.7578976 0.2822929 0.7572955 0.2824581 0.7660529 0.2828412 0.7654592 0.2848799 0.7676767 0.2836986 0.7542991 0.2818177 0.7567368 0.2812889 0.7562271 0.2807115 0.7557716 0.2800911 0.7553752 0.2823501 0.7531844 0.2794342 0.755041 0.2787466 0.7547736 0.2800206 0.7519671 0.2772361 0.7691304 0.2774196 0.7719483 0.2765502 0.7691782 0.2758627 0.7691641 0.2765502 0.7691782 0.275817 0.7719888 0.2714726 0.7525211 0.272996 0.7551917 0.2723544 0.7555558 0.2723544 0.7555558 0.2717522 0.7559806 0.2699931 0.7534676 0.2709577 0.7668739 0.2687069 0.7687048 0.2704947 0.7663442 0.2700825 0.7657697 0.2672027 0.7667048 0.2697251 0.7651557 0.2659233 0.760912 0.2689576 0.7609627 0.2689105 0.7616877 0.2691957 0.7638285 0.2694282 0.7645066 0.2664894 0.7651605 0.2765684 0.7543987 0.2773066 0.7544504 0.2766561 0.7595654 0.2751052 0.7614025 0.2751831 0.7612464 0.2755047 0.7614347 0.2804312 0.7473547 0.2816244 0.7477546 0.2800206 0.7519671 0.1858975 0.8053328 0.1914018 0.7517976 0.2076111 0.7655269 0.2076111 0.7655269 0.2594227 0.7708541 0.2551456 0.8124527 0.2943882 0.7165156 0.2563543 0.7172648 0.2559 0.6942063 0.08432489 0.8420109 0.07841497 0.8362203 0.1320422 0.8356735 0.07841497 0.8362203 0.07772582 0.7686499 0.1320422 0.8356735 0.07772582 0.7686499 0.131353 0.768103 0.1320422 0.8356735 0.1305715 0.6914646 0.131353 0.768103 0.07772582 0.7686499 0.2020955 0.8408099 0.2028772 0.917448 0.1353068 0.9181372 0.1345251 0.8414989 0.1353068 0.9181372 0.1270332 0.9182216 0.1262516 0.8415833 0.1270332 0.9182216 0.08510655 0.9186492 0.08432489 0.8420109 0.08510655 0.9186492 0.076833 0.9187335 0.07605141 0.8420953 0.076833 0.9187335 0.009262621 0.9194228 0.1329432 0.9240122 0.1336323 0.9915825 0.08000504 0.9921296 0.08000504 0.9921296 0.07931596 0.924559 0.1329432 0.9240122 0.07931596 0.924559 0.08510655 0.9186492 0.1329432 0.9240122 - - - - - - - - - - - - - - -

195 0 0 260 0 1 261 0 2 72 1 3 107 1 4 108 1 5 198 2 6 257 2 7 258 2 8 319 3 9 384 3 10 385 3 11 0 4 12 24 4 13 6 4 14 233 5 15 300 5 16 301 5 17 28 6 18 26 6 19 27 6 20 231 7 21 302 7 22 303 7 23 216 8 24 273 8 25 274 8 26 50 9 27 119 9 28 120 9 29 210 10 30 290 10 31 291 10 32 78 11 33 123 11 34 124 11 35 213 12 36 276 12 37 277 12 38 193 13 39 310 13 40 311 13 41 238 14 42 305 14 43 306 14 44 76 15 45 111 15 46 112 15 47 87 16 48 132 16 49 133 16 50 18 17 51 16 17 52 17 17 53 221 18 54 285 18 55 286 18 56 182 19 57 266 19 58 267 19 59 358 20 60 411 20 61 412 20 62 207 21 63 293 21 64 294 21 65 190 22 66 248 22 67 249 22 68 356 23 69 403 23 70 404 23 71 24 17 72 21 17 73 22 17 74 194 24 75 309 24 76 310 24 77 31 25 78 121 25 79 122 25 80 89 26 81 134 26 82 135 26 83 347 27 84 396 27 85 397 27 86 83 28 87 128 28 88 129 28 89 67 29 90 177 29 91 178 29 92 346 30 93 391 30 94 392 30 95 197 31 96 258 31 97 259 31 98 54 32 99 155 32 100 156 32 101 186 33 102 262 33 103 263 33 104 335 34 105 375 34 106 376 34 107 66 35 108 176 35 109 177 35 110 321 36 111 382 36 112 383 36 113 327 37 114 407 37 115 408 37 116 62 38 117 172 38 118 173 38 119 36 39 120 159 39 121 160 39 122 240 40 123 253 40 124 254 40 125 232 41 126 301 41 127 302 41 128 341 42 129 363 42 130 364 42 131 228 43 132 294 43 133 295 43 134 69 44 135 179 44 136 180 44 137 333 45 138 377 45 139 378 45 140 181 46 141 29 46 142 18 46 143 323 47 144 380 47 145 381 47 146 5 48 147 4 48 148 22 48 149 96 49 150 151 49 151 152 49 152 206 50 153 277 50 154 278 50 155 90 51 156 140 51 157 141 51 158 361 52 159 402 52 160 403 52 161 343 53 162 368 53 163 369 53 164 93 54 165 143 54 166 144 54 167 103 55 168 153 55 169 154 55 170 183 56 171 265 56 172 266 56 173 77 57 174 112 57 175 113 57 176 3 17 177 0 17 178 1 17 179 86 58 180 131 58 181 132 58 182 80 59 183 125 59 184 126 59 185 7 6 186 11 6 187 15 6 188 84 60 189 129 60 190 130 60 191 81 61 192 126 61 193 127 61 194 352 62 195 398 62 196 399 62 197 46 63 198 115 63 199 116 63 200 360 64 201 378 64 202 379 64 203 49 65 204 118 65 205 119 65 206 227 66 207 226 66 208 124 66 209 32 67 210 122 67 211 123 67 212 100 68 213 148 68 214 149 68 215 224 69 216 298 69 217 299 69 218 70 70 219 105 70 220 106 70 221 354 71 222 405 71 223 406 71 224 350 72 225 400 72 226 401 72 227 202 73 228 281 73 229 282 73 230 329 74 231 373 74 232 374 74 233 219 75 234 287 75 235 288 75 236 338 76 237 366 76 238 367 76 239 349 77 240 394 77 241 395 77 242 98 78 243 146 78 244 147 78 245 65 79 246 175 79 247 176 79 248 203 80 249 280 80 250 281 80 251 242 81 252 251 81 253 252 81 254 41 82 255 169 82 256 170 82 257 189 83 258 249 83 259 250 83 260 241 84 261 252 84 262 253 84 263 223 85 264 283 85 265 284 85 266 58 86 267 165 86 268 166 86 269 412 87 270 357 87 271 358 87 272 88 88 273 133 88 274 134 88 275 215 89 276 274 89 277 275 89 278 211 90 279 289 90 280 290 90 281 234 91 282 299 91 283 300 91 284 74 92 285 109 92 286 110 92 287 38 93 288 161 93 289 162 93 290 102 94 291 150 94 292 151 94 293 18 95 294 180 95 295 181 95 296 331 96 297 371 96 298 372 96 299 97 97 300 152 97 301 153 97 302 235 98 303 308 98 304 309 98 305 244 99 306 269 99 307 270 99 308 28 100 309 23 100 310 24 100 311 246 101 312 267 101 313 268 101 314 35 102 315 160 102 316 161 102 317 204 103 318 279 103 319 280 103 320 44 104 321 113 104 322 114 104 323 199 105 324 256 105 325 257 105 326 209 106 327 291 106 328 292 106 329 247 107 330 248 107 331 191 107 332 200 108 333 255 108 334 256 108 335 94 109 336 144 109 337 145 109 338 229 110 339 304 110 340 305 110 341 47 111 342 116 111 343 117 111 344 8 100 345 9 100 346 10 100 347 237 112 348 306 112 349 307 112 350 218 113 351 271 113 352 272 113 353 205 114 354 278 114 355 279 114 356 16 115 357 8 115 358 17 115 359 55 116 360 156 116 361 157 116 362 79 117 363 124 117 364 125 117 365 196 118 366 259 118 367 260 118 368 39 119 369 162 119 370 163 119 371 82 120 372 127 120 373 128 120 374 20 121 375 43 121 376 62 121 377 48 122 378 117 122 379 118 122 380 57 123 381 164 123 382 165 123 383 188 124 384 250 124 385 251 124 386 51 125 387 135 125 388 136 125 389 322 126 390 381 126 391 382 126 392 56 127 393 157 127 394 158 127 395 212 128 396 288 128 397 289 128 398 359 129 399 379 129 400 380 129 401 342 130 402 369 130 403 370 130 404 220 131 405 286 131 406 287 131 407 101 132 408 149 132 409 150 132 410 45 133 411 114 133 412 115 133 413 326 134 414 408 134 415 409 134 416 63 135 417 173 135 418 174 135 419 337 136 420 367 136 421 368 136 422 313 137 423 386 137 424 387 137 425 59 138 426 166 138 427 167 138 428 239 139 429 254 139 430 255 139 431 332 140 432 370 140 433 371 140 434 192 141 435 312 141 436 247 141 437 192 142 438 247 142 439 191 142 440 99 143 441 147 143 442 148 143 443 324 144 444 410 144 445 411 144 446 340 145 447 364 145 448 365 145 449 230 146 450 303 146 451 304 146 452 1 121 453 7 121 454 26 121 455 243 147 456 270 147 457 271 147 458 245 148 459 268 148 460 269 148 461 208 149 462 292 149 463 293 149 464 34 150 465 139 150 466 140 150 467 321 121 468 320 121 469 308 121 470 236 151 471 307 151 472 308 151 473 7 17 474 4 17 475 5 17 476 53 152 477 137 152 478 138 152 479 355 153 480 404 153 481 405 153 482 222 154 483 284 154 484 285 154 485 85 155 486 130 155 487 131 155 488 278 156 489 325 156 490 324 156 491 104 157 492 154 157 493 155 157 494 73 158 495 108 158 496 109 158 497 23 159 498 27 159 499 21 159 500 316 160 501 389 160 502 390 160 503 351 161 504 399 161 505 400 161 506 184 162 507 264 162 508 265 162 509 334 163 510 376 163 511 377 163 512 30 164 513 120 164 514 121 164 515 60 165 516 167 165 517 168 165 518 12 166 519 19 166 520 13 166 521 328 167 522 406 167 523 407 167 524 187 168 525 261 168 526 262 168 527 61 169 528 168 169 529 169 169 530 227 170 531 295 170 532 296 170 533 68 171 534 178 171 535 179 171 536 42 172 537 170 172 538 171 172 539 339 173 540 365 173 541 366 173 542 330 174 543 372 174 544 373 174 545 362 175 546 401 175 547 402 175 548 43 176 549 171 176 550 172 176 551 336 100 552 374 100 553 375 100 554 353 177 555 397 177 556 398 177 557 318 178 558 385 178 559 386 178 560 64 179 561 174 179 562 175 179 563 217 180 564 272 180 565 273 180 566 344 181 567 393 181 568 394 181 569 185 182 570 263 182 571 264 182 572 325 183 573 409 183 574 410 183 575 37 184 576 158 184 577 159 184 578 345 185 579 392 185 580 393 185 581 91 186 582 141 186 583 142 186 584 75 187 585 110 187 586 111 187 587 315 188 588 390 188 589 391 188 590 226 189 591 296 189 592 297 189 593 40 190 594 163 190 595 164 190 596 95 191 597 145 191 598 146 191 599 10 192 600 88 192 601 89 192 602 201 193 603 282 193 604 283 193 605 71 194 606 106 194 607 107 194 608 320 195 609 383 195 610 384 195 611 225 196 612 297 196 613 298 196 614 317 197 615 388 197 616 389 197 617 214 198 618 275 198 619 276 198 620 92 6 621 142 6 622 143 6 623 314 199 624 387 199 625 388 199 626 52 200 627 136 200 628 137 200 629 369 121 630 411 121 631 395 121 632 185 201 633 184 201 634 163 201 635 192 202 636 311 202 637 312 202 638 348 203 639 395 203 640 396 203 641 33 204 642 138 204 643 139 204 644 14 161 645 13 161 646 6 161 647 10 205 648 15 205 649 11 205 650 416 121 651 418 121 652 420 121 653 415 6 654 414 6 655 424 6 656 413 100 657 417 100 658 416 100 659 416 206 660 419 206 661 418 206 662 418 17 663 421 17 664 420 17 665 420 207 666 423 207 667 422 207 668 422 161 669 424 161 670 414 161 671 421 159 672 419 159 673 417 159 674 195 208 675 196 208 676 260 208 677 72 209 678 71 209 679 107 209 680 198 210 681 199 210 682 257 210 683 319 211 684 320 211 685 384 211 686 0 212 687 2 212 688 24 212 689 24 4 690 22 4 691 6 4 692 22 213 693 4 213 694 6 213 695 6 159 696 13 159 697 8 159 698 13 159 699 19 159 700 17 159 701 17 159 702 8 159 703 13 159 704 8 159 705 0 159 706 6 159 707 233 214 708 234 214 709 300 214 710 28 6 711 25 6 712 26 6 713 231 215 714 232 215 715 302 215 716 216 216 717 217 216 718 273 216 719 50 217 720 49 217 721 119 217 722 210 218 723 211 218 724 290 218 725 78 219 726 32 219 727 123 219 728 213 12 729 214 12 730 276 12 731 193 220 732 194 220 733 310 220 734 238 221 735 229 221 736 305 221 737 76 222 738 75 222 739 111 222 740 87 223 741 86 223 742 132 223 743 17 17 744 19 17 745 18 17 746 19 17 747 20 17 748 18 17 749 221 224 750 222 224 751 285 224 752 182 225 753 183 225 754 266 225 755 358 226 756 324 226 757 411 226 758 207 227 759 208 227 760 293 227 761 190 228 762 191 228 763 248 228 764 356 229 765 361 229 766 403 229 767 24 17 768 23 17 769 21 17 770 194 230 771 235 230 772 309 230 773 31 231 774 30 231 775 121 231 776 89 26 777 88 26 778 134 26 779 347 232 780 348 232 781 396 232 782 83 233 783 82 233 784 128 233 785 67 234 786 66 234 787 177 234 788 346 235 789 315 235 790 391 235 791 197 236 792 198 236 793 258 236 794 54 237 795 104 237 796 155 237 797 186 238 798 187 238 799 262 238 800 335 34 801 336 34 802 375 34 803 66 35 804 65 35 805 176 35 806 321 239 807 322 239 808 382 239 809 327 240 810 328 240 811 407 240 812 62 241 813 43 241 814 172 241 815 36 242 816 37 242 817 159 242 818 240 243 819 241 243 820 253 243 821 232 244 822 233 244 823 301 244 824 341 245 825 357 245 826 363 245 827 228 246 828 207 246 829 294 246 830 69 247 831 68 247 832 179 247 833 333 248 834 334 248 835 377 248 836 181 249 837 105 249 838 29 249 839 323 250 840 359 250 841 380 250 842 22 161 843 21 161 844 27 161 845 27 161 846 26 161 847 22 161 848 26 161 849 5 161 850 22 161 851 96 251 852 102 251 853 151 251 854 206 252 855 213 252 856 277 252 857 90 253 858 34 253 859 140 253 860 361 254 861 362 254 862 402 254 863 343 255 864 337 255 865 368 255 866 93 256 867 92 256 868 143 256 869 103 257 870 97 257 871 153 257 872 183 258 873 184 258 874 265 258 875 77 259 876 76 259 877 112 259 878 3 17 879 2 17 880 0 17 881 86 260 882 85 260 883 131 260 884 80 261 885 79 261 886 125 261 887 7 6 888 1 6 889 11 6 890 84 262 891 83 262 892 129 262 893 81 263 894 80 263 895 126 263 896 352 264 897 353 264 898 398 264 899 46 265 900 45 265 901 115 265 902 360 266 903 333 266 904 378 266 905 49 267 906 48 267 907 118 267 908 225 268 909 224 268 910 126 268 911 224 121 912 128 121 913 127 121 914 127 269 915 126 269 916 224 269 917 126 270 918 125 270 919 225 270 920 125 271 921 124 271 922 226 271 923 124 272 924 123 272 925 227 272 926 123 121 927 122 121 928 227 121 929 227 273 930 122 273 931 228 273 932 122 121 933 121 121 934 228 121 935 121 121 936 207 121 937 228 121 938 125 274 939 226 274 940 225 274 941 32 275 942 31 275 943 122 275 944 100 276 945 99 276 946 148 276 947 224 277 948 225 277 949 298 277 950 70 278 951 29 278 952 105 278 953 354 279 954 355 279 955 405 279 956 350 280 957 351 280 958 400 280 959 202 281 960 203 281 961 281 281 962 329 74 963 330 74 964 373 74 965 219 282 966 220 282 967 287 282 968 338 283 969 339 283 970 366 283 971 349 284 972 344 284 973 394 284 974 98 285 975 95 285 976 146 285 977 65 286 978 64 286 979 175 286 980 203 287 981 204 287 982 280 287 983 242 288 984 188 288 985 251 288 986 41 289 987 61 289 988 169 289 989 189 290 990 190 290 991 249 290 992 241 291 993 242 291 994 252 291 995 223 85 996 201 85 997 283 85 998 58 292 999 57 292 1000 165 292 1001 412 293 1002 363 293 1003 357 293 1004 88 294 1005 87 294 1006 133 294 1007 215 295 1008 216 295 1009 274 295 1010 211 90 1011 212 90 1012 289 90 1013 234 296 1014 224 296 1015 299 296 1016 74 297 1017 73 297 1018 109 297 1019 38 298 1020 35 298 1021 161 298 1022 102 299 1023 101 299 1024 150 299 1025 18 300 1026 69 300 1027 180 300 1028 331 301 1029 332 301 1030 371 301 1031 97 302 1032 96 302 1033 152 302 1034 235 303 1035 236 303 1036 308 303 1037 244 304 1038 245 304 1039 269 304 1040 2 100 1041 3 100 1042 24 100 1043 3 100 1044 25 100 1045 24 100 1046 25 305 1047 28 305 1048 24 305 1049 246 306 1050 182 306 1051 267 306 1052 35 307 1053 36 307 1054 160 307 1055 204 308 1056 205 308 1057 279 308 1058 44 309 1059 77 309 1060 113 309 1061 199 310 1062 200 310 1063 256 310 1064 209 311 1065 210 311 1066 291 311 1067 200 312 1068 239 312 1069 255 312 1070 94 313 1071 93 313 1072 144 313 1073 229 110 1074 230 110 1075 304 110 1076 47 314 1077 46 314 1078 116 314 1079 11 100 1080 0 100 1081 10 100 1082 0 100 1083 8 100 1084 10 100 1085 237 315 1086 238 315 1087 306 315 1088 218 316 1089 243 316 1090 271 316 1091 205 317 1092 206 317 1093 278 317 1094 16 318 1095 9 318 1096 8 318 1097 55 319 1098 54 319 1099 156 319 1100 79 320 1101 78 320 1102 124 320 1103 196 321 1104 197 321 1105 259 321 1106 39 322 1107 38 322 1108 162 322 1109 82 323 1110 81 323 1111 127 323 1112 69 121 1113 18 121 1114 20 121 1115 12 324 1116 57 324 1117 58 324 1118 12 121 1119 58 121 1120 59 121 1121 68 325 1122 69 325 1123 20 325 1124 67 326 1125 68 326 1126 20 326 1127 20 327 1128 12 327 1129 41 327 1130 12 328 1131 59 328 1132 60 328 1133 12 121 1134 60 121 1135 61 121 1136 66 329 1137 67 329 1138 20 329 1139 65 330 1140 66 330 1141 20 330 1142 12 121 1143 61 121 1144 41 121 1145 64 121 1146 65 121 1147 20 121 1148 63 121 1149 64 121 1150 20 121 1151 20 331 1152 41 331 1153 42 331 1154 20 332 1155 42 332 1156 43 332 1157 62 121 1158 63 121 1159 20 121 1160 48 333 1161 47 333 1162 117 333 1163 57 334 1164 40 334 1165 164 334 1166 188 335 1167 189 335 1168 250 335 1169 51 336 1170 89 336 1171 135 336 1172 322 126 1173 323 126 1174 381 126 1175 56 337 1176 55 337 1177 157 337 1178 212 338 1179 219 338 1180 288 338 1181 359 339 1182 360 339 1183 379 339 1184 342 340 1185 343 340 1186 369 340 1187 220 341 1188 221 341 1189 286 341 1190 101 342 1191 100 342 1192 149 342 1193 45 133 1194 44 133 1195 114 133 1196 326 343 1197 327 343 1198 408 343 1199 63 344 1200 62 344 1201 173 344 1202 337 136 1203 338 136 1204 367 136 1205 313 345 1206 318 345 1207 386 345 1208 59 346 1209 58 346 1210 166 346 1211 239 347 1212 240 347 1213 254 347 1214 332 348 1215 342 348 1216 370 348 1217 99 349 1218 98 349 1219 147 349 1220 324 350 1221 325 350 1222 410 350 1223 340 351 1224 341 351 1225 364 351 1226 230 352 1227 231 352 1228 303 352 1229 7 121 1230 5 121 1231 26 121 1232 26 121 1233 25 121 1234 1 121 1235 25 121 1236 3 121 1237 1 121 1238 243 353 1239 244 353 1240 270 353 1241 245 354 1242 246 354 1243 268 354 1244 208 355 1245 209 355 1246 292 355 1247 34 356 1248 33 356 1249 139 356 1250 307 121 1251 306 121 1252 322 121 1253 306 121 1254 305 121 1255 322 121 1256 322 121 1257 305 121 1258 323 121 1259 305 121 1260 304 121 1261 323 121 1262 304 121 1263 303 121 1264 359 121 1265 323 121 1266 304 121 1267 359 121 1268 303 357 1269 360 357 1270 359 357 1271 309 121 1272 308 121 1273 320 121 1274 308 121 1275 307 121 1276 321 121 1277 309 121 1278 320 121 1279 319 121 1280 311 358 1281 310 358 1282 319 358 1283 310 359 1284 309 359 1285 319 359 1286 311 360 1287 319 360 1288 318 360 1289 247 121 1290 312 121 1291 313 121 1292 312 121 1293 311 121 1294 318 121 1295 313 121 1296 312 121 1297 318 121 1298 249 121 1299 248 121 1300 314 121 1301 248 121 1302 247 121 1303 313 121 1304 314 121 1305 248 121 1306 313 121 1307 251 361 1308 250 361 1309 317 361 1310 250 362 1311 249 362 1312 317 362 1313 251 121 1314 317 121 1315 316 121 1316 253 121 1317 252 121 1318 315 121 1319 252 363 1320 251 363 1321 316 363 1322 255 121 1323 254 121 1324 346 121 1325 254 121 1326 253 121 1327 346 121 1328 346 364 1329 253 364 1330 315 364 1331 257 121 1332 256 121 1333 344 121 1334 256 121 1335 255 121 1336 345 121 1337 345 121 1338 255 121 1339 346 121 1340 345 121 1341 344 121 1342 256 121 1343 252 365 1344 316 365 1345 315 365 1346 249 366 1347 314 366 1348 317 366 1349 307 367 1350 322 367 1351 321 367 1352 236 368 1353 237 368 1354 307 368 1355 7 17 1356 6 17 1357 4 17 1358 53 369 1359 52 369 1360 137 369 1361 355 370 1362 356 370 1363 404 370 1364 222 154 1365 223 154 1366 284 154 1367 85 371 1368 84 371 1369 130 371 1370 294 372 1371 293 372 1372 331 372 1373 293 373 1374 292 373 1375 331 373 1376 331 121 1377 292 121 1378 332 121 1379 292 121 1380 291 121 1381 332 121 1382 291 121 1383 290 121 1384 342 121 1385 342 121 1386 290 121 1387 343 121 1388 290 121 1389 289 121 1390 343 121 1391 289 121 1392 288 121 1393 343 121 1394 343 121 1395 288 121 1396 337 121 1397 288 121 1398 287 121 1399 337 121 1400 287 121 1401 286 121 1402 338 121 1403 286 374 1404 285 374 1405 339 374 1406 285 121 1407 284 121 1408 340 121 1409 286 375 1410 339 375 1411 338 375 1412 284 121 1413 283 121 1414 340 121 1415 283 121 1416 282 121 1417 341 121 1418 282 121 1419 281 121 1420 357 121 1421 281 121 1422 280 121 1423 358 121 1424 282 376 1425 357 376 1426 341 376 1427 280 121 1428 279 121 1429 358 121 1430 279 121 1431 278 121 1432 324 121 1433 358 121 1434 279 121 1435 324 121 1436 278 121 1437 277 121 1438 325 121 1439 277 121 1440 276 121 1441 326 121 1442 326 377 1443 276 377 1444 275 377 1445 275 378 1446 274 378 1447 327 378 1448 327 121 1449 274 121 1450 328 121 1451 274 121 1452 273 121 1453 328 121 1454 273 121 1455 272 121 1456 354 121 1457 354 121 1458 272 121 1459 355 121 1460 272 121 1461 271 121 1462 355 121 1463 271 121 1464 270 121 1465 355 121 1466 355 121 1467 270 121 1468 356 121 1469 270 121 1470 269 121 1471 356 121 1472 269 121 1473 268 121 1474 361 121 1475 356 121 1476 269 121 1477 361 121 1478 268 379 1479 267 379 1480 362 379 1481 267 380 1482 266 380 1483 362 380 1484 268 121 1485 362 121 1486 361 121 1487 266 121 1488 265 121 1489 350 121 1490 265 381 1491 264 381 1492 351 381 1493 266 121 1494 350 121 1495 362 121 1496 264 121 1497 263 121 1498 352 121 1499 263 121 1500 262 121 1501 352 121 1502 264 382 1503 352 382 1504 351 382 1505 262 383 1506 261 383 1507 353 383 1508 261 121 1509 260 121 1510 347 121 1511 347 384 1512 260 384 1513 348 384 1514 260 121 1515 259 121 1516 348 121 1517 259 121 1518 258 121 1519 349 121 1520 258 385 1521 257 385 1522 349 385 1523 257 386 1524 344 386 1525 349 386 1526 259 121 1527 349 121 1528 348 121 1529 287 387 1530 338 387 1531 337 387 1532 296 121 1533 295 121 1534 329 121 1535 295 121 1536 294 121 1537 330 121 1538 296 388 1539 329 388 1540 336 388 1541 298 389 1542 297 389 1543 336 389 1544 297 121 1545 296 121 1546 336 121 1547 298 390 1548 336 390 1549 335 390 1550 300 391 1551 299 391 1552 334 391 1553 299 392 1554 298 392 1555 335 392 1556 302 393 1557 301 393 1558 360 393 1559 301 121 1560 300 121 1561 333 121 1562 333 121 1563 300 121 1564 334 121 1565 360 394 1566 303 394 1567 302 394 1568 333 121 1569 360 121 1570 301 121 1571 299 395 1572 335 395 1573 334 395 1574 339 121 1575 285 121 1576 340 121 1577 350 121 1578 265 121 1579 351 121 1580 261 396 1581 347 396 1582 353 396 1583 329 121 1584 295 121 1585 330 121 1586 262 397 1587 353 397 1588 352 397 1589 331 121 1590 330 121 1591 294 121 1592 342 121 1593 332 121 1594 291 121 1595 273 398 1596 354 398 1597 328 398 1598 275 399 1599 327 399 1600 326 399 1601 340 121 1602 283 121 1603 341 121 1604 277 121 1605 326 121 1606 325 121 1607 357 121 1608 281 121 1609 358 121 1610 104 400 1611 103 400 1612 154 400 1613 73 401 1614 72 401 1615 108 401 1616 23 159 1617 28 159 1618 27 159 1619 316 402 1620 317 402 1621 389 402 1622 351 161 1623 352 161 1624 399 161 1625 184 403 1626 185 403 1627 264 403 1628 334 404 1629 335 404 1630 376 404 1631 30 405 1632 50 405 1633 120 405 1634 60 406 1635 59 406 1636 167 406 1637 12 407 1638 20 407 1639 19 407 1640 328 408 1641 354 408 1642 406 408 1643 187 409 1644 195 409 1645 261 409 1646 61 410 1647 60 410 1648 168 410 1649 227 411 1650 228 411 1651 295 411 1652 68 412 1653 67 412 1654 178 412 1655 42 413 1656 41 413 1657 170 413 1658 339 414 1659 340 414 1660 365 414 1661 330 415 1662 331 415 1663 372 415 1664 362 416 1665 350 416 1666 401 416 1667 43 417 1668 42 417 1669 171 417 1670 336 100 1671 329 100 1672 374 100 1673 353 418 1674 347 418 1675 397 418 1676 318 419 1677 319 419 1678 385 419 1679 64 420 1680 63 420 1681 174 420 1682 217 421 1683 218 421 1684 272 421 1685 344 422 1686 345 422 1687 393 422 1688 185 423 1689 186 423 1690 263 423 1691 325 424 1692 326 424 1693 409 424 1694 37 425 1695 56 425 1696 158 425 1697 345 426 1698 346 426 1699 392 426 1700 91 427 1701 90 427 1702 141 427 1703 75 428 1704 74 428 1705 110 428 1706 315 429 1707 316 429 1708 390 429 1709 226 430 1710 227 430 1711 296 430 1712 40 431 1713 39 431 1714 163 431 1715 95 432 1716 94 432 1717 145 432 1718 40 121 1719 57 121 1720 12 121 1721 16 121 1722 18 121 1723 29 121 1724 16 433 1725 29 433 1726 70 433 1727 39 121 1728 40 121 1729 12 121 1730 38 434 1731 39 434 1732 12 434 1733 16 435 1734 70 435 1735 71 435 1736 16 436 1737 71 436 1738 72 436 1739 38 121 1740 12 121 1741 35 121 1742 12 121 1743 14 121 1744 37 121 1745 35 437 1746 12 437 1747 36 437 1748 36 438 1749 12 438 1750 37 438 1751 16 439 1752 72 439 1753 73 439 1754 16 440 1755 73 440 1756 74 440 1757 9 441 1758 16 441 1759 45 441 1760 16 442 1761 74 442 1762 75 442 1763 16 121 1764 75 121 1765 76 121 1766 56 443 1767 37 443 1768 14 443 1769 55 121 1770 56 121 1771 14 121 1772 16 121 1773 76 121 1774 77 121 1775 16 444 1776 77 444 1777 44 444 1778 54 121 1779 55 121 1780 14 121 1781 104 121 1782 54 121 1783 14 121 1784 16 445 1785 44 445 1786 45 445 1787 103 121 1788 104 121 1789 14 121 1790 97 121 1791 103 121 1792 14 121 1793 9 121 1794 45 121 1795 46 121 1796 9 121 1797 46 121 1798 47 121 1799 97 121 1800 14 121 1801 96 121 1802 14 121 1803 10 121 1804 92 121 1805 96 121 1806 14 121 1807 102 121 1808 102 121 1809 14 121 1810 101 121 1811 9 446 1812 47 446 1813 48 446 1814 9 121 1815 48 121 1816 49 121 1817 101 121 1818 14 121 1819 100 121 1820 100 121 1821 14 121 1822 99 121 1823 9 447 1824 49 447 1825 50 447 1826 9 448 1827 50 448 1828 30 448 1829 99 121 1830 14 121 1831 98 121 1832 98 121 1833 14 121 1834 95 121 1835 9 449 1836 30 449 1837 31 449 1838 9 450 1839 31 450 1840 32 450 1841 95 121 1842 14 121 1843 94 121 1844 94 121 1845 14 121 1846 93 121 1847 10 121 1848 9 121 1849 80 121 1850 9 451 1851 32 451 1852 78 451 1853 9 452 1854 78 452 1855 79 452 1856 93 121 1857 14 121 1858 92 121 1859 9 453 1860 79 453 1861 80 453 1862 91 121 1863 92 121 1864 10 121 1865 10 454 1866 80 454 1867 81 454 1868 10 455 1869 81 455 1870 82 455 1871 90 121 1872 91 121 1873 10 121 1874 34 121 1875 90 121 1876 10 121 1877 10 456 1878 82 456 1879 83 456 1880 10 457 1881 83 457 1882 84 457 1883 33 121 1884 34 121 1885 10 121 1886 53 121 1887 33 121 1888 10 121 1889 10 458 1890 84 458 1891 85 458 1892 10 459 1893 85 459 1894 86 459 1895 52 121 1896 53 121 1897 10 121 1898 51 121 1899 52 121 1900 10 121 1901 10 460 1902 86 460 1903 87 460 1904 10 461 1905 87 461 1906 88 461 1907 89 121 1908 51 121 1909 10 121 1910 201 462 1911 202 462 1912 282 462 1913 71 463 1914 70 463 1915 106 463 1916 320 464 1917 321 464 1918 383 464 1919 225 465 1920 226 465 1921 297 465 1922 317 466 1923 314 466 1924 388 466 1925 214 467 1926 215 467 1927 275 467 1928 92 6 1929 91 6 1930 142 6 1931 314 468 1932 313 468 1933 387 468 1934 52 469 1935 51 469 1936 136 469 1937 381 470 1938 380 470 1939 379 470 1940 379 121 1941 378 121 1942 381 121 1943 378 121 1944 377 121 1945 381 121 1946 377 121 1947 376 121 1948 375 121 1949 375 471 1950 374 471 1951 373 471 1952 373 121 1953 372 121 1954 371 121 1955 371 121 1956 370 121 1957 369 121 1958 369 472 1959 368 472 1960 367 472 1961 367 121 1962 366 121 1963 369 121 1964 366 121 1965 365 121 1966 369 121 1967 365 473 1968 364 473 1969 363 473 1970 363 121 1971 412 121 1972 411 121 1973 411 121 1974 410 121 1975 409 121 1976 409 121 1977 408 121 1978 411 121 1979 408 121 1980 407 121 1981 411 121 1982 407 474 1983 406 474 1984 405 474 1985 405 121 1986 404 121 1987 407 121 1988 404 121 1989 403 121 1990 407 121 1991 403 475 1992 402 475 1993 399 475 1994 402 121 1995 401 121 1996 399 121 1997 401 476 1998 400 476 1999 399 476 2000 399 121 2001 398 121 2002 397 121 2003 397 477 2004 396 477 2005 395 477 2006 395 121 2007 394 121 2008 391 121 2009 394 478 2010 393 478 2011 391 478 2012 393 479 2013 392 479 2014 391 479 2015 391 480 2016 390 480 2017 389 480 2018 389 121 2019 388 121 2020 391 121 2021 388 121 2022 387 121 2023 391 121 2024 387 121 2025 386 121 2026 383 121 2027 386 481 2028 385 481 2029 383 481 2030 385 482 2031 384 482 2032 383 482 2033 383 483 2034 382 483 2035 381 483 2036 377 121 2037 375 121 2038 369 121 2039 375 484 2040 373 484 2041 369 484 2042 373 485 2043 371 485 2044 369 485 2045 365 121 2046 363 121 2047 369 121 2048 363 121 2049 411 121 2050 369 121 2051 399 486 2052 397 486 2053 395 486 2054 383 121 2055 381 121 2056 387 121 2057 381 121 2058 377 121 2059 387 121 2060 411 121 2061 407 121 2062 403 121 2063 403 121 2064 399 121 2065 411 121 2066 399 487 2067 395 487 2068 411 487 2069 395 488 2070 391 488 2071 377 488 2072 391 489 2073 387 489 2074 377 489 2075 377 121 2076 369 121 2077 395 121 2078 114 490 2079 113 490 2080 219 490 2081 113 491 2082 112 491 2083 220 491 2084 112 121 2085 111 121 2086 221 121 2087 111 121 2088 110 121 2089 222 121 2090 112 492 2091 221 492 2092 220 492 2093 110 493 2094 109 493 2095 222 493 2096 109 121 2097 108 121 2098 223 121 2099 222 494 2100 109 494 2101 223 494 2102 108 121 2103 107 121 2104 201 121 2105 107 121 2106 106 121 2107 202 121 2108 108 495 2109 201 495 2110 223 495 2111 106 121 2112 105 121 2113 203 121 2114 105 121 2115 181 121 2116 204 121 2117 106 496 2118 203 496 2119 202 496 2120 181 121 2121 180 121 2122 204 121 2123 180 121 2124 179 121 2125 205 121 2126 205 497 2127 179 497 2128 206 497 2129 179 121 2130 178 121 2131 206 121 2132 178 121 2133 177 121 2134 213 121 2135 213 121 2136 177 121 2137 214 121 2138 177 121 2139 176 121 2140 214 121 2141 176 498 2142 175 498 2143 215 498 2144 175 121 2145 174 121 2146 215 121 2147 174 121 2148 173 121 2149 216 121 2150 173 499 2151 172 499 2152 217 499 2153 172 500 2154 171 500 2155 218 500 2156 217 121 2157 172 121 2158 218 121 2159 171 121 2160 170 121 2161 243 121 2162 170 121 2163 169 121 2164 244 121 2165 171 501 2166 243 501 2167 218 501 2168 169 121 2169 168 121 2170 245 121 2171 168 121 2172 167 121 2173 245 121 2174 169 502 2175 245 502 2176 244 502 2177 167 503 2178 166 503 2179 246 503 2180 166 504 2181 165 504 2182 182 504 2183 246 121 2184 166 121 2185 182 121 2186 165 505 2187 164 505 2188 183 505 2189 164 506 2190 163 506 2191 184 506 2192 163 507 2193 162 507 2194 185 507 2195 162 121 2196 161 121 2197 185 121 2198 185 508 2199 161 508 2200 186 508 2201 161 121 2202 160 121 2203 186 121 2204 160 121 2205 159 121 2206 187 121 2207 187 509 2208 159 509 2209 195 509 2210 159 121 2211 158 121 2212 195 121 2213 158 121 2214 157 121 2215 196 121 2216 157 121 2217 156 121 2218 197 121 2219 156 510 2220 155 510 2221 198 510 2222 197 121 2223 156 121 2224 198 121 2225 155 121 2226 154 121 2227 198 121 2228 154 121 2229 153 121 2230 199 121 2231 198 511 2232 154 511 2233 199 511 2234 153 121 2235 152 121 2236 200 121 2237 152 121 2238 151 121 2239 239 121 2240 153 121 2241 200 121 2242 199 121 2243 151 121 2244 150 121 2245 240 121 2246 150 512 2247 149 512 2248 241 512 2249 151 513 2250 240 513 2251 239 513 2252 149 121 2253 148 121 2254 241 121 2255 148 121 2256 147 121 2257 242 121 2258 242 514 2259 147 514 2260 188 514 2261 147 121 2262 146 121 2263 188 121 2264 146 515 2265 145 515 2266 189 515 2267 189 121 2268 145 121 2269 190 121 2270 145 121 2271 144 121 2272 190 121 2273 144 121 2274 143 121 2275 191 121 2276 143 121 2277 142 121 2278 192 121 2279 142 121 2280 141 121 2281 192 121 2282 192 121 2283 141 121 2284 193 121 2285 141 121 2286 140 121 2287 193 121 2288 140 516 2289 139 516 2290 194 516 2291 193 121 2292 140 121 2293 194 121 2294 139 121 2295 138 121 2296 235 121 2297 138 121 2298 137 121 2299 236 121 2300 139 517 2301 235 517 2302 194 517 2303 137 121 2304 136 121 2305 237 121 2306 136 518 2307 135 518 2308 237 518 2309 137 519 2310 237 519 2311 236 519 2312 135 520 2313 134 520 2314 238 520 2315 134 121 2316 133 121 2317 229 121 2318 238 521 2319 134 521 2320 229 521 2321 133 121 2322 132 121 2323 230 121 2324 132 121 2325 131 121 2326 231 121 2327 131 522 2328 130 522 2329 232 522 2330 130 523 2331 129 523 2332 232 523 2333 232 121 2334 129 121 2335 233 121 2336 129 121 2337 128 121 2338 233 121 2339 128 524 2340 224 524 2341 234 524 2342 128 525 2343 234 525 2344 233 525 2345 132 121 2346 231 121 2347 230 121 2348 144 526 2349 191 526 2350 190 526 2351 158 527 2352 196 527 2353 195 527 2354 196 528 2355 157 528 2356 197 528 2357 164 121 2358 184 121 2359 183 121 2360 173 529 2361 217 529 2362 216 529 2363 176 530 2364 215 530 2365 214 530 2366 174 531 2367 216 531 2368 215 531 2369 115 121 2370 114 121 2371 212 121 2372 113 532 2373 220 532 2374 219 532 2375 117 121 2376 116 121 2377 210 121 2378 116 121 2379 115 121 2380 211 121 2381 211 121 2382 115 121 2383 212 121 2384 119 121 2385 118 121 2386 209 121 2387 118 121 2388 117 121 2389 210 121 2390 209 121 2391 118 121 2392 210 121 2393 121 121 2394 120 121 2395 207 121 2396 120 121 2397 119 121 2398 208 121 2399 208 121 2400 119 121 2401 209 121 2402 208 121 2403 207 121 2404 120 121 2405 221 121 2406 111 121 2407 222 121 2408 201 121 2409 107 121 2410 202 121 2411 178 533 2412 213 533 2413 206 533 2414 200 121 2415 152 121 2416 239 121 2417 146 534 2418 189 534 2419 188 534 2420 143 121 2421 192 121 2422 191 121 2423 114 535 2424 219 535 2425 212 535 2426 131 536 2427 232 536 2428 231 536 2429 211 121 2430 210 121 2431 116 121 2432 133 537 2433 230 537 2434 229 537 2435 238 121 2436 237 121 2437 135 121 2438 236 538 2439 235 538 2440 138 538 2441 203 121 2442 105 121 2443 204 121 2444 205 121 2445 204 121 2446 180 121 2447 148 539 2448 242 539 2449 241 539 2450 241 121 2451 240 121 2452 150 121 2453 243 121 2454 170 121 2455 244 121 2456 245 121 2457 167 121 2458 246 121 2459 160 540 2460 187 540 2461 186 540 2462 183 541 2463 182 541 2464 165 541 2465 192 542 2466 193 542 2467 311 542 2468 348 543 2469 349 543 2470 395 543 2471 33 544 2472 53 544 2473 138 544 2474 6 545 2475 7 545 2476 14 545 2477 14 161 2478 12 161 2479 13 161 2480 10 546 2481 14 546 2482 15 546 2483 420 121 2484 422 121 2485 416 121 2486 422 121 2487 414 121 2488 416 121 2489 414 121 2490 413 121 2491 416 121 2492 415 6 2493 413 6 2494 414 6 2495 413 100 2496 415 100 2497 417 100 2498 416 547 2499 417 547 2500 419 547 2501 418 17 2502 419 17 2503 421 17 2504 420 548 2505 421 548 2506 423 548 2507 422 161 2508 423 161 2509 424 161 2510 417 159 2511 415 159 2512 424 159 2513 424 159 2514 423 159 2515 417 159 2516 423 159 2517 421 159 2518 417 159 2519

-
-
-
- - - - -1.0006 -0.625 0.848 -1.0026 -0.627 0.848 0.7494004 -0.625 0.848 0.7514004 -0.627 0.848 0.7494004 0.571 0.848 0.7514004 0.573 0.848 -1.0006 0.571 0.848 -1.0026 0.573 0.848 0.4809127 0.571 0.65 -0.478337 0.571 0.65 0.4809127 -0.4363427 0.65 -0.478337 -0.4363427 0.65 -0.9986339 -0.625 0.7890107 -1.0006 0.571 0.7895358 -1.0006 -0.625 0.7895358 0.7494004 0.571 0.7892159 0.7490046 -0.625 0.7890107 0.7494004 -0.625 0.7892159 -0.4785996 0.573 0.648 0.4814004 0.573 0.648 -0.4785996 -0.437 0.648 0.4814004 -0.437 0.648 -1.0026 -0.627 0.788 -1.0026 0.573 0.788 0.7514004 0.573 0.788 0.7514004 -0.627 0.788 - - - - - - - - - - 1 0 0 0 0 1 0 1 0 0 -0.5931992 -0.8050557 0.2581218 0 0.9661125 0 0 -1 0 -1 -3.44038e-7 -0.2581218 0 -0.9661124 -0.4603177 0 0.8877543 0 1 6.79643e-7 0 0.5931991 0.8050559 -1 0 0 0 -1 0 0.4603176 0 -0.8877543 9.93424e-5 0 1 -6.75218e-5 0 1 0 -0.593199 -0.8050558 0.2581219 0 0.9661124 0.2580646 0 0.9661278 -0.2581216 0 -0.9661124 -0.460555 3.48392e-4 0.8876311 -0.4603171 0 0.8877547 0 1 -6.20882e-7 0 0.5931994 0.8050556 0.4603171 0 -0.8877546 - - - - - - - - - - 0.8926047 0.5104855 0.9866976 0.5082818 0.8885808 0.514334 0.8884316 0.5144841 0.8884316 0.3767313 0.8885808 0.514334 0.8885808 0.514334 0.8885575 0.3768587 0.8925521 0.5103086 0.9366801 0.2501449 0.9795874 0.02652591 0.9795874 0.3454102 0.9098128 0.4680974 0.9722396 0.4041125 0.9760082 0.4636778 0.9098128 0.4680974 0.9809626 0.5028479 0.8925521 0.5103086 0.9366801 0.07561308 0.7530581 0.2501449 0.7530581 0.07561308 0.9830301 0.3778303 0.9866976 0.5082818 0.9760082 0.4636778 0.7530581 0.3487517 0.9366801 0.2501449 0.9712229 0.3487517 0.986836 0.5084213 0.9830301 0.3778303 0.9831777 0.3776769 0.9773858 0.3818667 0.9722396 0.4041125 0.9099382 0.4045498 0.7166974 0.3454102 0.7166973 0.02652603 0.7530581 0.2501449 0.9712229 0.02031946 0.7530581 0.009411334 0.9712229 0.009411334 0.8935878 0.3817226 0.9098128 0.4680974 0.8925521 0.5103086 0.7530581 0.3487517 0.9712229 0.35966 0.7530581 0.35966 0.9773858 0.3818667 0.8885575 0.3768587 0.9830301 0.3778303 0.9795874 0.3454102 0.9904956 0.02652603 0.9904956 0.3454102 0.9366801 0.07561308 0.7530581 0.02031964 0.9712229 0.02031946 0.8926047 0.5104855 0.9809626 0.5028479 0.9866976 0.5082818 0.9866976 0.5082818 0.986836 0.5084213 0.8884316 0.5144841 0.8884316 0.3767313 0.9831777 0.3776769 0.9830301 0.3778303 0.8884316 0.3767313 0.9830301 0.3778303 0.8885575 0.3768587 0.8885808 0.514334 0.9866976 0.5082818 0.8884316 0.5144841 0.8884316 0.3767313 0.8885575 0.3768587 0.8885808 0.514334 0.8935918 0.3816773 0.8935878 0.3817226 0.8885575 0.3768587 0.8935878 0.3817226 0.8925521 0.5103086 0.8885575 0.3768587 0.8925521 0.5103086 0.8926047 0.5104855 0.8885808 0.514334 0.9366801 0.2501449 0.9366801 0.07561308 0.9795874 0.02652591 0.9098128 0.4680974 0.9099382 0.4045498 0.9722396 0.4041125 0.9760082 0.4636778 0.9809626 0.5028479 0.9098128 0.4680974 0.9809626 0.5028479 0.8926047 0.5104855 0.8925521 0.5103086 0.9366801 0.07561308 0.9366801 0.2501449 0.7530581 0.2501449 0.9866976 0.5082818 0.9809626 0.5028479 0.9760082 0.4636778 0.9760082 0.4636778 0.9722396 0.4041125 0.9830301 0.3778303 0.9722396 0.4041125 0.9773858 0.3818667 0.9830301 0.3778303 0.7530581 0.3487517 0.7530581 0.2501449 0.9366801 0.2501449 0.986836 0.5084213 0.9866976 0.5082818 0.9830301 0.3778303 0.9099382 0.4045498 0.8935878 0.3817226 0.8935918 0.3816773 0.8935918 0.3816773 0.9773858 0.3818667 0.9099382 0.4045498 0.7276057 0.02652603 0.7530581 0.07561308 0.7166973 0.02652603 0.7530581 0.07561308 0.7530581 0.2501449 0.7166973 0.02652603 0.7530581 0.2501449 0.7276057 0.3454102 0.7166974 0.3454102 0.9712229 0.02031946 0.7530581 0.02031964 0.7530581 0.009411334 0.8935878 0.3817226 0.9099382 0.4045498 0.9098128 0.4680974 0.7530581 0.3487517 0.9712229 0.3487517 0.9712229 0.35966 0.9773858 0.3818667 0.8935918 0.3816773 0.8885575 0.3768587 0.9795874 0.3454102 0.9795874 0.02652591 0.9904956 0.02652603 0.9366801 0.07561308 0.7530581 0.07561308 0.7530581 0.02031964 - - - - - - - - - - - - - - -

14 0 0 6 0 1 0 0 2 1 1 3 3 1 4 0 1 5 0 2 6 2 2 7 12 2 8 20 3 9 25 3 10 22 3 11 11 1 12 8 1 13 9 1 14 11 4 15 13 4 16 12 4 17 21 5 18 18 5 19 19 5 20 4 6 21 6 6 22 9 6 23 23 7 24 20 7 25 22 7 26 7 1 27 4 1 28 5 1 29 15 8 30 8 8 31 10 8 32 7 9 33 5 9 34 18 9 35 25 0 36 5 0 37 3 0 38 16 10 39 11 10 40 12 10 41 23 11 42 1 11 43 7 11 44 15 11 45 2 11 46 4 11 47 22 12 48 3 12 49 1 12 50 21 13 51 24 13 52 25 13 53 14 0 54 13 0 55 6 0 56 6 14 57 7 14 58 1 14 59 3 15 60 5 15 61 4 15 62 3 1 63 4 1 64 2 1 65 0 1 66 6 1 67 1 1 68 3 1 69 2 1 70 0 1 71 17 2 72 16 2 73 2 2 74 16 2 75 12 2 76 2 2 77 12 2 78 14 2 79 0 2 80 20 16 81 21 16 82 25 16 83 11 1 84 10 1 85 8 1 86 9 17 87 13 17 88 11 17 89 13 18 90 14 18 91 12 18 92 21 5 93 20 5 94 18 5 95 6 12 96 13 12 97 9 12 98 9 12 99 8 12 100 4 12 101 8 12 102 15 12 103 4 12 104 23 19 105 18 19 106 20 19 107 7 1 108 6 1 109 4 1 110 10 20 111 16 20 112 17 20 113 17 21 114 15 21 115 10 21 116 24 2 117 19 2 118 5 2 119 19 22 120 18 22 121 5 22 122 18 2 123 23 2 124 7 2 125 25 0 126 24 0 127 5 0 128 16 23 129 10 23 130 11 23 131 23 11 132 22 11 133 1 11 134 15 11 135 17 11 136 2 11 137 22 12 138 25 12 139 3 12 140 21 24 141 19 24 142 24 24 143

-
-
-
-
- - - - 1 0 0 0 0 1 0 0 0 0 1 2.33032 0 0 0 1 - - - - 0.2904861 0 0 0.4187222 0 -0.1005713 0 0.5237197 0 0 0.3967793 1.382459 0 0 0 1 - - - - - - - - - - - - 1 0 0 0 0 1 0 0.07315612 0 0 1 0 0 0 0 1 - - - - - - - - - - - - - - - 1 2.60602e-16 0 0.4732436 2.60602e-16 -0.1736481 0.9848078 -0.5151314 0 -0.9848078 -0.1736481 1.162193 0 0 0 1 - - - - - - - - - - - - - - - 1 0 0 0 0 1 0 0.07315612 0 0 1 0 0 0 0 1 - - - - - - - - - - - - 0.01815199 0 0 -0.5576562 0 0.03807207 -0.004948339 -0.5286319 0 -0.006713133 -0.02806343 1.327112 0 0 0 1 - - - - - - - - - - - - - - - -0.01815199 0 0 0.3926873 0 0.03807207 -0.004948339 -0.5286319 0 -0.006713133 -0.02806343 1.327112 0 0 0 1 - - - - - - - - - - - - - - - 1 0 0 0 0 1 0 0.07315612 0 0 1 0.9202835 0 0 0 1 - - - - - - - - - - - - 1 0 0 0 0 1 0 0.07315612 0 0 1 0.842444 0 0 0 1 - - - - - - - - - - - - 1.022986 0 0 0 0 1 0 0.3721467 0 0 1 1.750615 0 0 0 1 - - - - - - - - - - - - 1 0 0 0 0 1 0 0.07315612 0 0 1 0 0 0 0 1 - - - - - - - - - - - - - - - -
\ No newline at end of file diff --git a/src/picknik_ur_mock_hw_config/meshes/cnc.png b/src/picknik_ur_mock_hw_config/meshes/cnc.png deleted file mode 100644 index 942f675f..00000000 Binary files a/src/picknik_ur_mock_hw_config/meshes/cnc.png and /dev/null differ diff --git a/src/picknik_ur_mock_hw_config/meshes/cylinder-item.dae b/src/picknik_ur_mock_hw_config/meshes/cylinder-item.dae deleted file mode 100644 index 015c3569..00000000 --- a/src/picknik_ur_mock_hw_config/meshes/cylinder-item.dae +++ /dev/null @@ -1,166 +0,0 @@ - - - - - Blender User - Blender 3.6.1 commit date:2023-07-17, commit time:12:50, hash:8bda729ef4dc - - 2023-07-21T21:32:59 - 2023-07-21T21:32:59 - - Z_UP - - - - - - 0 0 0 - 1 - 0 - 0.001599967 - - - - - 0 - 0 - 1 - 1 - 1 - 1 - 1 - 0 - 0 - 0 - 0 - 25 - 45 - 0.15 - 0 - 1 - 2 - 0.04999995 - 40 - 1 - 512 - 3 - 1 - 0 - 0 - 0.25 - 0.25 - 0.25 - - - - - - - - - - cylinder-item - - - - - cylinder-item-surface - - - - - - 0 0 0 1 - - - - - - 1 - - - 1.45 - - - - - - - - - cylinder-item.png - - - - - - - - - - - - 0 0.2 -0.25 0 0.2 0.25 0.01960343 0.1990369 -0.25 0.01960343 0.1990369 0.25 0.03901803 0.196157 -0.25 0.03901803 0.196157 0.25 0.05805689 0.191388 -0.25 0.05805689 0.191388 0.25 0.07653665 0.1847759 -0.25 0.07653665 0.1847759 0.25 0.09427934 0.1763842 -0.25 0.09427934 0.1763842 0.25 0.111114 0.1662939 -0.25 0.111114 0.1662939 0.25 0.1268786 0.1546021 -0.25 0.1268786 0.1546021 0.25 0.1414213 0.1414213 -0.25 0.1414213 0.1414213 0.25 0.1546021 0.1268786 -0.25 0.1546021 0.1268786 0.25 0.1662939 0.111114 -0.25 0.1662939 0.111114 0.25 0.1763842 0.09427934 -0.25 0.1763842 0.09427934 0.25 0.1847759 0.07653665 -0.25 0.1847759 0.07653665 0.25 0.191388 0.05805689 -0.25 0.191388 0.05805689 0.25 0.196157 0.03901803 -0.25 0.196157 0.03901803 0.25 0.1990369 0.01960343 -0.25 0.1990369 0.01960343 0.25 0.2 0 -0.25 0.2 0 0.25 0.1990369 -0.01960343 -0.25 0.1990369 -0.01960343 0.25 0.196157 -0.03901803 -0.25 0.196157 -0.03901803 0.25 0.191388 -0.05805689 -0.25 0.191388 -0.05805689 0.25 0.1847759 -0.07653665 -0.25 0.1847759 -0.07653665 0.25 0.1763842 -0.09427934 -0.25 0.1763842 -0.09427934 0.25 0.1662939 -0.111114 -0.25 0.1662939 -0.111114 0.25 0.1546021 -0.1268786 -0.25 0.1546021 -0.1268786 0.25 0.1414213 -0.1414213 -0.25 0.1414213 -0.1414213 0.25 0.1268786 -0.1546021 -0.25 0.1268786 -0.1546021 0.25 0.111114 -0.1662939 -0.25 0.111114 -0.1662939 0.25 0.09427934 -0.1763842 -0.25 0.09427934 -0.1763842 0.25 0.07653665 -0.1847759 -0.25 0.07653665 -0.1847759 0.25 0.05805689 -0.191388 -0.25 0.05805689 -0.191388 0.25 0.03901803 -0.196157 -0.25 0.03901803 -0.196157 0.25 0.01960343 -0.1990369 -0.25 0.01960343 -0.1990369 0.25 0 -0.2 -0.25 0 -0.2 0.25 -0.01960343 -0.1990369 -0.25 -0.01960343 -0.1990369 0.25 -0.03901803 -0.196157 -0.25 -0.03901803 -0.196157 0.25 -0.05805689 -0.191388 -0.25 -0.05805689 -0.191388 0.25 -0.07653665 -0.1847759 -0.25 -0.07653665 -0.1847759 0.25 -0.09427934 -0.1763842 -0.25 -0.09427934 -0.1763842 0.25 -0.111114 -0.1662939 -0.25 -0.111114 -0.1662939 0.25 -0.1268786 -0.1546021 -0.25 -0.1268786 -0.1546021 0.25 -0.1414213 -0.1414213 -0.25 -0.1414213 -0.1414213 0.25 -0.1546021 -0.1268786 -0.25 -0.1546021 -0.1268786 0.25 -0.1662939 -0.111114 -0.25 -0.1662939 -0.111114 0.25 -0.1763842 -0.09427934 -0.25 -0.1763842 -0.09427934 0.25 -0.1847759 -0.07653665 -0.25 -0.1847759 -0.07653665 0.25 -0.191388 -0.05805689 -0.25 -0.191388 -0.05805689 0.25 -0.196157 -0.03901803 -0.25 -0.196157 -0.03901803 0.25 -0.1990369 -0.01960343 -0.25 -0.1990369 -0.01960343 0.25 -0.2 0 -0.25 -0.2 0 0.25 -0.1990369 0.01960343 -0.25 -0.1990369 0.01960343 0.25 -0.196157 0.03901803 -0.25 -0.196157 0.03901803 0.25 -0.191388 0.05805689 -0.25 -0.191388 0.05805689 0.25 -0.1847759 0.07653665 -0.25 -0.1847759 0.07653665 0.25 -0.1763842 0.09427934 -0.25 -0.1763842 0.09427934 0.25 -0.1662939 0.111114 -0.25 -0.1662939 0.111114 0.25 -0.1546021 0.1268786 -0.25 -0.1546021 0.1268786 0.25 -0.1414213 0.1414213 -0.25 -0.1414213 0.1414213 0.25 -0.1268786 0.1546021 -0.25 -0.1268786 0.1546021 0.25 -0.111114 0.1662939 -0.25 -0.111114 0.1662939 0.25 -0.09427934 0.1763842 -0.25 -0.09427934 0.1763842 0.25 -0.07653665 0.1847759 -0.25 -0.07653665 0.1847759 0.25 -0.05805689 0.191388 -0.25 -0.05805689 0.191388 0.25 -0.03901803 0.196157 -0.25 -0.03901803 0.196157 0.25 -0.01960343 0.1990369 -0.25 -0.01960343 0.1990369 0.25 - - - - - - - - - - 0.04906803 0.9987955 0 0.1467304 0.9891766 0 0.2429799 0.9700314 0 0.3368901 0.941544 0 0.4275552 0.9039894 0 0.5141029 0.8577287 0 0.5956991 0.8032077 0 0.671559 0.7409512 0 0.7409512 0.671559 0 0.8032076 0.5956994 0 0.8577282 0.5141035 0 0.9039894 0.427555 0 0.9415443 0.3368894 0 0.9700315 0.2429791 0 0.9891766 0.1467304 0 0.9987955 0.04906803 0 0.9987955 -0.04906803 0 0.9891766 -0.1467304 0 0.9700313 -0.2429805 0 0.9415438 -0.3368908 0 0.9039894 -0.427555 0 0.8577289 -0.5141025 0 0.8032082 -0.5956984 0 0.7409512 -0.671559 0 0.671559 -0.7409512 0 0.5956988 -0.8032081 0 0.5141032 -0.8577285 0 0.4275549 -0.9039895 0 0.3368902 -0.9415439 0 0.2429798 -0.9700314 0 0.1467304 -0.9891766 0 0.04906803 -0.9987955 0 -0.04906803 -0.9987955 0 -0.1467304 -0.9891766 0 -0.2429799 -0.9700314 0 -0.3368901 -0.941544 0 -0.4275552 -0.9039894 0 -0.5141029 -0.8577287 0 -0.5956991 -0.8032077 0 -0.671559 -0.7409512 0 -0.7409512 -0.671559 0 -0.8032076 -0.5956994 0 -0.8577282 -0.5141035 0 -0.9039894 -0.427555 0 -0.9415443 -0.3368894 0 -0.9700315 -0.2429791 0 -0.9891766 -0.1467304 0 -0.9987955 -0.04906803 0 -0.9987955 0.04906803 0 -0.9891766 0.1467304 0 -0.9700313 0.2429805 0 -0.9415438 0.3368908 0 -0.9039894 0.427555 0 -0.8577289 0.5141025 0 -0.8032082 0.5956984 0 -0.7409512 0.671559 0 -0.671559 0.7409512 0 -0.5956988 0.8032081 0 -0.5141032 0.8577285 0 -0.4275549 0.9039895 0 -0.3368902 0.9415439 0 -0.2429798 0.9700314 0 0 0 1 -0.1467304 0.9891766 0 -0.04906803 0.9987955 0 0 0 -1 0.1467304 0.9891766 0 0.2429798 0.9700314 0 0.3368902 0.9415439 0 0.4275549 0.9039895 0 0.5141032 0.8577285 0 0.5956988 0.8032081 0 0.8032082 0.5956984 0 0.8577289 0.5141025 0 0.9415438 0.3368908 0 0.9700313 0.2429805 0 0.9700315 -0.2429791 0 0.9415443 -0.3368894 0 0.8577282 -0.5141035 0 0.8032076 -0.5956994 0 0.5956991 -0.8032077 0 0.5141029 -0.8577287 0 0.4275552 -0.9039894 0 0.3368901 -0.941544 0 0.2429799 -0.9700314 0 0.1467304 -0.9891766 0 -0.1467304 -0.9891766 0 -0.2429798 -0.9700314 0 -0.3368902 -0.9415439 0 -0.4275549 -0.9039895 0 -0.5141032 -0.8577285 0 -0.5956988 -0.8032081 0 -0.8032082 -0.5956984 0 -0.8577289 -0.5141025 0 -0.9415438 -0.3368908 0 -0.9700313 -0.2429805 0 -0.9700315 0.2429791 0 -0.9415443 0.3368894 0 -0.8577282 0.5141035 0 -0.8032076 0.5956994 0 -0.5956991 0.8032077 0 -0.5141029 0.8577287 0 -0.4275552 0.9039894 0 -0.3368901 0.941544 0 -0.2429799 0.9700314 0 -1.59856e-6 0 1 1.59856e-6 0 1 3.72529e-7 0 1 -3.72529e-7 0 1 -0.1467304 0.9891766 0 -1.64965e-5 0 -1 2.46654e-5 0 -1 2.46654e-5 0 -1 1.64965e-5 0 -1 -2.46654e-5 0 -1 -2.46654e-5 0 -1 -4.19448e-6 0 -1 4.19448e-6 0 -1 - - - - - - - - - - 1 1 0.984375 0.5 1 0.5 0.984375 1 0.96875 0.5 0.984375 0.5 0.96875 1 0.953125 0.5 0.96875 0.5 0.953125 1 0.9375 0.5 0.953125 0.5 0.9375 1 0.921875 0.5 0.9375 0.5 0.921875 1 0.90625 0.5 0.921875 0.5 0.90625 1 0.890625 0.5 0.90625 0.5 0.890625 1 0.875 0.5 0.890625 0.5 0.875 1 0.859375 0.5 0.875 0.5 0.859375 1 0.84375 0.5 0.859375 0.5 0.84375 1 0.828125 0.5 0.84375 0.5 0.828125 1 0.8125 0.5 0.828125 0.5 0.8125 1 0.796875 0.5 0.8125 0.5 0.796875 1 0.78125 0.5 0.796875 0.5 0.78125 1 0.765625 0.5 0.78125 0.5 0.765625 1 0.75 0.5 0.765625 0.5 0.75 1 0.734375 0.5 0.75 0.5 0.734375 1 0.71875 0.5 0.734375 0.5 0.71875 1 0.703125 0.5 0.71875 0.5 0.703125 1 0.6875 0.5 0.703125 0.5 0.6875 1 0.671875 0.5 0.6875 0.5 0.671875 1 0.65625 0.5 0.671875 0.5 0.65625 1 0.640625 0.5 0.65625 0.5 0.640625 1 0.625 0.5 0.640625 0.5 0.625 1 0.609375 0.5 0.625 0.5 0.609375 1 0.59375 0.5 0.609375 0.5 0.59375 1 0.578125 0.5 0.59375 0.5 0.578125 1 0.5625 0.5 0.578125 0.5 0.5625 1 0.546875 0.5 0.5625 0.5 0.546875 1 0.53125 0.5 0.546875 0.5 0.53125 1 0.515625 0.5 0.53125 0.5 0.515625 1 0.5 0.5 0.515625 0.5 0.5 1 0.484375 0.5 0.5 0.5 0.484375 1 0.46875 0.5 0.484375 0.5 0.46875 1 0.453125 0.5 0.46875 0.5 0.453125 1 0.4375 0.5 0.453125 0.5 0.4375 1 0.421875 0.5 0.4375 0.5 0.421875 1 0.40625 0.5 0.421875 0.5 0.40625 1 0.390625 0.5 0.40625 0.5 0.390625 1 0.375 0.5 0.390625 0.5 0.375 1 0.359375 0.5 0.375 0.5 0.359375 1 0.34375 0.5 0.359375 0.5 0.34375 1 0.328125 0.5 0.34375 0.5 0.328125 1 0.3125 0.5 0.328125 0.5 0.3125 1 0.296875 0.5 0.3125 0.5 0.296875 1 0.28125 0.5 0.296875 0.5 0.28125 1 0.265625 0.5 0.28125 0.5 0.265625 1 0.25 0.5 0.265625 0.5 0.25 1 0.234375 0.5 0.25 0.5 0.234375 1 0.21875 0.5 0.234375 0.5 0.21875 1 0.203125 0.5 0.21875 0.5 0.203125 1 0.1875 0.5 0.203125 0.5 0.1875 1 0.171875 0.5 0.1875 0.5 0.171875 1 0.15625 0.5 0.171875 0.5 0.15625 1 0.140625 0.5 0.15625 0.5 0.140625 1 0.125 0.5 0.140625 0.5 0.125 1 0.109375 0.5 0.125 0.5 0.109375 1 0.09375 0.5 0.109375 0.5 0.09375 1 0.078125 0.5 0.09375 0.5 0.078125 1 0.0625 0.5 0.078125 0.5 0.0625 1 0.046875 0.5 0.0625 0.5 0.046875 1 0.03125 0.5 0.046875 0.5 0.4495527 0.3833369 0.2968217 0.4853885 0.2031783 0.01461154 0.03125 1 0.015625 0.5 0.03125 0.5 0.015625 1 0 0.5 0.015625 0.5 0.7735241 0.01115566 0.5111557 0.2264758 0.7264759 0.4888443 1 1 0.984375 1 0.984375 0.5 0.984375 1 0.96875 1 0.96875 0.5 0.96875 1 0.953125 1 0.953125 0.5 0.953125 1 0.9375 1 0.9375 0.5 0.9375 1 0.921875 1 0.921875 0.5 0.921875 1 0.90625 1 0.90625 0.5 0.90625 1 0.890625 1 0.890625 0.5 0.890625 1 0.875 1 0.875 0.5 0.875 1 0.859375 1 0.859375 0.5 0.859375 1 0.84375 1 0.84375 0.5 0.84375 1 0.828125 1 0.828125 0.5 0.828125 1 0.8125 1 0.8125 0.5 0.8125 1 0.796875 1 0.796875 0.5 0.796875 1 0.78125 1 0.78125 0.5 0.78125 1 0.765625 1 0.765625 0.5 0.765625 1 0.75 1 0.75 0.5 0.75 1 0.734375 1 0.734375 0.5 0.734375 1 0.71875 1 0.71875 0.5 0.71875 1 0.703125 1 0.703125 0.5 0.703125 1 0.6875 1 0.6875 0.5 0.6875 1 0.671875 1 0.671875 0.5 0.671875 1 0.65625 1 0.65625 0.5 0.65625 1 0.640625 1 0.640625 0.5 0.640625 1 0.625 1 0.625 0.5 0.625 1 0.609375 1 0.609375 0.5 0.609375 1 0.59375 1 0.59375 0.5 0.59375 1 0.578125 1 0.578125 0.5 0.578125 1 0.5625 1 0.5625 0.5 0.5625 1 0.546875 1 0.546875 0.5 0.546875 1 0.53125 1 0.53125 0.5 0.53125 1 0.515625 1 0.515625 0.5 0.515625 1 0.5 1 0.5 0.5 0.5 1 0.484375 1 0.484375 0.5 0.484375 1 0.46875 1 0.46875 0.5 0.46875 1 0.453125 1 0.453125 0.5 0.453125 1 0.4375 1 0.4375 0.5 0.4375 1 0.421875 1 0.421875 0.5 0.421875 1 0.40625 1 0.40625 0.5 0.40625 1 0.390625 1 0.390625 0.5 0.390625 1 0.375 1 0.375 0.5 0.375 1 0.359375 1 0.359375 0.5 0.359375 1 0.34375 1 0.34375 0.5 0.34375 1 0.328125 1 0.328125 0.5 0.328125 1 0.3125 1 0.3125 0.5 0.3125 1 0.296875 1 0.296875 0.5 0.296875 1 0.28125 1 0.28125 0.5 0.28125 1 0.265625 1 0.265625 0.5 0.265625 1 0.25 1 0.25 0.5 0.25 1 0.234375 1 0.234375 0.5 0.234375 1 0.21875 1 0.21875 0.5 0.21875 1 0.203125 1 0.203125 0.5 0.203125 1 0.1875 1 0.1875 0.5 0.1875 1 0.171875 1 0.171875 0.5 0.171875 1 0.15625 1 0.15625 0.5 0.15625 1 0.140625 1 0.140625 0.5 0.140625 1 0.125 1 0.125 0.5 0.125 1 0.109375 1 0.109375 0.5 0.109375 1 0.09375 1 0.09375 0.5 0.09375 1 0.078125 1 0.078125 0.5 0.078125 1 0.0625 1 0.0625 0.5 0.0625 1 0.046875 1 0.046875 0.5 0.046875 1 0.03125 1 0.03125 0.5 0.2968217 0.4853885 0.2735241 0.4888443 0.25 0.49 0.25 0.49 0.2264758 0.4888443 0.2968217 0.4853885 0.2264758 0.4888443 0.2031783 0.4853885 0.2968217 0.4853885 0.2031783 0.4853885 0.1803317 0.4796656 0.1581559 0.4717311 0.1581559 0.4717311 0.1368647 0.4616611 0.1166631 0.4495527 0.1166631 0.4495527 0.09774559 0.4355225 0.08029437 0.4197056 0.08029437 0.4197056 0.0644775 0.4022544 0.05044728 0.3833369 0.05044728 0.3833369 0.03833889 0.3631352 0.02826893 0.341844 0.02826893 0.341844 0.0203343 0.3196683 0.01461154 0.2968217 0.01461154 0.2968217 0.01115566 0.2735241 0.00999999 0.25 0.00999999 0.25 0.01115566 0.2264758 0.01461154 0.2968217 0.01115566 0.2264758 0.01461154 0.2031783 0.01461154 0.2968217 0.01461154 0.2031783 0.0203343 0.1803317 0.02826893 0.1581559 0.02826893 0.1581559 0.03833889 0.1368647 0.05044728 0.1166631 0.05044728 0.1166631 0.0644775 0.09774559 0.08029437 0.08029437 0.08029437 0.08029437 0.09774559 0.0644775 0.1166631 0.05044728 0.1166631 0.05044728 0.1368647 0.03833889 0.1581559 0.02826893 0.1581559 0.02826893 0.1803317 0.0203343 0.2031783 0.01461154 0.2031783 0.01461154 0.2264758 0.01115566 0.2968217 0.01461154 0.2264758 0.01115566 0.25 0.00999999 0.2968217 0.01461154 0.25 0.00999999 0.2735241 0.01115566 0.2968217 0.01461154 0.2968217 0.01461154 0.3196683 0.0203343 0.341844 0.02826893 0.341844 0.02826893 0.3631352 0.03833889 0.3833369 0.05044728 0.3833369 0.05044728 0.4022544 0.0644775 0.4197056 0.08029437 0.4197056 0.08029437 0.4355225 0.09774559 0.4495527 0.1166631 0.4495527 0.1166631 0.4616611 0.1368647 0.4717311 0.1581559 0.4717311 0.1581559 0.4796656 0.1803317 0.4853885 0.2031783 0.4853885 0.2031783 0.4888443 0.2264758 0.49 0.25 0.49 0.25 0.4888443 0.2735241 0.4853885 0.2031783 0.4888443 0.2735241 0.4853885 0.2968217 0.4853885 0.2031783 0.4853885 0.2968217 0.4796656 0.3196683 0.4717311 0.341844 0.4717311 0.341844 0.4616611 0.3631352 0.4495527 0.3833369 0.4495527 0.3833369 0.4355225 0.4022544 0.4197056 0.4197056 0.4197056 0.4197056 0.4022544 0.4355225 0.3833369 0.4495527 0.3833369 0.4495527 0.3631352 0.4616611 0.341844 0.4717311 0.341844 0.4717311 0.3196683 0.4796656 0.2968217 0.4853885 0.2031783 0.4853885 0.1581559 0.4717311 0.1166631 0.4495527 0.1166631 0.4495527 0.08029437 0.4197056 0.05044728 0.3833369 0.05044728 0.3833369 0.02826893 0.341844 0.01461154 0.2968217 0.01461154 0.2031783 0.02826893 0.1581559 0.05044728 0.1166631 0.05044728 0.1166631 0.08029437 0.08029437 0.1166631 0.05044728 0.1166631 0.05044728 0.1581559 0.02826893 0.2031783 0.01461154 0.2968217 0.01461154 0.341844 0.02826893 0.3833369 0.05044728 0.3833369 0.05044728 0.4197056 0.08029437 0.4495527 0.1166631 0.4495527 0.1166631 0.4717311 0.1581559 0.4853885 0.2031783 0.4853885 0.2968217 0.4717311 0.341844 0.4495527 0.3833369 0.4495527 0.3833369 0.4197056 0.4197056 0.3833369 0.4495527 0.3833369 0.4495527 0.341844 0.4717311 0.2968217 0.4853885 0.2968217 0.4853885 0.2031783 0.4853885 0.1166631 0.4495527 0.1166631 0.4495527 0.05044728 0.3833369 0.01461154 0.2968217 0.01461154 0.2968217 0.01461154 0.2031783 0.05044728 0.1166631 0.05044728 0.1166631 0.1166631 0.05044728 0.2031783 0.01461154 0.2031783 0.01461154 0.2968217 0.01461154 0.3833369 0.05044728 0.3833369 0.05044728 0.4495527 0.1166631 0.4853885 0.2031783 0.4853885 0.2031783 0.4853885 0.2968217 0.4495527 0.3833369 0.4495527 0.3833369 0.3833369 0.4495527 0.2968217 0.4853885 0.2968217 0.4853885 0.1166631 0.4495527 0.01461154 0.2968217 0.01461154 0.2968217 0.05044728 0.1166631 0.2968217 0.4853885 0.05044728 0.1166631 0.2031783 0.01461154 0.2968217 0.4853885 0.2031783 0.01461154 0.3833369 0.05044728 0.4853885 0.2031783 0.4853885 0.2031783 0.4495527 0.3833369 0.2031783 0.01461154 0.03125 1 0.015625 1 0.015625 0.5 0.015625 1 0 1 0 0.5 0.7264759 0.4888443 0.75 0.49 0.7735241 0.4888443 0.7735241 0.4888443 0.7968217 0.4853885 0.8196683 0.4796656 0.8196683 0.4796656 0.841844 0.4717311 0.8631352 0.4616611 0.8631352 0.4616611 0.8833369 0.4495527 0.8196683 0.4796656 0.8833369 0.4495527 0.9022544 0.4355225 0.8196683 0.4796656 0.9022544 0.4355225 0.9197056 0.4197056 0.9355225 0.4022544 0.9355225 0.4022544 0.9495527 0.3833369 0.9022544 0.4355225 0.9495527 0.3833369 0.9616611 0.3631352 0.9022544 0.4355225 0.9616611 0.3631352 0.9717311 0.341844 0.9888443 0.2735241 0.9717311 0.341844 0.9796656 0.3196683 0.9888443 0.2735241 0.9796656 0.3196683 0.9853885 0.2968217 0.9888443 0.2735241 0.9888443 0.2735241 0.99 0.25 0.9888443 0.2264758 0.9888443 0.2264758 0.9853885 0.2031783 0.9796656 0.1803317 0.9796656 0.1803317 0.9717311 0.1581559 0.9616611 0.1368647 0.9616611 0.1368647 0.9495527 0.1166631 0.9796656 0.1803317 0.9495527 0.1166631 0.9355225 0.09774559 0.9796656 0.1803317 0.9355225 0.09774559 0.9197056 0.08029437 0.9022544 0.0644775 0.9022544 0.0644775 0.8833369 0.05044728 0.9355225 0.09774559 0.8833369 0.05044728 0.8631352 0.03833889 0.9355225 0.09774559 0.8631352 0.03833889 0.841844 0.02826893 0.7735241 0.01115566 0.841844 0.02826893 0.8196683 0.0203343 0.7735241 0.01115566 0.8196683 0.0203343 0.7968217 0.01461154 0.7735241 0.01115566 0.7735241 0.01115566 0.75 0.00999999 0.7264759 0.01115566 0.7264759 0.01115566 0.7031784 0.01461154 0.6803317 0.0203343 0.6803317 0.0203343 0.658156 0.02826893 0.6368648 0.03833889 0.6368648 0.03833889 0.6166632 0.05044728 0.6803317 0.0203343 0.6166632 0.05044728 0.5977456 0.0644775 0.6803317 0.0203343 0.5977456 0.0644775 0.5802944 0.08029437 0.5644775 0.09774559 0.5644775 0.09774559 0.5504474 0.1166631 0.5977456 0.0644775 0.5504474 0.1166631 0.5383389 0.1368647 0.5977456 0.0644775 0.5383389 0.1368647 0.5282689 0.1581559 0.5111557 0.2264758 0.5282689 0.1581559 0.5203344 0.1803317 0.5111557 0.2264758 0.5203344 0.1803317 0.5146116 0.2031783 0.5111557 0.2264758 0.5111557 0.2264758 0.51 0.25 0.5111557 0.2735241 0.5111557 0.2735241 0.5146116 0.2968217 0.5203344 0.3196683 0.5203344 0.3196683 0.5282689 0.341844 0.5383389 0.3631352 0.5383389 0.3631352 0.5504474 0.3833369 0.5203344 0.3196683 0.5504474 0.3833369 0.5644775 0.4022544 0.5203344 0.3196683 0.5644775 0.4022544 0.5802944 0.4197056 0.5977456 0.4355225 0.5977456 0.4355225 0.6166632 0.4495527 0.5644775 0.4022544 0.6166632 0.4495527 0.6368648 0.4616611 0.5644775 0.4022544 0.6368648 0.4616611 0.658156 0.4717311 0.7264759 0.4888443 0.658156 0.4717311 0.6803317 0.4796656 0.7264759 0.4888443 0.6803317 0.4796656 0.7031784 0.4853885 0.7264759 0.4888443 0.7264759 0.4888443 0.7735241 0.4888443 0.9022544 0.4355225 0.7735241 0.4888443 0.8196683 0.4796656 0.9022544 0.4355225 0.9888443 0.2735241 0.9888443 0.2264758 0.9355225 0.09774559 0.9888443 0.2264758 0.9796656 0.1803317 0.9355225 0.09774559 0.7735241 0.01115566 0.7264759 0.01115566 0.5977456 0.0644775 0.7264759 0.01115566 0.6803317 0.0203343 0.5977456 0.0644775 0.5111557 0.2264758 0.5111557 0.2735241 0.5644775 0.4022544 0.5111557 0.2735241 0.5203344 0.3196683 0.5644775 0.4022544 0.9022544 0.4355225 0.9616611 0.3631352 0.9888443 0.2735241 0.9355225 0.09774559 0.8631352 0.03833889 0.7735241 0.01115566 0.5977456 0.0644775 0.5383389 0.1368647 0.5111557 0.2264758 0.5644775 0.4022544 0.6368648 0.4616611 0.7264759 0.4888443 0.7264759 0.4888443 0.9022544 0.4355225 0.9888443 0.2735241 0.9888443 0.2735241 0.9355225 0.09774559 0.7735241 0.01115566 0.7735241 0.01115566 0.5977456 0.0644775 0.5111557 0.2264758 0.5111557 0.2264758 0.5644775 0.4022544 0.7264759 0.4888443 0.7264759 0.4888443 0.9888443 0.2735241 0.7735241 0.01115566 - - - - - - - - - - - - - - -

1 0 0 2 0 1 0 0 2 3 1 3 4 1 4 2 1 5 5 2 6 6 2 7 4 2 8 7 3 9 8 3 10 6 3 11 9 4 12 10 4 13 8 4 14 11 5 15 12 5 16 10 5 17 13 6 18 14 6 19 12 6 20 15 7 21 16 7 22 14 7 23 17 8 24 18 8 25 16 8 26 19 9 27 20 9 28 18 9 29 21 10 30 22 10 31 20 10 32 23 11 33 24 11 34 22 11 35 25 12 36 26 12 37 24 12 38 27 13 39 28 13 40 26 13 41 29 14 42 30 14 43 28 14 44 31 15 45 32 15 46 30 15 47 33 16 48 34 16 49 32 16 50 35 17 51 36 17 52 34 17 53 37 18 54 38 18 55 36 18 56 39 19 57 40 19 58 38 19 59 41 20 60 42 20 61 40 20 62 43 21 63 44 21 64 42 21 65 45 22 66 46 22 67 44 22 68 47 23 69 48 23 70 46 23 71 49 24 72 50 24 73 48 24 74 51 25 75 52 25 76 50 25 77 53 26 78 54 26 79 52 26 80 55 27 81 56 27 82 54 27 83 57 28 84 58 28 85 56 28 86 59 29 87 60 29 88 58 29 89 61 30 90 62 30 91 60 30 92 63 31 93 64 31 94 62 31 95 65 32 96 66 32 97 64 32 98 67 33 99 68 33 100 66 33 101 69 34 102 70 34 103 68 34 104 71 35 105 72 35 106 70 35 107 73 36 108 74 36 109 72 36 110 75 37 111 76 37 112 74 37 113 77 38 114 78 38 115 76 38 116 79 39 117 80 39 118 78 39 119 81 40 120 82 40 121 80 40 122 83 41 123 84 41 124 82 41 125 85 42 126 86 42 127 84 42 128 87 43 129 88 43 130 86 43 131 89 44 132 90 44 133 88 44 134 91 45 135 92 45 136 90 45 137 93 46 138 94 46 139 92 46 140 95 47 141 96 47 142 94 47 143 97 48 144 98 48 145 96 48 146 99 49 147 100 49 148 98 49 149 101 50 150 102 50 151 100 50 152 103 51 153 104 51 154 102 51 155 105 52 156 106 52 157 104 52 158 107 53 159 108 53 160 106 53 161 109 54 162 110 54 163 108 54 164 111 55 165 112 55 166 110 55 167 113 56 168 114 56 169 112 56 170 115 57 171 116 57 172 114 57 173 117 58 174 118 58 175 116 58 176 119 59 177 120 59 178 118 59 179 121 60 180 122 60 181 120 60 182 123 61 183 124 61 184 122 61 185 21 62 186 5 62 187 69 62 188 125 63 189 126 63 190 124 63 191 127 64 192 0 64 193 126 64 194 62 65 195 94 65 196 126 65 197 1 0 198 3 0 199 2 0 200 3 66 201 5 66 202 4 66 203 5 67 204 7 67 205 6 67 206 7 68 207 9 68 208 8 68 209 9 69 210 11 69 211 10 69 212 11 70 213 13 70 214 12 70 215 13 71 216 15 71 217 14 71 218 15 7 219 17 7 220 16 7 221 17 8 222 19 8 223 18 8 224 19 72 225 21 72 226 20 72 227 21 73 228 23 73 229 22 73 230 23 11 231 25 11 232 24 11 233 25 74 234 27 74 235 26 74 236 27 75 237 29 75 238 28 75 239 29 14 240 31 14 241 30 14 242 31 15 243 33 15 244 32 15 245 33 16 246 35 16 247 34 16 248 35 17 249 37 17 250 36 17 251 37 76 252 39 76 253 38 76 254 39 77 255 41 77 256 40 77 257 41 20 258 43 20 259 42 20 260 43 78 261 45 78 262 44 78 263 45 79 264 47 79 265 46 79 266 47 23 267 49 23 268 48 23 269 49 24 270 51 24 271 50 24 272 51 80 273 53 80 274 52 80 275 53 81 276 55 81 277 54 81 278 55 82 279 57 82 280 56 82 281 57 83 282 59 83 283 58 83 284 59 84 285 61 84 286 60 84 287 61 85 288 63 85 289 62 85 290 63 31 291 65 31 292 64 31 293 65 32 294 67 32 295 66 32 296 67 86 297 69 86 298 68 86 299 69 87 300 71 87 301 70 87 302 71 88 303 73 88 304 72 88 305 73 89 306 75 89 307 74 89 308 75 90 309 77 90 310 76 90 311 77 91 312 79 91 313 78 91 314 79 39 315 81 39 316 80 39 317 81 40 318 83 40 319 82 40 320 83 92 321 85 92 322 84 92 323 85 93 324 87 93 325 86 93 326 87 43 327 89 43 328 88 43 329 89 94 330 91 94 331 90 94 332 91 95 333 93 95 334 92 95 335 93 46 336 95 46 337 94 46 338 95 47 339 97 47 340 96 47 341 97 48 342 99 48 343 98 48 344 99 49 345 101 49 346 100 49 347 101 96 348 103 96 349 102 96 350 103 97 351 105 97 352 104 97 353 105 52 354 107 52 355 106 52 356 107 98 357 109 98 358 108 98 359 109 99 360 111 99 361 110 99 362 111 55 363 113 55 364 112 55 365 113 56 366 115 56 367 114 56 368 115 100 369 117 100 370 116 100 371 117 101 372 119 101 373 118 101 374 119 102 375 121 102 376 120 102 377 121 103 378 123 103 379 122 103 380 123 104 381 125 104 382 124 104 383 5 62 384 3 62 385 1 62 386 1 62 387 127 62 388 5 62 389 127 62 390 125 62 391 5 62 392 125 62 393 123 62 394 121 62 395 121 62 396 119 62 397 117 62 398 117 62 399 115 62 400 113 62 401 113 62 402 111 62 403 109 62 404 109 62 405 107 62 406 105 62 407 105 62 408 103 62 409 101 62 410 101 62 411 99 62 412 97 62 413 97 62 414 95 62 415 101 62 416 95 62 417 93 62 418 101 62 419 93 62 420 91 62 421 89 62 422 89 62 423 87 62 424 85 62 425 85 62 426 83 62 427 81 62 428 81 62 429 79 62 430 77 62 431 77 62 432 75 62 433 73 62 434 73 62 435 71 62 436 69 62 437 69 62 438 67 62 439 61 62 440 67 62 441 65 62 442 61 62 443 65 62 444 63 62 445 61 62 446 61 62 447 59 62 448 57 62 449 57 62 450 55 62 451 53 62 452 53 62 453 51 62 454 49 62 455 49 62 456 47 62 457 45 62 458 45 62 459 43 62 460 41 62 461 41 62 462 39 62 463 37 62 464 37 62 465 35 62 466 33 62 467 33 62 468 31 62 469 37 62 470 31 62 471 29 62 472 37 62 473 29 62 474 27 62 475 25 62 476 25 62 477 23 62 478 21 62 479 21 62 480 19 62 481 17 62 482 17 62 483 15 62 484 13 62 485 13 62 486 11 62 487 9 62 488 9 62 489 7 62 490 5 62 491 125 62 492 121 62 493 117 62 494 117 62 495 113 62 496 109 62 497 109 62 498 105 62 499 101 62 500 93 62 501 89 62 502 85 62 503 85 62 504 81 62 505 77 62 506 77 62 507 73 62 508 69 62 509 61 62 510 57 62 511 53 62 512 53 62 513 49 62 514 45 62 515 45 62 516 41 62 517 37 62 518 29 62 519 25 62 520 21 62 521 21 62 522 17 62 523 13 62 524 13 62 525 9 62 526 5 62 527 5 62 528 125 62 529 117 62 530 117 62 531 109 62 532 101 62 533 101 105 534 93 105 535 85 105 536 85 62 537 77 62 538 69 62 539 69 62 540 61 62 541 53 62 542 53 62 543 45 62 544 37 62 545 37 106 546 29 106 547 21 106 548 21 62 549 13 62 550 5 62 551 5 62 552 117 62 553 101 62 554 101 107 555 85 107 556 5 107 557 85 62 558 69 62 559 5 62 560 69 62 561 53 62 562 37 62 563 37 108 564 21 108 565 69 108 566 125 109 567 127 109 568 126 109 569 127 64 570 1 64 571 0 64 572 126 65 573 0 65 574 2 65 575 2 65 576 4 65 577 6 65 578 6 65 579 8 65 580 10 65 581 10 65 582 12 65 583 6 65 584 12 65 585 14 65 586 6 65 587 14 65 588 16 65 589 18 65 590 18 65 591 20 65 592 14 65 593 20 65 594 22 65 595 14 65 596 22 65 597 24 65 598 30 65 599 24 110 600 26 110 601 30 110 602 26 111 603 28 111 604 30 111 605 30 65 606 32 65 607 34 65 608 34 112 609 36 112 610 38 112 611 38 65 612 40 65 613 42 65 614 42 65 615 44 65 616 38 65 617 44 65 618 46 65 619 38 65 620 46 65 621 48 65 622 50 65 623 50 65 624 52 65 625 46 65 626 52 65 627 54 65 628 46 65 629 54 65 630 56 65 631 62 65 632 56 65 633 58 65 634 62 65 635 58 65 636 60 65 637 62 65 638 62 65 639 64 65 640 66 65 641 66 65 642 68 65 643 70 65 644 70 65 645 72 65 646 74 65 647 74 65 648 76 65 649 70 65 650 76 65 651 78 65 652 70 65 653 78 65 654 80 65 655 82 65 656 82 65 657 84 65 658 78 65 659 84 65 660 86 65 661 78 65 662 86 65 663 88 65 664 94 65 665 88 113 666 90 113 667 94 113 668 90 114 669 92 114 670 94 114 671 94 65 672 96 65 673 98 65 674 98 115 675 100 115 676 102 115 677 102 65 678 104 65 679 106 65 680 106 65 681 108 65 682 102 65 683 108 65 684 110 65 685 102 65 686 110 65 687 112 65 688 114 65 689 114 65 690 116 65 691 110 65 692 116 65 693 118 65 694 110 65 695 118 65 696 120 65 697 126 65 698 120 65 699 122 65 700 126 65 701 122 65 702 124 65 703 126 65 704 126 65 705 2 65 706 14 65 707 2 65 708 6 65 709 14 65 710 30 65 711 34 65 712 46 65 713 34 116 714 38 116 715 46 116 716 62 65 717 66 65 718 78 65 719 66 65 720 70 65 721 78 65 722 94 65 723 98 65 724 110 65 725 98 117 726 102 117 727 110 117 728 14 65 729 22 65 730 30 65 731 46 65 732 54 65 733 62 65 734 78 65 735 86 65 736 94 65 737 110 65 738 118 65 739 126 65 740 126 65 741 14 65 742 30 65 743 30 65 744 46 65 745 62 65 746 62 65 747 78 65 748 94 65 749 94 65 750 110 65 751 126 65 752 126 65 753 30 65 754 62 65 755

-
-
-
-
- - - - 0.2723969 0 0 -2.50608e-4 0 0.2723969 0 -5.30411e-4 0 0 0.2723969 0.071059 0 0 0 1 - - - - - - - - - - - - 1 0 0 7.93293e-4 0 1 0 0.001094017 0 0 1 1.200842 0 0 0 1 - - - - - - - -
diff --git a/src/picknik_ur_mock_hw_config/meshes/cylinder-item.png b/src/picknik_ur_mock_hw_config/meshes/cylinder-item.png deleted file mode 100644 index bdfabc8a..00000000 Binary files a/src/picknik_ur_mock_hw_config/meshes/cylinder-item.png and /dev/null differ diff --git a/src/picknik_ur_mock_hw_config/meshes/table-collision.dae b/src/picknik_ur_mock_hw_config/meshes/table-collision.dae deleted file mode 100644 index bed3cb61..00000000 --- a/src/picknik_ur_mock_hw_config/meshes/table-collision.dae +++ /dev/null @@ -1,70 +0,0 @@ - - - - - Blender User - Blender 3.6.1 commit date:2023-07-17, commit time:12:50, hash:8bda729ef4dc - - 2023-08-01T21:33:12 - 2023-08-01T21:33:12 - - Z_UP - - - - - - - - -1 -1 -1 -1 -1 1 -1 1 -1 -1 1 1 1 -1 -1 1 -1 1 1 1 -1 1 1 1 - - - - - - - - - - -1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1 - - - - - - - - - - 0.625 0 0.375 0.25 0.375 0 0.625 0.25 0.375 0.5 0.375 0.25 0.625 0.5 0.375 0.75 0.375 0.5 0.625 0.75 0.375 1 0.375 0.75 0.375 0.5 0.125 0.75 0.125 0.5 0.875 0.5 0.625 0.75 0.625 0.5 0.625 0 0.625 0.25 0.375 0.25 0.625 0.25 0.625 0.5 0.375 0.5 0.625 0.5 0.625 0.75 0.375 0.75 0.625 0.75 0.625 1 0.375 1 0.375 0.5 0.375 0.75 0.125 0.75 0.875 0.5 0.875 0.75 0.625 0.75 - - - - - - - - - - - - - - -

1 0 0 2 0 1 0 0 2 3 1 3 6 1 4 2 1 5 7 2 6 4 2 7 6 2 8 5 3 9 0 3 10 4 3 11 6 4 12 0 4 13 2 4 14 3 5 15 5 5 16 7 5 17 1 0 18 3 0 19 2 0 20 3 1 21 7 1 22 6 1 23 7 2 24 5 2 25 4 2 26 5 3 27 1 3 28 0 3 29 6 4 30 4 4 31 0 4 32 3 5 33 1 5 34 5 5 35

-
-
-
-
- - - - 0.3757816 0 0 -5.04553e-5 0 0.3903046 0 0.006199756 0 0 0.2840506 0.2873469 0 0 0 1 - - - - - - - -
\ No newline at end of file diff --git a/src/picknik_ur_mock_hw_config/meshes/table.dae b/src/picknik_ur_mock_hw_config/meshes/table.dae deleted file mode 100644 index 7b850f9e..00000000 --- a/src/picknik_ur_mock_hw_config/meshes/table.dae +++ /dev/null @@ -1,193 +0,0 @@ - - - - - Blender User - Blender 3.6.1 commit date:2023-07-17, commit time:12:50, hash:8bda729ef4dc - - 2023-07-31T15:47:27 - 2023-07-31T15:47:27 - - Z_UP - - - - - - - table - - - - - table-surface - - - - - - 0 0 0 1 - - - - - - 1 - - - 1.45 - - - - - - - - - - table - - - - - table-surface - - - - - - 0 0 0 1 - - - - - - 1.45 - - - - - - - - - - table - - - - - table-surface - - - - - - 0 0 0 1 - - - - - - 1 - - - 1.45 - - - - - - - - - table.png - - - - - - - - - - - - - - - - - - 0.9974064 1.003384 -0.9999999 0.9974064 1.003384 0.9999997 0.9974069 -0.9966153 -0.9999999 0.9974069 -0.9966153 0.9999997 -1.002593 1.003384 -0.9999999 -1.002593 1.003384 0.9999997 -1.002593 -0.9966155 -0.9999999 -1.002593 -0.9966155 0.9999997 0.7272977 -0.8518986 -0.9999999 0.5581111 -0.5734477 -0.9999999 0.5445514 -0.54376 -0.9999999 0.5581113 -0.9447156 -0.9999999 0.3889245 -0.6662648 -0.9999999 0.3550872 -0.6662648 -0.9999999 0.3753896 -0.6365633 -0.9999999 0.3048083 -0.304017 -0.9999999 0.3550873 -0.8518986 -0.9999999 0.3889246 -0.8518986 -0.9999999 0.1859006 -0.3332376 -0.9999999 0.206203 -0.3581125 -0.9999999 0.1723657 -0.3581125 -0.9999999 0.2062031 -0.5437465 -0.9999999 0.1859007 -0.5734478 -0.9999999 0.1723657 -0.5437465 -0.9999999 0.01671409 -0.05478686 -0.9999999 0.1859008 -0.9447157 -0.9999999 -0.01712316 -0.2404208 -0.9999999 0.003179132 -0.2652956 -0.9999999 0.01671409 -0.2404208 -0.9999999 0.003179192 -0.6365634 -0.9999999 -0.0171231 -0.6662649 -0.9999999 0.01671415 -0.6662649 -0.9999999 -0.01712304 -0.8518987 -0.9999999 -0.01712316 -0.05478686 -0.9999999 0.003179132 -0.02508544 -0.9999999 0.01671421 -0.8518987 -0.9999999 -0.1863097 0.03803002 -0.9999999 -0.1660073 0.06773144 -0.9999999 -0.1998447 0.06773144 -0.9999999 -0.1998446 -0.3581126 -0.9999999 -0.1998446 -0.5437465 -0.9999999 -0.1863096 -0.3332377 -0.9999999 -0.1660073 -0.3581126 -0.9999999 -0.1660073 -0.5437465 -0.9999999 -0.1863096 -0.5734478 -0.9999999 -0.1863096 -0.9447157 -0.9999999 -0.3893336 0.3710572 -0.9999999 -0.3690313 0.3461822 -0.9999999 -0.3893336 -0.05478692 -0.9999999 -0.3690313 -0.0250855 -0.9999999 -0.3554962 -0.05478692 -0.9999999 -0.3893336 -0.2404209 -0.9999999 -0.3554962 -0.2404209 -0.9999999 -0.3690312 -0.2652957 -0.9999999 -0.3893334 -0.6662649 -0.9999999 -0.3690311 -0.6365634 -0.9999999 -0.3554961 -0.6662649 -0.9999999 -0.3893334 -0.8518987 -0.9999999 -0.3554961 -0.8518987 -0.9999999 -0.5382177 0.2533653 -0.9999999 -0.5382177 -0.3581126 -0.9999999 -0.5585201 0.2782402 -0.9999999 -0.5720551 0.2533652 -0.9999999 -0.5720551 0.06773138 -0.9999999 -0.5382177 0.06773138 -0.9999999 -0.5585201 0.03802996 -0.9999999 -0.5585201 -0.3332377 -0.9999999 -0.5720551 -0.3581126 -0.9999999 -0.5382176 -0.5437465 -0.9999999 -0.55852 -0.5734478 -0.9999999 -0.7277066 0.5566908 -0.9999999 -0.7277066 0.371057 -0.9999999 -0.7277066 -0.05478698 -0.9999999 -0.7277066 -0.2404209 -0.9999999 -0.7277065 -0.666265 -0.9999999 -0.7277065 -0.8518988 -0.9999999 -0.9104282 0.06773132 -0.9999999 -0.9104282 -0.3581126 -0.9999999 -0.9104281 -0.5437466 -0.9999999 -0.9104284 0.8648431 -0.9999999 -0.9104284 0.6792092 -0.9999999 -0.9104282 0.2533652 -0.9999999 -0.7412418 0.5863923 -0.9999999 -0.7412416 0.3461821 -0.9999999 -0.7412416 -0.02508556 -0.9999999 -0.7412416 -0.2652957 -0.9999999 -0.7412415 -0.6365635 -0.9999999 -0.5720549 -0.5437465 -0.9999999 -0.5585199 -0.9447157 -0.9999999 0.9167863 0.8648434 -0.9999999 0.9167863 0.6792095 -0.9999999 0.9167863 0.2533655 -0.9999999 0.9167864 0.06773155 -0.9999999 0.9167866 -0.3581124 -0.9999999 0.9167866 -0.5437464 -0.9999999 0.7475997 0.9576603 -0.9999999 0.5784133 0.8648434 -0.9999999 0.5784133 0.6792095 -0.9999999 0.7272974 0.5566911 -0.9999999 0.7272974 0.3710573 -0.9999999 0.7272976 -0.05478674 -0.9999999 0.7272977 -0.2404207 -0.9999999 0.7272977 -0.6662648 -0.9999999 0.7475998 0.5863925 -0.9999999 0.7475999 0.3461823 -0.9999999 0.7475999 -0.02508533 -0.9999999 0.7475999 -0.2652955 -0.9999999 0.7476 -0.6365633 -0.9999999 0.5445762 -0.5437464 -0.9999999 0.5445759 0.6792095 -0.9999999 0.5581109 0.649508 -0.9999999 0.5445759 0.2533654 -0.9999999 0.558111 0.2782403 -0.9999999 0.5784133 0.2533654 -0.9999999 0.5445761 0.06773149 -0.9999999 0.5784134 0.06773149 -0.9999999 0.558111 0.03803008 -0.9999999 0.5445762 -0.3581125 -0.9999999 0.558111 -0.3332375 -0.9999999 0.5784135 -0.3581125 -0.9999999 0.5784135 -0.5437464 -0.9999999 0.3889244 0.5566911 -0.9999999 0.3889244 -0.0547868 -0.9999999 0.3753896 -0.2652956 -0.9999999 0.3889245 -0.2404208 -0.9999999 0.3550872 -0.2404208 -0.9999999 0.3753894 0.5863925 -0.9999999 0.3550871 0.5566911 -0.9999999 0.3550871 0.3710573 -0.9999999 0.3889244 0.3710573 -0.9999999 0.3753895 0.3461823 -0.9999999 0.3753895 -0.02508538 -0.9999999 0.3550871 -0.0547868 -0.9999999 0.5445759 0.8648434 -0.9999999 0.3753894 0.9576603 -0.9999999 0.2921445 -0.2749515 -0.9999999 0.1723655 0.6792094 -0.9999999 0.2062028 0.6792094 -0.9999999 0.1859005 0.649508 -0.9999999 0.1859005 0.2782403 -0.9999999 0.1723656 0.2533653 -0.9999999 0.2062029 0.2533653 -0.9999999 0.2062028 0.8648433 -0.9999999 0.1723655 0.8648433 -0.9999999 0.2062029 0.06773149 -0.9999999 0.1859006 0.03803002 -0.9999999 0.1723656 0.06773144 -0.9999999 -0.01712328 0.3710572 -0.9999999 -0.01712328 0.5566911 -0.9999999 0.003179013 0.5863924 -0.9999999 0.01671397 0.5566911 -0.9999999 0.01671403 0.3710572 -0.9999999 0.003179073 0.3461822 -0.9999999 0.003178954 0.9576602 -0.9999999 -0.1998448 0.8648433 -0.9999999 -0.1660075 0.8648433 -0.9999999 -0.1660075 0.6792094 -0.9999999 -0.1863098 0.649508 -0.9999999 -0.1863098 0.2782402 -0.9999999 -0.1660074 0.2533653 -0.9999999 -0.3554964 0.5566911 -0.9999999 -0.3554963 0.3710572 -0.9999999 -0.1998447 0.2533653 -0.9999999 -0.1998448 0.6792094 -0.9999999 -0.5382179 0.8648433 -0.9999999 -0.5382179 0.6792094 -0.9999999 -0.3893337 0.5566911 -0.9999999 -0.3690314 0.5863924 -0.9999999 -0.5720552 0.6792094 -0.9999999 -0.5585203 0.649508 -0.9999999 -0.7412419 0.9576601 -0.9999999 -0.5720552 0.8648433 -0.9999999 -0.3690314 0.9576602 -0.9999999 0.9167863 0.8648434 0.9999997 0.9167863 0.6792095 0.9999997 0.9167863 0.2533655 0.9999997 0.9167864 0.06773155 0.9999997 0.9167866 -0.3581124 0.9999997 0.9167866 -0.5437464 0.9999997 0.7272974 0.5566911 0.9999997 0.7272974 0.3710573 0.9999997 0.7272976 -0.05478674 0.9999997 0.7272977 -0.2404207 0.9999997 0.7272977 -0.6662648 0.9999997 0.7272977 -0.8518986 0.9999997 0.7475998 0.5863925 0.9999997 0.7475999 0.3461823 0.9999997 0.7475999 -0.02508533 0.9999997 0.7475999 -0.2652955 0.9999997 0.7476 -0.6365633 0.9999997 0.5445759 0.2533654 0.9999997 0.5445762 -0.3581125 0.9999997 0.558111 0.2782403 0.9999997 0.5784133 0.2533654 0.9999997 0.5784134 0.06773149 0.9999997 0.5445761 0.06773149 0.9999997 0.558111 0.03803008 0.9999997 0.558111 -0.3332375 0.9999997 0.5784135 -0.3581125 0.9999997 0.5784135 -0.5437464 0.9999997 0.5445762 -0.5437464 0.9999997 0.5581111 -0.5734477 0.9999997 0.3889245 -0.2404208 0.9999997 0.3550873 -0.8518986 0.9999997 0.3889246 -0.8518986 0.9999997 0.3889244 0.3710573 0.9999997 0.3753895 0.3461823 0.9999997 0.3889244 -0.0547868 0.9999997 0.3753895 -0.02508538 0.9999997 0.3550871 -0.0547868 0.9999997 0.3550872 -0.2404208 0.9999997 0.3753896 -0.2652956 0.9999997 0.3889245 -0.6662648 0.9999997 0.3753896 -0.6365633 0.9999997 0.3550872 -0.6662648 0.9999997 0.5581113 -0.9447156 0.9999997 0.1723656 0.06773144 0.9999997 0.2062029 0.06773149 0.9999997 0.1859006 0.03803002 0.9999997 0.1859006 -0.3332376 0.9999997 0.206203 -0.3581125 0.9999997 0.2062031 -0.5437465 0.9999997 0.1859007 -0.5734478 0.9999997 0.01671409 -0.05478686 0.9999997 0.1723657 -0.3581125 0.9999997 0.1723657 -0.5437465 0.9999997 -0.01712316 -0.05478686 0.9999997 0.01671409 -0.2404208 0.9999997 -0.01712316 -0.2404208 0.9999997 0.003179132 -0.2652956 0.9999997 0.003179132 -0.02508544 0.9999997 0.003179192 -0.6365634 0.9999997 0.01671415 -0.6662649 0.9999997 0.01671421 -0.8518987 0.9999997 0.1859008 -0.9447157 0.9999997 -0.1660073 -0.3581126 0.9999997 -0.0171231 -0.6662649 0.9999997 -0.01712304 -0.8518987 0.9999997 -0.1998446 -0.3581126 0.9999997 -0.1863096 -0.3332377 0.9999997 -0.1660073 -0.5437465 0.9999997 -0.1998446 -0.5437465 0.9999997 -0.1863096 -0.5734478 0.9999997 -0.3893334 -0.6662649 0.9999997 -0.3690311 -0.6365634 0.9999997 -0.3893334 -0.8518987 0.9999997 -0.3554961 -0.8518987 0.9999997 -0.3554961 -0.6662649 0.9999997 -0.55852 -0.5734478 0.9999997 -0.5382176 -0.5437465 0.9999997 -0.7277065 -0.8518988 0.9999997 -0.5585199 -0.9447157 0.9999997 -0.1863096 -0.9447157 0.9999997 0.7475997 0.9576603 0.9999997 0.5784133 0.6792095 0.9999997 0.5581109 0.649508 0.9999997 0.5784133 0.8648434 0.9999997 0.5445759 0.8648434 0.9999997 0.3889244 0.5566911 0.9999997 0.3753894 0.5863925 0.9999997 0.5445759 0.6792095 0.9999997 0.3753894 0.9576603 0.9999997 0.2062028 0.6792094 0.9999997 0.2062028 0.8648433 0.9999997 0.3550871 0.5566911 0.9999997 0.3550871 0.3710573 0.9999997 0.1723656 0.2533653 0.9999997 0.1723655 0.8648433 0.9999997 0.1723655 0.6792094 0.9999997 0.1859005 0.649508 0.9999997 0.1859005 0.2782403 0.9999997 0.2062029 0.2533653 0.9999997 0.01671403 0.3710572 0.9999997 0.01671397 0.5566911 0.9999997 0.003179013 0.5863924 0.9999997 -0.01712328 0.5566911 0.9999997 -0.01712328 0.3710572 0.9999997 0.003179073 0.3461822 0.9999997 -0.1660075 0.8648433 0.9999997 -0.1998448 0.6792094 0.9999997 -0.1660075 0.6792094 0.9999997 -0.1863098 0.649508 0.9999997 -0.1863098 0.2782402 0.9999997 -0.1998447 0.2533653 0.9999997 -0.1660074 0.2533653 0.9999997 -0.1998447 0.06773144 0.9999997 -0.1998448 0.8648433 0.9999997 -0.1660073 0.06773144 0.9999997 -0.1863097 0.03803002 0.9999997 0.003178954 0.9576602 0.9999997 -0.3893337 0.5566911 0.9999997 -0.3893336 -0.05478692 0.9999997 -0.3690314 0.5863924 0.9999997 -0.3554964 0.5566911 0.9999997 -0.3554963 0.3710572 0.9999997 -0.3893336 0.3710572 0.9999997 -0.3690313 0.3461822 0.9999997 -0.3690313 -0.0250855 0.9999997 -0.3554962 -0.05478692 0.9999997 -0.3554962 -0.2404209 0.9999997 -0.3893336 -0.2404209 0.9999997 -0.3690312 -0.2652957 0.9999997 -0.5382179 0.6792094 0.9999997 -0.5382177 0.06773138 0.9999997 -0.5382179 0.8648433 0.9999997 -0.5720552 0.8648433 0.9999997 -0.5720552 0.6792094 0.9999997 -0.5585203 0.649508 0.9999997 -0.5382177 0.2533653 0.9999997 -0.5585201 0.2782402 0.9999997 -0.5720551 0.2533652 0.9999997 -0.5720551 0.06773138 0.9999997 -0.5585201 0.03802996 0.9999997 -0.5382177 -0.3581126 0.9999997 -0.5585201 -0.3332377 0.9999997 -0.5720551 -0.3581126 0.9999997 -0.7277066 -0.2404209 0.9999997 -0.7277066 0.5566908 0.9999997 -0.7277066 0.371057 0.9999997 -0.7277066 -0.05478698 0.9999997 -0.5720549 -0.5437465 0.9999997 -0.7277065 -0.666265 0.9999997 -0.9104282 0.06773132 0.9999997 -0.9104282 -0.3581126 0.9999997 -0.9104281 -0.5437466 0.9999997 -0.9104284 0.8648431 0.9999997 -0.9104284 0.6792092 0.9999997 -0.9104282 0.2533652 0.9999997 -0.7412419 0.9576601 0.9999997 -0.7412418 0.5863923 0.9999997 -0.7412416 0.3461821 0.9999997 -0.7412416 -0.02508556 0.9999997 -0.7412416 -0.2652957 0.9999997 -0.7412415 -0.6365635 0.9999997 -0.3690314 0.9576602 0.9999997 -1.00235 1.00303 44.88305 -1.00235 -0.9987009 44.88305 -1.00235 1.00303 4.982971 -1.00235 -0.9987009 4.982971 0.99997 -0.9987009 44.88305 0.99997 -0.9987009 4.982971 0.99997 1.00303 44.88305 0.99997 1.00303 4.982971 0.881444 -0.8384312 45.89908 0.881444 -0.8384312 44.47127 0.8918015 -0.8394005 45.89908 0.8918015 -0.8394005 44.47127 0.9017611 -0.8422713 45.89908 0.9017611 -0.8422713 44.47127 0.9109398 -0.8469332 45.89908 0.9109398 -0.8469332 44.47127 0.918985 -0.853207 45.89908 0.918985 -0.853207 44.47127 0.9255877 -0.8608518 45.89908 0.9255877 -0.8608518 44.47127 0.9304938 -0.8695735 45.89908 0.9304938 -0.8695735 44.47127 0.933515 -0.8790373 45.89908 0.933515 -0.8790373 44.47127 0.9345351 -0.8888792 45.89908 0.9345351 -0.8888792 44.47127 0.933515 -0.8987211 45.89908 0.933515 -0.8987211 44.47127 0.9304938 -0.9081848 45.89908 0.9304938 -0.9081848 44.47127 0.9255877 -0.9169066 45.89908 0.9255877 -0.9169066 44.47127 0.918985 -0.9245514 45.89908 0.918985 -0.9245514 44.47127 0.9109398 -0.9308252 45.89908 0.9109398 -0.9308252 44.47127 0.9017611 -0.9354871 45.89908 0.9017611 -0.9354871 44.47127 0.8918015 -0.9383579 45.89908 0.8918015 -0.9383579 44.47127 0.881444 -0.9393272 45.89908 0.881444 -0.9393272 44.47127 0.8710864 -0.9383579 45.89908 0.8710864 -0.9383579 44.47127 0.8611268 -0.9354871 45.89908 0.8611268 -0.9354871 44.47127 0.8519481 -0.9308252 45.89908 0.8519481 -0.9308252 44.47127 0.8439029 -0.9245514 45.89908 0.8439029 -0.9245514 44.47127 0.8373003 -0.9169066 45.89908 0.8373003 -0.9169066 44.47127 0.8323941 -0.9081848 45.89908 0.8323941 -0.9081848 44.47127 0.829373 -0.8987211 45.89908 0.829373 -0.8987211 44.47127 0.8283528 -0.8888792 45.89908 0.8283528 -0.8888792 44.47127 0.829373 -0.8790373 45.89908 0.829373 -0.8790373 44.47127 0.8323941 -0.8695735 45.89908 0.8323941 -0.8695735 44.47127 0.8373003 -0.8608518 45.89908 0.8373003 -0.8608518 44.47127 0.8439029 -0.853207 45.89908 0.8439029 -0.853207 44.47127 0.8519481 -0.8469332 45.89908 0.8519481 -0.8469332 44.47127 0.8611268 -0.8422713 45.89908 0.8611268 -0.8422713 44.47127 0.8710864 -0.8394005 45.89908 0.8710864 -0.8394005 44.47127 0.8814441 -0.7947795 48.02053 0.8814441 -0.7947795 45.91701 0.9007638 -0.7965876 48.02053 0.9007638 -0.7965876 45.91701 0.9193412 -0.8019424 48.02053 0.9193412 -0.8019424 45.91701 0.9364621 -0.8106381 48.02053 0.9364621 -0.8106381 45.91701 0.9514688 -0.8223406 48.02053 0.9514688 -0.8223406 45.91701 0.9637844 -0.8366002 48.02053 0.9637844 -0.8366002 45.91701 0.9729357 -0.8528688 48.02053 0.9729357 -0.8528688 45.91701 0.9785711 -0.8705213 48.02053 0.9785711 -0.8705213 45.91701 0.9804739 -0.8888792 48.02053 0.9804739 -0.8888792 45.91701 0.9785711 -0.9072372 48.02053 0.9785711 -0.9072372 45.91701 0.9729357 -0.9248896 48.02053 0.9729357 -0.9248896 45.91701 0.9637844 -0.9411582 48.02053 0.9637844 -0.9411582 45.91701 0.9514688 -0.9554178 48.02053 0.9514688 -0.9554178 45.91701 0.9364621 -0.9671204 48.02053 0.9364621 -0.9671204 45.91701 0.9193412 -0.9758161 48.02053 0.9193412 -0.9758161 45.91701 0.9007638 -0.9811709 48.02053 0.9007638 -0.9811709 45.91701 0.8814441 -0.9829789 48.02053 0.8814441 -0.9829789 45.91701 0.8621243 -0.9811709 48.02053 0.8621243 -0.9811709 45.91701 0.8435469 -0.9758161 48.02053 0.8435469 -0.9758161 45.91701 0.826426 -0.9671204 48.02053 0.826426 -0.9671204 45.91701 0.8114193 -0.9554178 48.02053 0.8114193 -0.9554178 45.91701 0.7991037 -0.9411582 48.02053 0.7991037 -0.9411582 45.91701 0.7899523 -0.9248896 48.02053 0.7899523 -0.9248896 45.91701 0.784317 -0.9072372 48.02053 0.784317 -0.9072372 45.91701 0.7824141 -0.8888792 48.02053 0.7824141 -0.8888792 45.91701 0.784317 -0.8705213 48.02053 0.784317 -0.8705213 45.91701 0.7899523 -0.8528688 48.02053 0.7899523 -0.8528688 45.91701 0.7991037 -0.8366002 48.02053 0.7991037 -0.8366002 45.91701 0.8114193 -0.8223406 48.02053 0.8114193 -0.8223406 45.91701 0.826426 -0.8106381 48.02053 0.826426 -0.8106381 45.91701 0.8435469 -0.8019424 48.02053 0.8435469 -0.8019424 45.91701 0.8621243 -0.7965876 48.02053 0.8621243 -0.7965876 45.91701 -0.8868827 -0.8384312 45.89908 -0.8868827 -0.8384312 44.47127 -0.8765251 -0.8394005 45.89908 -0.8765251 -0.8394005 44.47127 -0.8665655 -0.8422713 45.89908 -0.8665655 -0.8422713 44.47127 -0.8573868 -0.8469332 45.89908 -0.8573868 -0.8469332 44.47127 -0.8493416 -0.853207 45.89908 -0.8493416 -0.853207 44.47127 -0.842739 -0.8608518 45.89908 -0.842739 -0.8608518 44.47127 -0.8378328 -0.8695735 45.89908 -0.8378328 -0.8695735 44.47127 -0.8348116 -0.8790373 45.89908 -0.8348116 -0.8790373 44.47127 -0.8337915 -0.8888792 45.89908 -0.8337915 -0.8888792 44.47127 -0.8348116 -0.8987211 45.89908 -0.8348116 -0.8987211 44.47127 -0.8378328 -0.9081848 45.89908 -0.8378328 -0.9081848 44.47127 -0.842739 -0.9169066 45.89908 -0.842739 -0.9169066 44.47127 -0.8493416 -0.9245514 45.89908 -0.8493416 -0.9245514 44.47127 -0.8573868 -0.9308252 45.89908 -0.8573868 -0.9308252 44.47127 -0.8665655 -0.9354871 45.89908 -0.8665655 -0.9354871 44.47127 -0.8765251 -0.9383579 45.89908 -0.8765251 -0.9383579 44.47127 -0.8868827 -0.9393272 45.89908 -0.8868827 -0.9393272 44.47127 -0.8972402 -0.9383579 45.89908 -0.8972402 -0.9383579 44.47127 -0.9071998 -0.9354871 45.89908 -0.9071998 -0.9354871 44.47127 -0.9163786 -0.9308252 45.89908 -0.9163786 -0.9308252 44.47127 -0.9244238 -0.9245514 45.89908 -0.9244238 -0.9245514 44.47127 -0.9310263 -0.9169066 45.89908 -0.9310263 -0.9169066 44.47127 -0.9359325 -0.9081848 45.89908 -0.9359325 -0.9081848 44.47127 -0.9389537 -0.8987211 45.89908 -0.9389537 -0.8987211 44.47127 -0.9399738 -0.8888792 45.89908 -0.9399738 -0.8888792 44.47127 -0.9389537 -0.8790373 45.89908 -0.9389537 -0.8790373 44.47127 -0.9359325 -0.8695735 45.89908 -0.9359325 -0.8695735 44.47127 -0.9310263 -0.8608518 45.89908 -0.9310263 -0.8608518 44.47127 -0.9244238 -0.853207 45.89908 -0.9244238 -0.853207 44.47127 -0.9163786 -0.8469332 45.89908 -0.9163786 -0.8469332 44.47127 -0.9071998 -0.8422713 45.89908 -0.9071998 -0.8422713 44.47127 -0.8972402 -0.8394005 45.89908 -0.8972402 -0.8394005 44.47127 -0.8868826 -0.7947795 48.02053 -0.8868826 -0.7947795 45.91701 -0.8675628 -0.7965876 48.02053 -0.8675628 -0.7965876 45.91701 -0.8489854 -0.8019424 48.02053 -0.8489854 -0.8019424 45.91701 -0.8318645 -0.8106381 48.02053 -0.8318645 -0.8106381 45.91701 -0.8168578 -0.8223406 48.02053 -0.8168578 -0.8223406 45.91701 -0.8045423 -0.8366002 48.02053 -0.8045423 -0.8366002 45.91701 -0.7953909 -0.8528688 48.02053 -0.7953909 -0.8528688 45.91701 -0.7897555 -0.8705213 48.02053 -0.7897555 -0.8705213 45.91701 -0.7878527 -0.8888792 48.02053 -0.7878527 -0.8888792 45.91701 -0.7897555 -0.9072372 48.02053 -0.7897555 -0.9072372 45.91701 -0.7953909 -0.9248896 48.02053 -0.7953909 -0.9248896 45.91701 -0.8045423 -0.9411582 48.02053 -0.8045423 -0.9411582 45.91701 -0.8168578 -0.9554178 48.02053 -0.8168578 -0.9554178 45.91701 -0.8318645 -0.9671204 48.02053 -0.8318645 -0.9671204 45.91701 -0.8489854 -0.9758161 48.02053 -0.8489854 -0.9758161 45.91701 -0.8675628 -0.9811709 48.02053 -0.8675628 -0.9811709 45.91701 -0.8868826 -0.9829789 48.02053 -0.8868826 -0.9829789 45.91701 -0.9062024 -0.9811709 48.02053 -0.9062024 -0.9811709 45.91701 -0.9247797 -0.9758161 48.02053 -0.9247797 -0.9758161 45.91701 -0.9419007 -0.9671204 48.02053 -0.9419007 -0.9671204 45.91701 -0.9569073 -0.9554178 48.02053 -0.9569073 -0.9554178 45.91701 -0.9692229 -0.9411582 48.02053 -0.9692229 -0.9411582 45.91701 -0.9783743 -0.9248896 48.02053 -0.9783743 -0.9248896 45.91701 -0.9840096 -0.9072372 48.02053 -0.9840096 -0.9072372 45.91701 -0.9859125 -0.8888792 48.02053 -0.9859125 -0.8888792 45.91701 -0.9840096 -0.8705213 48.02053 -0.9840096 -0.8705213 45.91701 -0.9783743 -0.8528688 48.02053 -0.9783743 -0.8528688 45.91701 -0.9692229 -0.8366002 48.02053 -0.9692229 -0.8366002 45.91701 -0.9569073 -0.8223406 48.02053 -0.9569073 -0.8223406 45.91701 -0.9419007 -0.8106381 48.02053 -0.9419007 -0.8106381 45.91701 -0.9247797 -0.8019424 48.02053 -0.9247797 -0.8019424 45.91701 -0.9062024 -0.7965876 48.02053 -0.9062024 -0.7965876 45.91701 -0.8868827 0.936083 45.89908 -0.8868827 0.936083 44.47127 -0.8765251 0.9351136 45.89908 -0.8765251 0.9351136 44.47127 -0.8665655 0.9322429 45.89908 -0.8665655 0.9322429 44.47127 -0.8573868 0.927581 45.89908 -0.8573868 0.927581 44.47127 -0.8493416 0.9213071 45.89908 -0.8493416 0.9213071 44.47127 -0.842739 0.9136624 45.89908 -0.842739 0.9136624 44.47127 -0.8378328 0.9049406 45.89908 -0.8378328 0.9049406 44.47127 -0.8348116 0.8954769 45.89908 -0.8348116 0.8954769 44.47127 -0.8337915 0.885635 45.89908 -0.8337915 0.885635 44.47127 -0.8348116 0.875793 45.89908 -0.8348116 0.875793 44.47127 -0.8378328 0.8663294 45.89908 -0.8378328 0.8663294 44.47127 -0.842739 0.8576076 45.89908 -0.842739 0.8576076 44.47127 -0.8493416 0.8499628 45.89908 -0.8493416 0.8499628 44.47127 -0.8573868 0.843689 45.89908 -0.8573868 0.843689 44.47127 -0.8665655 0.8390271 45.89908 -0.8665655 0.8390271 44.47127 -0.8765251 0.8361563 45.89908 -0.8765251 0.8361563 44.47127 -0.8868827 0.835187 45.89908 -0.8868827 0.835187 44.47127 -0.8972402 0.8361563 45.89908 -0.8972402 0.8361563 44.47127 -0.9071998 0.8390271 45.89908 -0.9071998 0.8390271 44.47127 -0.9163786 0.843689 45.89908 -0.9163786 0.843689 44.47127 -0.9244238 0.8499628 45.89908 -0.9244238 0.8499628 44.47127 -0.9310263 0.8576076 45.89908 -0.9310263 0.8576076 44.47127 -0.9359325 0.8663294 45.89908 -0.9359325 0.8663294 44.47127 -0.9389537 0.875793 45.89908 -0.9389537 0.875793 44.47127 -0.9399738 0.885635 45.89908 -0.9399738 0.885635 44.47127 -0.9389537 0.8954769 45.89908 -0.9389537 0.8954769 44.47127 -0.9359325 0.9049406 45.89908 -0.9359325 0.9049406 44.47127 -0.9310263 0.9136624 45.89908 -0.9310263 0.9136624 44.47127 -0.9244238 0.9213071 45.89908 -0.9244238 0.9213071 44.47127 -0.9163786 0.927581 45.89908 -0.9163786 0.927581 44.47127 -0.9071998 0.9322429 45.89908 -0.9071998 0.9322429 44.47127 -0.8972402 0.9351136 45.89908 -0.8972402 0.9351136 44.47127 -0.8868826 0.9797347 48.02053 -0.8868826 0.9797347 45.91701 -0.8675628 0.9779266 48.02053 -0.8675628 0.9779266 45.91701 -0.8489854 0.9725717 48.02053 -0.8489854 0.9725717 45.91701 -0.8318645 0.963876 48.02053 -0.8318645 0.963876 45.91701 -0.8168578 0.9521735 48.02053 -0.8168578 0.9521735 45.91701 -0.8045423 0.9379139 48.02053 -0.8045423 0.9379139 45.91701 -0.7953909 0.9216454 48.02053 -0.7953909 0.9216454 45.91701 -0.7897555 0.9039929 48.02053 -0.7897555 0.9039929 45.91701 -0.7878527 0.885635 48.02053 -0.7878527 0.885635 45.91701 -0.7897555 0.8672769 48.02053 -0.7897555 0.8672769 45.91701 -0.7953909 0.8496245 48.02053 -0.7953909 0.8496245 45.91701 -0.8045423 0.8333559 48.02053 -0.8045423 0.8333559 45.91701 -0.8168578 0.8190964 48.02053 -0.8168578 0.8190964 45.91701 -0.8318645 0.8073939 48.02053 -0.8318645 0.8073939 45.91701 -0.8489854 0.7986981 48.02053 -0.8489854 0.7986981 45.91701 -0.8675628 0.7933433 48.02053 -0.8675628 0.7933433 45.91701 -0.8868826 0.7915352 48.02053 -0.8868826 0.7915352 45.91701 -0.9062024 0.7933433 48.02053 -0.9062024 0.7933433 45.91701 -0.9247797 0.7986981 48.02053 -0.9247797 0.7986981 45.91701 -0.9419007 0.8073939 48.02053 -0.9419007 0.8073939 45.91701 -0.9569073 0.8190964 48.02053 -0.9569073 0.8190964 45.91701 -0.9692229 0.8333559 48.02053 -0.9692229 0.8333559 45.91701 -0.9783743 0.8496245 48.02053 -0.9783743 0.8496245 45.91701 -0.9840096 0.8672769 48.02053 -0.9840096 0.8672769 45.91701 -0.9859125 0.885635 48.02053 -0.9859125 0.885635 45.91701 -0.9840096 0.9039929 48.02053 -0.9840096 0.9039929 45.91701 -0.9783743 0.9216454 48.02053 -0.9783743 0.9216454 45.91701 -0.9692229 0.9379139 48.02053 -0.9692229 0.9379139 45.91701 -0.9569073 0.9521735 48.02053 -0.9569073 0.9521735 45.91701 -0.9419007 0.963876 48.02053 -0.9419007 0.963876 45.91701 -0.9247797 0.9725717 48.02053 -0.9247797 0.9725717 45.91701 -0.9062024 0.9779266 48.02053 -0.9062024 0.9779266 45.91701 0.881444 0.936083 45.89908 0.881444 0.936083 44.47127 0.8918015 0.9351136 45.89908 0.8918015 0.9351136 44.47127 0.9017611 0.9322429 45.89908 0.9017611 0.9322429 44.47127 0.9109398 0.927581 45.89908 0.9109398 0.927581 44.47127 0.918985 0.9213071 45.89908 0.918985 0.9213071 44.47127 0.9255877 0.9136624 45.89908 0.9255877 0.9136624 44.47127 0.9304938 0.9049406 45.89908 0.9304938 0.9049406 44.47127 0.933515 0.8954769 45.89908 0.933515 0.8954769 44.47127 0.9345351 0.885635 45.89908 0.9345351 0.885635 44.47127 0.933515 0.875793 45.89908 0.933515 0.875793 44.47127 0.9304938 0.8663294 45.89908 0.9304938 0.8663294 44.47127 0.9255877 0.8576076 45.89908 0.9255877 0.8576076 44.47127 0.918985 0.8499628 45.89908 0.918985 0.8499628 44.47127 0.9109398 0.843689 45.89908 0.9109398 0.843689 44.47127 0.9017611 0.8390271 45.89908 0.9017611 0.8390271 44.47127 0.8918015 0.8361563 45.89908 0.8918015 0.8361563 44.47127 0.881444 0.835187 45.89908 0.881444 0.835187 44.47127 0.8710864 0.8361563 45.89908 0.8710864 0.8361563 44.47127 0.8611268 0.8390271 45.89908 0.8611268 0.8390271 44.47127 0.8519481 0.843689 45.89908 0.8519481 0.843689 44.47127 0.8439029 0.8499628 45.89908 0.8439029 0.8499628 44.47127 0.8373003 0.8576076 45.89908 0.8373003 0.8576076 44.47127 0.8323941 0.8663294 45.89908 0.8323941 0.8663294 44.47127 0.829373 0.875793 45.89908 0.829373 0.875793 44.47127 0.8283528 0.885635 45.89908 0.8283528 0.885635 44.47127 0.829373 0.8954769 45.89908 0.829373 0.8954769 44.47127 0.8323941 0.9049406 45.89908 0.8323941 0.9049406 44.47127 0.8373003 0.9136624 45.89908 0.8373003 0.9136624 44.47127 0.8439029 0.9213071 45.89908 0.8439029 0.9213071 44.47127 0.8519481 0.927581 45.89908 0.8519481 0.927581 44.47127 0.8611268 0.9322429 45.89908 0.8611268 0.9322429 44.47127 0.8710864 0.9351136 45.89908 0.8710864 0.9351136 44.47127 0.8814441 0.9797347 48.02053 0.8814441 0.9797347 45.91701 0.9007638 0.9779266 48.02053 0.9007638 0.9779266 45.91701 0.9193412 0.9725717 48.02053 0.9193412 0.9725717 45.91701 0.9364621 0.963876 48.02053 0.9364621 0.963876 45.91701 0.9514688 0.9521735 48.02053 0.9514688 0.9521735 45.91701 0.9637844 0.9379139 48.02053 0.9637844 0.9379139 45.91701 0.9729357 0.9216454 48.02053 0.9729357 0.9216454 45.91701 0.9785711 0.9039929 48.02053 0.9785711 0.9039929 45.91701 0.9804739 0.885635 48.02053 0.9804739 0.885635 45.91701 0.9785711 0.8672769 48.02053 0.9785711 0.8672769 45.91701 0.9729357 0.8496245 48.02053 0.9729357 0.8496245 45.91701 0.9637844 0.8333559 48.02053 0.9637844 0.8333559 45.91701 0.9514688 0.8190964 48.02053 0.9514688 0.8190964 45.91701 0.9364621 0.8073939 48.02053 0.9364621 0.8073939 45.91701 0.9193412 0.7986981 48.02053 0.9193412 0.7986981 45.91701 0.9007638 0.7933433 48.02053 0.9007638 0.7933433 45.91701 0.8814441 0.7915352 48.02053 0.8814441 0.7915352 45.91701 0.8621243 0.7933433 48.02053 0.8621243 0.7933433 45.91701 0.8435469 0.7986981 48.02053 0.8435469 0.7986981 45.91701 0.826426 0.8073939 48.02053 0.826426 0.8073939 45.91701 0.8114193 0.8190964 48.02053 0.8114193 0.8190964 45.91701 0.7991037 0.8333559 48.02053 0.7991037 0.8333559 45.91701 0.7899523 0.8496245 48.02053 0.7899523 0.8496245 45.91701 0.784317 0.8672769 48.02053 0.784317 0.8672769 45.91701 0.7824141 0.885635 48.02053 0.7824141 0.885635 45.91701 0.784317 0.9039929 48.02053 0.784317 0.9039929 45.91701 0.7899523 0.9216454 48.02053 0.7899523 0.9216454 45.91701 0.7991037 0.9379139 48.02053 0.7991037 0.9379139 45.91701 0.8114193 0.9521735 48.02053 0.8114193 0.9521735 45.91701 0.826426 0.963876 48.02053 0.826426 0.963876 45.91701 0.8435469 0.9725717 48.02053 0.8435469 0.9725717 45.91701 0.8621243 0.9779266 48.02053 0.8621243 0.9779266 45.91701 -0.9381864 -0.9015545 -1.574644 -0.9381864 -0.9015545 6.216695 -0.9260033 -0.9038572 -1.574644 -0.9260033 -0.9038572 6.216695 -0.9156749 -0.9104148 -1.574644 -0.9156749 -0.9104148 6.216695 -0.9087737 -0.920229 -1.574644 -0.9087737 -0.920229 6.216695 -0.9063503 -0.9318056 -1.574644 -0.9063503 -0.9318056 6.216695 -0.9087737 -0.9433822 -1.574644 -0.9087737 -0.9433822 6.216695 -0.9156749 -0.9531964 -1.574644 -0.9156749 -0.9531964 6.216695 -0.9260033 -0.959754 -1.574644 -0.9260033 -0.959754 6.216695 -0.9381864 -0.9620568 -1.574644 -0.9381864 -0.9620568 6.216695 -0.9503695 -0.959754 -1.574644 -0.9503695 -0.959754 6.216695 -0.9606979 -0.9531964 -1.574644 -0.9606979 -0.9531964 6.216695 -0.9675991 -0.9433822 -1.574644 -0.9675991 -0.9433822 6.216695 -0.9700225 -0.9318056 -1.574644 -0.9700225 -0.9318056 6.216695 -0.9675991 -0.920229 -1.574644 -0.9675991 -0.920229 6.216695 -0.9606979 -0.9104148 -1.574644 -0.9606979 -0.9104148 6.216695 -0.9503695 -0.9038572 -1.574644 -0.9503695 -0.9038572 6.216695 -1.012239 -1.006126 4.844316 -1.012239 -1.006126 4.310675 -1.012239 1.008303 4.844316 -1.012239 1.008303 4.310675 1.002988 -1.006126 4.844316 1.002988 -1.006126 4.310675 1.002988 1.008303 4.844316 1.002988 1.008303 4.310675 0.9322701 -0.9015545 -1.574644 0.9322701 -0.9015545 6.216695 0.9444532 -0.9038572 -1.574644 0.9444532 -0.9038572 6.216695 0.9547815 -0.9104148 -1.574644 0.9547815 -0.9104148 6.216695 0.9616827 -0.920229 -1.574644 0.9616827 -0.920229 6.216695 0.9641062 -0.9318056 -1.574644 0.9641062 -0.9318056 6.216695 0.9616827 -0.9433822 -1.574644 0.9616827 -0.9433822 6.216695 0.9547815 -0.9531964 -1.574644 0.9547815 -0.9531964 6.216695 0.9444532 -0.959754 -1.574644 0.9444532 -0.959754 6.216695 0.9322701 -0.9620568 -1.574644 0.9322701 -0.9620568 6.216695 0.9200869 -0.959754 -1.574644 0.9200869 -0.959754 6.216695 0.9097586 -0.9531964 -1.574644 0.9097586 -0.9531964 6.216695 0.9028574 -0.9433822 -1.574644 0.9028574 -0.9433822 6.216695 0.900434 -0.9318056 -1.574644 0.900434 -0.9318056 6.216695 0.9028574 -0.920229 -1.574644 0.9028574 -0.920229 6.216695 0.9097586 -0.9104148 -1.574644 0.9097586 -0.9104148 6.216695 0.9200869 -0.9038572 -1.574644 0.9200869 -0.9038572 6.216695 0.9322701 0.9619006 -1.574644 0.9322701 0.9619006 6.216695 0.9444532 0.9595978 -1.574644 0.9444532 0.9595978 6.216695 0.9547815 0.9530403 -1.574644 0.9547815 0.9530403 6.216695 0.9616827 0.943226 -1.574644 0.9616827 0.943226 6.216695 0.9641062 0.9316495 -1.574644 0.9641062 0.9316495 6.216695 0.9616827 0.9200729 -1.574644 0.9616827 0.9200729 6.216695 0.9547815 0.9102587 -1.574644 0.9547815 0.9102587 6.216695 0.9444532 0.9037011 -1.574644 0.9444532 0.9037011 6.216695 0.9322701 0.9013983 -1.574644 0.9322701 0.9013983 6.216695 0.9200869 0.9037011 -1.574644 0.9200869 0.9037011 6.216695 0.9097586 0.9102587 -1.574644 0.9097586 0.9102587 6.216695 0.9028574 0.9200729 -1.574644 0.9028574 0.9200729 6.216695 0.900434 0.9316495 -1.574644 0.900434 0.9316495 6.216695 0.9028574 0.943226 -1.574644 0.9028574 0.943226 6.216695 0.9097586 0.9530403 -1.574644 0.9097586 0.9530403 6.216695 0.9200869 0.9595978 -1.574644 0.9200869 0.9595978 6.216695 -0.9381864 0.9619006 -1.574644 -0.9381864 0.9619006 6.216695 -0.9260033 0.9595978 -1.574644 -0.9260033 0.9595978 6.216695 -0.9156749 0.9530403 -1.574644 -0.9156749 0.9530403 6.216695 -0.9087737 0.943226 -1.574644 -0.9087737 0.943226 6.216695 -0.9063503 0.9316495 -1.574644 -0.9063503 0.9316495 6.216695 -0.9087737 0.9200729 -1.574644 -0.9087737 0.9200729 6.216695 -0.9156749 0.9102587 -1.574644 -0.9156749 0.9102587 6.216695 -0.9260033 0.9037011 -1.574644 -0.9260033 0.9037011 6.216695 -0.9381864 0.9013983 -1.574644 -0.9381864 0.9013983 6.216695 -0.9503695 0.9037011 -1.574644 -0.9503695 0.9037011 6.216695 -0.9606979 0.9102587 -1.574644 -0.9606979 0.9102587 6.216695 -0.9675991 0.9200729 -1.574644 -0.9675991 0.9200729 6.216695 -0.9700225 0.9316495 -1.574644 -0.9700225 0.9316495 6.216695 -0.9675991 0.943226 -1.574644 -0.9675991 0.943226 6.216695 -0.9606979 0.9530403 -1.574644 -0.9606979 0.9530403 6.216695 -0.9503695 0.9595978 -1.574644 -0.9503695 0.9595978 6.216695 - - - - - - - - - - 1 2.38419e-7 0 1.19209e-7 -1 0 -1 0 0 -1.19209e-7 1 0 2.37264e-6 0 -1 0 0 -1 -2.37228e-6 0 -1 -1.74191e-6 0 -1 1.36338e-6 0 -1 2.37229e-6 0 -1 -1.22283e-6 0 -1 -1.22284e-6 0 -1 -2.37229e-6 0 -1 1.36338e-6 0 -1 -2.44565e-6 0 1 -2.44568e-6 0 1 -1.18614e-6 0 1 0 0 1 1.18615e-6 0 1 -1.18614e-6 0 1 -1.18615e-6 0 1 0.480981 0.876731 0 1 0 0 0.4809816 -0.8767308 0 -0.4809805 -0.8767313 0 -0.480981 0.876731 0 0.4809805 0.8767313 0 0.4809814 -0.8767308 0 -0.4809811 -0.876731 0 -0.4809809 0.8767311 0 0.4809809 0.8767311 0 0.4809811 -0.876731 0 -0.4809809 -0.8767311 0 -0.4809811 0.876731 0 0.4809811 0.876731 0 0.4809811 -0.876731 0 -0.4809809 0.8767311 0 0.4809808 0.8767312 0 0.4809813 -0.8767309 0 -0.4809801 -0.8767316 0 -0.4809815 0.8767308 0 -0.4809813 -0.8767309 0 -0.4809812 0.8767309 0 0.4809808 0.8767313 0 1 1.60544e-7 0 -0.4809809 -0.8767312 0 -0.4809812 0.8767309 0 0.4809811 0.876731 0 1 3.21087e-7 0 0.4809812 -0.876731 0 -1 -1.60544e-7 0 0.4809811 0.8767311 0 0.4809823 -0.8767303 0 -0.4809808 -0.8767312 0 -1 -3.21087e-7 0 0.4809808 0.8767311 0 1 6.42174e-7 0 0.4809808 -0.8767312 0 -0.4809805 -0.8767313 0 -1 -6.42174e-7 0 -0.4809811 0.876731 0 0.4809809 0.8767311 0 0.4809809 -0.876731 0 -0.4809809 -0.8767312 0 -1 -6.42174e-7 0 -0.4809809 0.8767312 0 0.4809808 0.8767311 0 0.4809808 -0.8767311 0 -0.4809805 -0.8767314 0 -1 -1.60544e-7 0 -0.480981 0.876731 0 0.4809811 -0.8767311 0 -0.4809806 -0.8767312 0 0.4809806 0.8767312 0 0.4809807 -0.8767313 0 -0.4809803 -0.8767315 0 0.4809803 0.8767315 0 1 3.21087e-7 0 0.4809811 -0.876731 0 -0.4809811 -0.876731 0 -1 -6.42174e-7 0 -0.4809803 0.8767315 0 0.4809804 0.8767313 0 1 1.60544e-7 0 0.4809812 -0.876731 0 -0.4809809 -0.876731 0 -1 -3.21087e-7 0 -0.4809806 0.8767312 0 0.4809803 0.8767315 0 0.4809812 -0.876731 0 -0.4809809 -0.8767311 0 -1 -1.60544e-7 0 -0.4809808 0.8767312 0 0.4809808 0.8767312 0 -0.4809807 -0.8767312 0 -0.4809804 0.8767314 0 0.4809818 -0.8767306 0 0.4809804 0.8767314 0 1 1.60544e-7 0 0.480981 -0.876731 0 -0.4809811 0.876731 0 0.4809812 -0.8767309 0 -0.4809809 -0.876731 0 -1 -1.60544e-7 0 1 6.42175e-7 0 0.4809809 -0.8767312 0 -0.4809808 -0.8767312 0 1 6.42174e-7 0 -1 -6.42175e-7 0 0.4809812 0.8767309 0 1 3.21087e-7 0 0.4809815 -0.8767308 0 -0.4809818 -0.8767307 0 -0.4809818 0.8767307 0 0.4809814 0.8767307 0 1 1.60544e-7 0 -1 -3.21087e-7 0 -0.480982 0.8767306 0 0.4809817 -0.8767307 0 -0.4809814 -0.8767308 0 -1 -1.40476e-7 0 0.480982 -0.8767306 0 -0.4809812 -0.8767309 0 -0.4809816 0.8767307 0 0 -1 0 0 1 0 -0.09317559 -0.9956498 0 -0.2769668 -0.9608795 0 -0.4528379 -0.8915929 0 -0.6149438 -0.788571 0 -0.7568067 -0.6536388 0 -0.8715639 -0.490282 0 -0.9526293 -0.3041341 0 -0.9946715 -0.1030955 0 -0.9946715 0.1030955 0 -0.952639 0.3041036 0 -0.871571 0.4902694 0 -0.7568067 0.6536388 0 -0.6149438 0.788571 0 -0.4528379 0.8915929 0 -0.276971 0.9608783 0 -0.09317559 0.9956498 0 0.09317409 0.9956499 0 0.276971 0.9608783 0 0.4528379 0.8915929 0 0.6149359 0.7885771 0 0.7568067 0.6536388 0 0.8715639 0.490282 0 0.9526342 0.3041188 0 0.9946715 0.1030955 0 0.9946697 -0.1031122 0 0.952639 -0.3041036 0 0.8715639 -0.490282 0 0.7568149 -0.6536294 0 0.6149438 -0.788571 0 0.4528445 -0.8915895 0 0.2769668 -0.9608795 0 0.09317559 -0.9956498 0 -0.09318107 -0.9956492 0 -0.2769685 -0.9608791 0 -0.4528392 -0.8915922 0 -0.6149448 -0.7885702 0 -0.7568101 -0.6536349 0 -0.8715708 -0.4902698 0 -0.9526336 -0.3041205 0 -0.9946712 -0.1030977 0 -0.9946712 0.1030977 0 -0.9526334 0.3041214 0 -0.8715708 0.4902698 0 -0.7568029 0.6536433 0 -0.6149485 0.7885674 0 -0.4528369 0.8915935 0 -0.2769685 0.9608791 0 -0.09317874 0.9956494 0 0.09317821 0.9956495 0 0.2769685 0.9608791 0 0.4528369 0.8915935 0 0.6149456 0.7885696 0 0.7568058 0.6536398 0 0.8715708 0.4902698 0 0.9526334 0.3041214 0 0.9946712 0.1030977 0 0.9946712 -0.1030977 0 0.9526336 -0.3041205 0 0.8715708 -0.4902698 0 0.7568101 -0.6536349 0 0.6149448 -0.7885702 0 0.4528392 -0.8915922 0 0.2769701 -0.9608786 0 0.09318 -0.9956493 0 3.55965e-4 0 -1 -0.9946697 0.1031122 0 -0.7568149 0.6536294 0 -0.6149359 0.7885771 0 -0.4528445 0.8915895 0 -0.2769668 0.9608795 0 0.2769668 0.9608795 0 0.6149438 0.788571 0 0.871571 0.4902694 0 0.7568067 -0.6536388 0 0.4528379 -0.8915929 0 0.09317708 -0.9956496 0 -0.7568131 -0.6536314 0 -0.9526354 -0.3041149 0 -0.9946706 -0.1031038 0 -0.9946706 0.1031038 0 -0.8715682 0.4902744 0 -0.7568088 0.6536363 0 -0.6149456 0.7885696 0 -0.09317821 0.9956495 0 0.2769716 0.9608781 0 0.4528345 0.8915947 0 0.7568088 0.6536363 0 0.9526368 0.3041103 0 0.99467 -0.1031099 0 0.8715656 -0.490279 0 0.6149477 -0.788568 0 0.2769685 -0.9608791 0 3.55963e-4 0 -1 -0.09318751 -0.9956486 0 -0.2769556 -0.9608828 0 -0.6149489 -0.7885671 0 -0.7568013 -0.6536449 0 -0.8715659 -0.4902785 0 -0.9526285 -0.3041365 0 -0.9946699 0.1031109 0 -0.9526379 0.3041072 0 -0.871573 0.4902658 0 0.871573 0.4902658 0 0.952633 0.3041225 0 0.9946717 0.1030942 0 0.9526382 -0.3041059 0 0.8715659 -0.4902785 0 0.7568013 -0.6536449 0 0.6149489 -0.7885671 0 0.2769556 -0.9608828 0 0.093189 -0.9956485 0 -0.09317821 -0.9956495 0 -0.2769712 -0.9608782 0 -0.6149466 -0.7885687 0 -0.8715694 -0.4902724 0 -0.9946706 -0.1031041 0 -0.9946708 0.1031029 0 -0.952633 0.3041223 0 -0.6149438 0.788571 0 -0.4528403 0.8915917 0 0.452838 0.8915929 0 0.6149438 0.788571 0 0.9526367 0.3041112 0 0.9946714 0.1030968 0 0.99467 -0.1031102 0 0.8715641 -0.4902816 0 0.6149495 -0.7885665 0 0.2769712 -0.9608782 0 0.09317713 -0.9956496 0 3.55964e-4 0 -1 -0.9946717 0.1030942 0 0.8715659 0.4902785 0 0.7568096 -0.6536355 0 0.09318751 -0.9956486 0 -0.9946713 -0.1030981 0 -0.9946714 0.1030968 0 -0.6149466 0.7885687 0 0.4528403 0.8915917 0 0.952633 0.3041223 0 0.9946713 -0.1030981 0 0.8715694 -0.4902724 0 0.6149466 -0.7885687 0 0.2769728 -0.9608778 0 3.55965e-4 0 -1 0.185724 0.9826021 0 0.5359964 0.8442204 0 0.8180037 0.575213 0 0.9787835 0.2048977 0 0.9787855 -0.2048878 0 0.8180086 -0.5752062 0 0.5360054 -0.8442146 0 0.1857258 -0.9826017 0 -0.1857221 -0.9826023 0 -0.5360009 -0.8442175 0 -0.8180037 -0.575213 0 -0.9787835 -0.2048977 0 -0.9787835 0.2048977 0 -0.8180086 0.5752062 0 -0.5360054 0.8442146 0 -0.1857258 0.9826017 0 0.1857221 0.9826023 0 0.5360009 0.8442175 0 0.9787835 -0.2048977 0 -0.185724 -0.9826021 0 -0.9787855 0.2048878 0 -0.185724 0.9826021 0 -1.18614e-6 0 -1 2.72676e-6 0 -1 -2.72678e-6 0 -1 -1.18614e-6 0 -1 1.07831e-6 0 -1 -2.72678e-6 0 -1 2.72677e-6 0 -1 1.07831e-6 0 -1 0 0 -1 -1.18614e-6 0 -1 0 0 -1 -2.44566e-6 0 -1 2.37229e-6 0 -1 -2.44565e-6 0 -1 1.18615e-6 0 -1 -2.44566e-6 0 -1 -1.07831e-6 0 -1 1.07831e-6 0 -1 1.07831e-6 0 -1 -5.04747e-6 0 -1 -1.18614e-6 0 -1 -1.97691e-6 0 -1 -1.07831e-6 0 -1 1.07831e-6 0 -1 -3.89455e-6 0 -1 2.09813e-6 0 -1 -1.07831e-6 0 -1 1.07831e-6 0 -1 -3.95276e-6 0 -1 2.72677e-6 0 -1 -2.15663e-6 0 -1 5.93073e-6 0 -1 -4.31325e-7 0 -1 7.90768e-6 0 -1 -4.58325e-6 0 -1 -1.18614e-6 0 -1 2.37229e-6 0 -1 1.03413e-6 0 -1 7.90759e-6 0 -1 -1.52775e-6 0 -1 -1.18614e-6 0 -1 1.18614e-6 0 -1 1.07831e-6 0 -1 -2.15662e-6 0 -1 6.20476e-7 0 -1 3.47229e-6 0 -1 -6.46717e-7 0 -1 -1.51867e-6 0 -1 6.96766e-6 0 -1 1.18614e-6 0 -1 -1.97691e-6 0 -1 -2.72676e-6 0 -1 -7.66019e-7 0 -1 -5.04739e-6 0 -1 3.03734e-6 0 -1 -2.68128e-7 0 -1 -1.18614e-6 0 -1 2.44566e-6 0 -1 2.44565e-6 0 -1 1.18615e-6 0 -1 -2.72676e-6 0 -1 -1.18615e-6 0 -1 2.44566e-6 0 -1 2.72676e-6 0 -1 -2.72676e-6 0 -1 4.81891e-7 0 -1 -1.07832e-6 0 -1 -1.07831e-6 0 -1 0 0 -1 2.15663e-6 0 -1 1.83425e-6 0 1 1.83424e-6 0 1 6.81691e-7 0 1 2.44566e-6 0 1 -1.83424e-6 0 1 2.44565e-6 0 1 -1.83424e-6 0 1 0 0 1 -6.81694e-7 0 1 -6.81691e-7 0 1 1.07831e-6 0 1 -6.81695e-7 0 1 -1.83424e-6 0 1 1.83424e-6 0 1 0 0 1 -2.37228e-6 0 1 0 0 1 -6.81694e-7 0 1 1.83424e-6 0 1 2.37229e-6 0 1 -2.15663e-6 0 1 2.15662e-6 0 1 -2.37228e-6 0 1 0 0 1 -2.37228e-6 0 1 -1.83425e-6 0 1 -6.8169e-7 0 1 6.81692e-7 0 1 -2.44566e-6 0 1 1.83424e-6 0 1 -8.78625e-7 0 1 -3.7856e-6 0 1 -8.78623e-7 0 1 7.66019e-7 0 1 6.81692e-7 0 1 -3.78555e-6 0 1 -1.74192e-6 0 1 3.83009e-7 0 1 1.99136e-6 0 1 3.47229e-6 0 1 2.37228e-6 0 1 1.07831e-6 0 1 2.96535e-6 0 1 6.07469e-6 0 1 -6.96763e-6 0 1 5.36255e-7 0 1 2.37229e-6 0 1 2.96538e-6 0 1 -2.44567e-6 0 1 1.83424e-6 0 1 -5.20843e-6 0 1 7.96541e-6 0 1 8.6265e-7 0 1 0.4809811 0.876731 0 0.480981 -0.876731 0 -0.480981 -0.876731 0 0.4809805 0.8767314 0 0.4809815 -0.8767308 0 -0.4809809 -0.8767311 0 0.4809811 -0.876731 0 -0.4809803 -0.8767315 0 -0.4809808 -0.8767312 0 -0.4809813 0.8767309 0 1 1.60544e-7 0 -0.4809814 0.8767309 0 0.4809812 0.876731 0 1 3.21087e-7 0 0.4809811 -0.876731 0 0.4809808 0.8767312 0 0.4809825 -0.8767303 0 -1 -3.21087e-7 0 -0.4809811 0.8767309 0 1 6.42174e-7 0 0.4809802 -0.8767315 0 -0.4809811 -0.876731 0 -1 -6.42174e-7 0 -0.4809811 0.876731 0 0.4809809 0.8767311 0 0.4809808 -0.8767312 0 -0.4809804 -0.8767313 0 -0.4809808 -0.8767313 0 0.4809809 0.8767311 0 0.4809803 -0.8767313 0 -0.4809808 0.8767311 0 0.4809803 0.8767315 0 1 3.21087e-7 0 0.4809808 -0.8767312 0 -0.4809805 -0.8767312 0 -1 -6.42174e-7 0 -0.4809803 0.8767315 0 1 1.60544e-7 0 -0.4809808 -0.8767311 0 -1 -3.21087e-7 0 -0.4809806 0.8767312 0 -0.4809803 0.8767313 0 0.4809811 -0.876731 0 -0.4809808 -0.8767311 0 -1 -1.60544e-7 0 0.4809805 0.8767313 0 0.4809812 -0.8767309 0 1 1.60544e-7 0 0.480981 -0.8767311 0 0.4809808 -0.8767311 0 -0.4809805 -0.8767313 0 -0.4809809 0.8767311 0 -0.4806234 0.8769271 0 0.4809809 0.876731 0 -1 -1.60544e-7 0 1 6.42175e-7 0 -0.4809812 0.876731 0 1 6.42174e-7 0 -1 -6.42175e-7 0 0.4809812 0.8767309 0 1 3.21087e-7 0 0.4809812 -0.8767309 0 -0.4809812 -0.8767309 0 -0.4809818 0.8767307 0 0.4809814 0.8767308 0 1 1.60544e-7 0 -1 -3.21087e-7 0 -0.480982 0.8767306 0 0.4809817 0.8767307 0 0.4809817 -0.8767307 0 -0.4809814 -0.8767309 0 -1 -1.40476e-7 0 -0.4809815 0.8767308 0 0.4809823 -0.8767305 0 -0.4809814 -0.8767309 0 -0.0931766 -0.9956496 0 -0.2769729 -0.9608778 0 -0.4528412 -0.8915913 0 -0.6149463 -0.788569 0 -0.7568085 -0.6536368 0 -0.871573 -0.4902658 0 -0.9526395 -0.3041024 0 -0.9946716 -0.1030951 0 -0.9946716 0.1030951 0 -0.9526297 0.3041328 0 -0.8715659 0.4902785 0 -0.7568085 0.6536368 0 -0.6149463 0.788569 0 -0.4528412 0.8915913 0 -0.2769686 0.960879 0 -0.0931766 0.9956496 0 0.0931766 0.9956496 0 0.2769686 0.960879 0 0.4528477 0.8915879 0 0.6149463 0.788569 0 0.7568166 0.6536273 0 0.9526395 0.3041024 0 0.9946699 0.1031118 0 0.9946716 -0.1030951 0 0.9526345 -0.3041176 0 0.7568085 -0.6536368 0 0.6149384 -0.7885752 0 0.4528412 -0.8915913 0 -7.06502e-4 0 0.9999998 0.002004563 0 0.9999981 7.06502e-4 0 0.9999998 -0.002004563 0 0.9999981 0.2769729 -0.9608778 0 0.09317511 -0.9956498 0 9.12569e-4 0 -0.9999997 -9.67638e-4 0 -0.9999995 -8.30756e-4 0 -0.9999997 0.002043843 0 -0.999998 -9.12574e-4 0 -0.9999996 9.67638e-4 0 -0.9999995 8.30756e-4 0 -0.9999997 -0.002043843 0 -0.999998 -0.09318202 -0.9956492 0 -0.2769678 -0.9608793 0 -0.452838 -0.8915928 0 -0.7568029 -0.6536433 0 -0.9526339 -0.3041196 0 -0.9526336 0.3041205 0 -0.7568075 0.6536378 0 -0.4528404 0.8915916 0 -0.2769678 0.9608793 0 0.09317713 0.9956496 0 0.2769694 0.9608787 0 0.4528404 0.8915916 0 0.6149485 0.7885674 0 0.7568075 0.6536378 0 0.9526336 0.3041205 0 0.9526339 -0.3041196 0 0.7568058 -0.6536398 0 0.6149419 -0.7885724 0 0.452838 -0.8915928 0 -2.95245e-4 0 1 -0.001152276 0 0.9999994 2.95245e-4 0 1 -5.81889e-4 0 0.9999998 7.40603e-4 0 0.9999998 0.001152276 0 0.9999994 0.2769678 -0.9608793 0 0.09318143 -0.9956491 0 -5.5623e-4 0 -0.9999999 -9.96684e-4 0 -0.9999996 7.23482e-4 0 -0.9999998 4.06117e-4 0 -1 -3.55965e-4 0 -1 5.5623e-4 0 -0.9999998 9.96686e-4 0 -0.9999996 -7.2348e-4 0 -0.9999998 -4.06117e-4 0 -1 -0.2769686 -0.960879 0 -0.4528477 -0.8915879 0 -0.6149384 -0.7885752 0 -0.7568166 -0.6536273 0 -0.9946699 -0.1031118 0 0.09317809 0.9956495 0 0.4528412 0.8915913 0 0.7568085 0.6536368 0 0.871573 -0.4902658 0 0.6149463 -0.788569 0 0.002004563 0 0.9999981 0.2769686 -0.960879 0 9.12574e-4 0 -0.9999996 -9.67633e-4 0 -0.9999995 9.67633e-4 0 -0.9999995 -0.002043843 0 -0.999998 -0.09318143 -0.9956491 0 -0.6149419 -0.7885724 0 -0.7568088 -0.6536363 0 -0.8715682 -0.4902744 0 -0.9526354 0.3041149 0 -0.7568105 0.6536344 0 0.2769678 0.9608793 0 0.6149514 0.788565 0 0.8715656 0.490279 0 0.99467 0.1031099 0 0.9526375 -0.3041085 0 0.7568088 -0.6536363 0 0.4528356 -0.8915941 0 -2.95246e-4 0 1 -5.81891e-4 0 0.9999999 7.40608e-4 0 0.9999998 0.276971 -0.9608783 0 5.56232e-4 0 -0.9999999 -4.06118e-4 0 -1 -0.2769575 -0.9608823 0 -0.614941 -0.7885732 0 -0.7568114 -0.6536335 0 -0.871574 -0.490264 0 -0.952639 -0.3041036 0 -0.9946717 0.1030938 0 -0.9526285 0.3041365 0 -0.871567 0.4902768 0 0.871567 0.4902768 0 0.9526382 0.3041059 0 0.99467 0.1031104 0 0.9526342 -0.3041188 0 0.871574 -0.490264 0 0.7568031 -0.6536429 0 -7.06501e-4 0 0.9999998 7.065e-4 0 0.9999998 0.2769575 -0.9608823 0 0.09318608 -0.9956488 0 -8.30757e-4 0 -0.9999997 -0.001288354 0 -0.9999992 0.001258552 0 -0.9999992 9.30454e-4 0 -0.9999997 0.001288354 0 -0.9999992 -0.001258552 0 -0.9999992 7.06501e-4 0 -0.9999998 -0.2769705 -0.9608784 0 -0.6149438 -0.788571 0 -0.8715667 -0.4902769 0 -0.9526351 0.3041158 0 -0.4528427 0.8915904 0 0.4528427 0.8915904 0 0.6149495 0.7885665 0 0.9946701 0.103109 0 0.6149438 -0.788571 0 -2.95246e-4 0 1 7.40604e-4 0 0.9999998 0.001152276 0 0.9999994 -3.2036e-4 0 1 3.55965e-4 0 1 9.96684e-4 0 0.9999996 -0.001152276 0 0.9999994 0.2769737 -0.9608776 0 0.09317821 -0.9956495 0 -5.5623e-4 0 -0.9999998 -9.96686e-4 0 -0.9999996 7.2348e-4 0 -0.9999998 4.06117e-4 0 -1 5.56231e-4 0 -1 9.96684e-4 0 -0.9999996 -7.23482e-4 0 -0.9999998 -0.2769618 -0.960881 0 -0.7568031 -0.6536429 0 0.871567 -0.4902768 0 0.614941 -0.7885732 0 0.2769618 -0.960881 0 -0.001288354 0 -0.9999992 9.30449e-4 0 -0.9999996 -0.001258552 0 -0.9999993 -0.09317874 -0.9956494 0 0.6149466 0.7885687 0 -2.95245e-4 0 1 0.2769705 -0.9608784 0 0.1857258 0.9826017 0 0.5360054 0.8442146 0 0.8180086 0.5752062 0 0.9787855 0.2048878 0 0.8180037 -0.575213 0 0.5359964 -0.8442204 0 0.185724 -0.9826021 0 -0.1857258 -0.9826017 0 -0.5360054 -0.8442146 0 -0.8180086 -0.5752062 0 -0.8180037 0.575213 0 -8.0863e-5 0 1 1.34894e-4 0 1 8.0863e-5 0 1 -1.34894e-4 0 1 -0.5360009 0.8442175 0 -0.1857221 0.9826023 0 2.18814e-5 0 -1 -2.18814e-5 0 -1 0.5360009 -0.8442175 0 0.1857221 -0.9826023 0 -0.9787855 -0.2048878 0 8.08628e-5 0 1 2.18814e-5 0 -1 - - - - - - - - - - 0.8830742 0.5371637 0.7755767 0.6446613 0.7755767 0.5371637 0.8830742 0.6446613 0.7755767 0.7521589 0.7755767 0.6446613 0.8830742 0.7521589 0.7755767 0.8596563 0.7755767 0.7521589 0.8830742 0.8596563 0.7755767 0.967154 0.7755767 0.8596563 0.6916907 0.7749035 0.7015116 0.7715112 0.6924195 0.7764993 0.7306112 0.8093662 0.7324298 0.8193438 0.7306112 0.8193438 0.7215175 0.7715112 0.7116964 0.7749035 0.72079 0.7699149 0.7755767 0.7521589 0.7706229 0.7864776 0.7706229 0.7765001 0.7615292 0.7914665 0.7517083 0.7878146 0.7524357 0.7864776 0.7517083 0.7749035 0.7615292 0.7715112 0.7524357 0.7765001 0.7415234 0.7715112 0.7317023 0.7749035 0.740796 0.7699149 0.6905995 0.8193438 0.682597 0.8256697 0.6815058 0.8243326 0.6905993 0.7864776 0.682597 0.7928034 0.6815058 0.7914666 0.7215175 0.8372436 0.7116964 0.840636 0.72079 0.8356472 0.7215175 0.8243326 0.7116964 0.8206809 0.7124238 0.8193438 0.7317023 0.840636 0.7415234 0.8372436 0.7324298 0.8422324 0.7415234 0.8571989 0.7524357 0.8522101 0.7615292 0.8571989 0.9760536 0.8256697 0.9680513 0.8193438 0.9771448 0.8243326 0.9760536 0.7928034 0.9680513 0.7864776 0.9771448 0.7914666 0.96696 0.7749035 0.9571389 0.7715112 0.9578664 0.7699149 0.8971214 0.8571989 0.906215 0.8522101 0.9171273 0.8571989 0.906215 0.7864776 0.906215 0.7765001 0.9080338 0.7864776 0.9371333 0.7715112 0.9469543 0.7749035 0.9462268 0.7765001 0.9469543 0.840636 0.9371333 0.8372436 0.9378607 0.8356472 0.9269483 0.840636 0.9171273 0.8372436 0.9178549 0.8356472 0.9269483 0.8206809 0.9171273 0.8243326 0.9262209 0.8193438 0.9905717 0.7521589 0.9760536 0.7599373 0.9669602 0.7549484 0.3355668 0.5470865 0.3625472 0.5822257 0.3625472 0.5470865 0.3355668 0.6173651 0.3625472 0.5822257 0.3355668 0.5822256 0.3355668 0.6525043 0.3625472 0.6173651 0.3355668 0.6173651 0.3355668 0.6876436 0.3625472 0.6525043 0.3355668 0.6525043 0.3355668 0.6876436 0.3625472 0.7227829 0.3625472 0.6876436 0.3355668 0.7227829 0.3625472 0.7579222 0.3625472 0.7227829 0.3629911 0.5470865 0.3899714 0.5822257 0.3899714 0.5470865 0.3629911 0.6173651 0.3899714 0.5822257 0.3629911 0.5822256 0.3629911 0.6525043 0.3899714 0.6173651 0.3629911 0.6173651 0.3629911 0.6876436 0.3899714 0.6525043 0.3629911 0.6525043 0.3629911 0.6876436 0.3899714 0.7227829 0.3899714 0.6876436 0.3629911 0.7227829 0.3899714 0.7579222 0.3899714 0.7227829 0.3904153 0.5470865 0.4173957 0.5822257 0.4173957 0.5470865 0.3904153 0.6173651 0.4173957 0.5822257 0.3904153 0.5822256 0.3904153 0.6525043 0.4173957 0.6173651 0.3904153 0.6173651 0.3904153 0.6876436 0.4173957 0.6525043 0.3904153 0.6525043 0.3904153 0.6876436 0.4173957 0.7227829 0.4173957 0.6876436 0.3904153 0.7227829 0.4173957 0.7579222 0.4173957 0.7227829 0.4178395 0.5470865 0.4448199 0.5822257 0.4448199 0.5470865 0.4178395 0.6173651 0.4448199 0.5822257 0.4178395 0.5822256 0.4178395 0.6525043 0.4448199 0.6173651 0.4178395 0.6173651 0.4178395 0.6876436 0.4448199 0.6525043 0.4178395 0.6525043 0.4178395 0.6876436 0.4448199 0.7227829 0.4448199 0.6876436 0.4178395 0.7227829 0.4448199 0.7579222 0.4448199 0.7227829 0.4452638 0.5470865 0.4722442 0.5822257 0.4722442 0.5470865 0.4452638 0.6173651 0.4722442 0.5822257 0.4452638 0.5822256 0.4452638 0.6525043 0.4722442 0.6173651 0.4452638 0.6173651 0.4452638 0.6876436 0.4722442 0.6525043 0.4452638 0.6525043 0.4452638 0.6876436 0.4722442 0.7227829 0.4722442 0.6876436 0.4452638 0.7227829 0.4722442 0.7579222 0.4722442 0.7227829 0.472688 0.5470865 0.4996684 0.5822257 0.4996684 0.5470865 0.472688 0.6173651 0.4996684 0.5822257 0.472688 0.5822256 0.472688 0.6525043 0.4996684 0.6173651 0.472688 0.6173651 0.472688 0.6876436 0.4996684 0.6525043 0.472688 0.6525043 0.472688 0.6876436 0.4996684 0.7227829 0.4996684 0.6876436 0.472688 0.7227829 0.4996684 0.7579222 0.4996684 0.7227829 0.5001122 0.5470865 0.5270928 0.5822256 0.5270928 0.5470865 0.5001122 0.6173651 0.5270928 0.5822256 0.5001122 0.5822257 0.5001122 0.6525043 0.5270928 0.6173651 0.5001122 0.6173651 0.5001122 0.6876436 0.5270928 0.6525043 0.5001122 0.6525043 0.5001122 0.6876436 0.5270928 0.7227829 0.5270928 0.6876436 0.5001122 0.7227829 0.5270928 0.7579222 0.5270928 0.7227829 0.5275364 0.5470865 0.554517 0.5822256 0.554517 0.5470865 0.5275364 0.6173651 0.554517 0.5822256 0.5275364 0.5822256 0.5275364 0.6525043 0.554517 0.6173651 0.5275364 0.6173651 0.5275364 0.6876436 0.554517 0.6525043 0.5275364 0.6525043 0.5275364 0.6876436 0.554517 0.7227829 0.554517 0.6876436 0.5275364 0.7227829 0.554517 0.7579222 0.554517 0.7227829 0.5549607 0.5470865 0.5819413 0.5822256 0.5819413 0.5470865 0.554961 0.6173651 0.5819413 0.5822256 0.5549607 0.5822256 0.554961 0.6525043 0.5819413 0.6173651 0.554961 0.6173651 0.554961 0.6876436 0.5819413 0.6525043 0.554961 0.6525043 0.554961 0.6876436 0.5819413 0.7227829 0.5819413 0.6876436 0.554961 0.7227829 0.5819413 0.7579222 0.5819413 0.7227829 0.01746535 0.542943 0.07317203 0.6154952 0.07317203 0.542943 0.01746541 0.6880474 0.07317203 0.6154952 0.01746535 0.6154952 0.01746541 0.7605998 0.07317203 0.6880474 0.01746541 0.6880474 0.01746541 0.8331519 0.07317203 0.7605998 0.01746541 0.7605998 0.01746541 0.8331519 0.07317203 0.9057043 0.07317203 0.8331519 0.01746541 0.9057043 0.07317203 0.9782566 0.07317203 0.9057043 0.07408839 0.542943 0.129795 0.6154952 0.129795 0.542943 0.07408839 0.6880474 0.129795 0.6154952 0.07408839 0.6154952 0.07408839 0.7605998 0.129795 0.6880474 0.07408839 0.6880474 0.07408839 0.8331519 0.129795 0.7605998 0.07408839 0.7605998 0.07408839 0.8331519 0.129795 0.9057043 0.129795 0.8331519 0.07408839 0.9057043 0.129795 0.9782566 0.129795 0.9057043 0.1307113 0.542943 0.186418 0.6154952 0.186418 0.542943 0.1307113 0.6880474 0.186418 0.6154952 0.1307113 0.6154952 0.1307113 0.7605998 0.186418 0.6880474 0.1307113 0.6880474 0.1307113 0.8331519 0.186418 0.7605996 0.1307113 0.7605998 0.1307113 0.8331519 0.186418 0.9057043 0.186418 0.8331519 0.1307113 0.9057043 0.186418 0.9782566 0.186418 0.9057043 0.1873343 0.542943 0.243041 0.6154952 0.243041 0.542943 0.1873343 0.6880474 0.243041 0.6154952 0.1873343 0.6154952 0.1873343 0.7605998 0.243041 0.6880474 0.1873343 0.6880474 0.1873343 0.8331519 0.243041 0.7605998 0.1873343 0.7605998 0.1873343 0.8331519 0.243041 0.9057043 0.243041 0.8331519 0.1873343 0.9057043 0.243041 0.9782566 0.243041 0.9057043 0.2439573 0.542943 0.299664 0.6154952 0.299664 0.542943 0.2439574 0.6880474 0.299664 0.6154952 0.2439574 0.6154952 0.2439574 0.7605996 0.299664 0.6880474 0.2439574 0.6880474 0.2439574 0.8331519 0.299664 0.7605998 0.2439574 0.7605996 0.2439574 0.8331519 0.299664 0.9057043 0.299664 0.8331519 0.2439574 0.9057043 0.299664 0.9782566 0.299664 0.9057043 0.3355668 0.7583661 0.3625472 0.7935054 0.3625472 0.7583661 0.3355668 0.8286446 0.3625472 0.7935054 0.3355668 0.7935053 0.3355668 0.8637839 0.3625472 0.8286446 0.3355668 0.8286446 0.3355668 0.8989232 0.3625472 0.8637839 0.3355668 0.8637839 0.3355668 0.8989232 0.3625472 0.9340626 0.3625472 0.8989232 0.3355668 0.9340626 0.3625472 0.9692018 0.3625472 0.9340626 0.3629911 0.7583661 0.3899714 0.7935054 0.3899714 0.7583659 0.3629911 0.8286446 0.3899714 0.7935054 0.3629911 0.7935053 0.3629911 0.8637839 0.3899714 0.8286446 0.3629911 0.8286446 0.3629911 0.8989232 0.3899714 0.8637839 0.3629911 0.8637839 0.3629911 0.8989232 0.3899714 0.9340626 0.3899714 0.8989232 0.3629911 0.9471353 0.3629911 0.9692018 0.3899714 0.9692018 0.3904153 0.7583659 0.4173957 0.7935054 0.4173957 0.7583659 0.3904153 0.8286446 0.4173957 0.7935054 0.3904153 0.7935053 0.3904153 0.8637839 0.4173957 0.8286446 0.3904153 0.8286446 0.3904153 0.8989232 0.4173957 0.8637839 0.3904153 0.8637839 0.3904153 0.8989232 0.4173957 0.9340626 0.4173957 0.8989232 0.3904153 0.9340626 0.4173957 0.9692018 0.4173957 0.9340626 0.4178395 0.7583659 0.4448199 0.7935054 0.4448199 0.7583659 0.4178395 0.8286446 0.4448199 0.7935054 0.4178395 0.7935053 0.4178395 0.8637839 0.4448199 0.8286446 0.4178395 0.8286446 0.4178395 0.8989232 0.4448199 0.8637839 0.4178395 0.8637839 0.4178395 0.8989232 0.4448199 0.9340626 0.4448199 0.8989232 0.4178395 0.9340626 0.4448199 0.9692018 0.4448199 0.9340626 0.4452638 0.7583659 0.4722442 0.7935054 0.4722442 0.7583659 0.4452638 0.8286446 0.4722442 0.7935054 0.4452638 0.7935053 0.4452638 0.8637839 0.4722442 0.8286446 0.4452638 0.8286446 0.4452638 0.8989232 0.4722442 0.8637839 0.4452638 0.8637839 0.4452638 0.8989232 0.4722442 0.9340626 0.4722442 0.8989232 0.4452638 0.9340626 0.4722442 0.9692018 0.4722442 0.9340626 0.472688 0.7583659 0.4996684 0.7935054 0.4996684 0.7583659 0.472688 0.8286446 0.4996684 0.7935054 0.472688 0.7935053 0.472688 0.8491244 0.4996684 0.8637839 0.4996684 0.8286446 0.472688 0.8989232 0.4996684 0.8637839 0.472688 0.8637839 0.472688 0.8989232 0.4996684 0.9340626 0.4996684 0.8989232 0.472688 0.9340676 0.472688 0.9692018 0.4996684 0.9692018 0.5001122 0.7583659 0.5270928 0.7935054 0.5270928 0.7583659 0.5001122 0.8286446 0.5270928 0.7935054 0.5001122 0.7935053 0.5001122 0.8637839 0.5270928 0.8286446 0.5001122 0.8286446 0.5001122 0.8989232 0.5270928 0.8637839 0.5001122 0.8637839 0.5001122 0.8989232 0.5270928 0.9340626 0.5270928 0.8989232 0.5001122 0.9340626 0.5270928 0.9692018 0.5270928 0.9340626 0.5275364 0.7583659 0.554517 0.7935054 0.554517 0.7583659 0.5275364 0.8286446 0.554517 0.7935054 0.5275364 0.7935053 0.5275364 0.8637839 0.554517 0.8286446 0.5275364 0.8286446 0.5275364 0.8989232 0.554517 0.8637839 0.5275364 0.8637839 0.5275364 0.8989232 0.554517 0.9340626 0.554517 0.8989232 0.5275364 0.9340626 0.554517 0.9692018 0.554517 0.9340626 0.5549607 0.7583659 0.5819413 0.7935053 0.5819413 0.7583659 0.5549607 0.8286446 0.5819413 0.7935053 0.5549607 0.7935053 0.5549607 0.8637839 0.5819413 0.8286446 0.5549607 0.8286446 0.5549607 0.8989232 0.5819413 0.8637839 0.5549607 0.8637839 0.5549607 0.8989232 0.5819413 0.9340626 0.5819413 0.8989232 0.5549607 0.9340626 0.5819413 0.9692018 0.5819413 0.9340626 0.5823852 0.5470865 0.6093655 0.5822256 0.6093655 0.5470865 0.5823852 0.6173651 0.6093655 0.5822256 0.5823852 0.5822256 0.5823852 0.6525043 0.6093655 0.6173651 0.5823852 0.6173651 0.5823852 0.6876436 0.6093655 0.6525043 0.5823852 0.6525043 0.5823852 0.6876436 0.6093655 0.7227829 0.6093655 0.6876436 0.5823852 0.7227829 0.6093655 0.7579222 0.6093655 0.7227829 0.5823849 0.7583659 0.6093655 0.7935053 0.6093655 0.7583659 0.5823849 0.8286446 0.6093655 0.7935053 0.5823849 0.7935053 0.5823849 0.8637839 0.6093655 0.8286446 0.5823849 0.8286446 0.5823849 0.8989232 0.6093655 0.8637839 0.5823849 0.8637839 0.5823849 0.8989232 0.6093655 0.9340626 0.6093655 0.8989232 0.5823849 0.9340626 0.6093655 0.9692018 0.6093655 0.9340626 0.6098094 0.5470865 0.6367898 0.5822257 0.6367898 0.5470865 0.6098094 0.6173651 0.6367898 0.5822257 0.6098094 0.5822256 0.6098094 0.6525043 0.6367898 0.6173651 0.6098094 0.6173651 0.6098094 0.6876437 0.6367898 0.6525043 0.6098094 0.6525043 0.6098094 0.6876437 0.6367898 0.7227829 0.6367898 0.6876436 0.6098094 0.7227829 0.6367898 0.7579223 0.6367898 0.7227829 0.6098094 0.7583659 0.6367898 0.7935053 0.6367898 0.7583659 0.6098094 0.8286446 0.6367898 0.7935053 0.6098094 0.7935053 0.6098094 0.8637839 0.6367898 0.8286445 0.6098094 0.8286446 0.6098094 0.8989232 0.6367898 0.8637839 0.6098094 0.8637839 0.6098094 0.8989232 0.6367898 0.9340626 0.6367898 0.8989232 0.6098094 0.9340626 0.6367898 0.9692018 0.6367898 0.9340626 0.4965105 0.1496902 0.3630295 0.06654256 0.3630295 0.1496902 0.4965105 0.1496902 0.3630295 0.2901237 0.4965105 0.2901237 0.4965105 0.2901237 0.5796583 0.1496902 0.4965105 0.1496902 0.4965105 0.5137047 0.3630295 0.3732712 0.3630295 0.5137047 0.3630295 0.1496902 0.2798816 0.2901237 0.3630295 0.2901237 0.3630295 0.2901237 0.4965105 0.3732712 0.4965105 0.2901237 0.06854629 0.2737155 0.02928906 0.276169 0.02928906 0.2737155 0.06854629 0.276169 0.02928906 0.2786228 0.02928906 0.276169 0.06854629 0.2786228 0.02928906 0.281076 0.02928906 0.2786228 0.06854629 0.281076 0.02928906 0.2835297 0.02928906 0.281076 0.06854629 0.2835297 0.02928906 0.2859833 0.02928906 0.2835297 0.06854629 0.2859833 0.02928906 0.288437 0.02928906 0.2859833 0.06854629 0.288437 0.02928906 0.2908906 0.02928906 0.288437 0.06854629 0.2908906 0.02928906 0.2933443 0.02928906 0.2908906 0.06854629 0.2933443 0.02928906 0.295798 0.02928906 0.2933443 0.06854629 0.295798 0.02928906 0.2982512 0.02928906 0.295798 0.06854629 0.2982512 0.02928906 0.3007048 0.02928906 0.2982512 0.06854629 0.3007048 0.02928906 0.3031585 0.02928906 0.3007048 0.06854629 0.3031585 0.02928906 0.3056122 0.02928906 0.3031585 0.06854629 0.3056122 0.02928906 0.3080657 0.02928906 0.3056122 0.06854629 0.3080657 0.02928906 0.3105193 0.02928906 0.3080657 0.06854629 0.3105193 0.02928906 0.3129729 0.02928906 0.3105193 0.06854629 0.3129729 0.02928906 0.3154264 0.02928906 0.3129729 0.06854629 0.3154264 0.02928906 0.31788 0.02928906 0.3154264 0.06854629 0.31788 0.02928906 0.3203335 0.02928906 0.31788 0.06854629 0.3203335 0.02928906 0.3227872 0.02928906 0.3203335 0.06854629 0.3227872 0.02928906 0.3252408 0.02928906 0.3227872 0.06854629 0.3252408 0.02928906 0.3276945 0.02928906 0.3252408 0.06854629 0.3276945 0.02928906 0.3301477 0.02928906 0.3276945 0.06854629 0.3301477 0.02928906 0.3326014 0.02928906 0.3301477 0.06854629 0.3326014 0.02928906 0.335055 0.02928906 0.3326014 0.06854629 0.335055 0.02928906 0.3375087 0.02928906 0.335055 0.06854629 0.3375087 0.02928906 0.3399623 0.02928906 0.3375087 0.06854629 0.3399623 0.02928906 0.3424161 0.02928906 0.3399623 0.06854629 0.3424161 0.02928906 0.3448697 0.02928906 0.3424161 0.06854629 0.3448697 0.02928906 0.347323 0.02928906 0.3448697 0.06679451 0.4480686 0.06679451 0.4517623 0.04619479 0.4311625 0.06854629 0.347323 0.02928906 0.3497766 0.02928906 0.347323 0.06854629 0.3497766 0.02928906 0.3522303 0.02928906 0.3497766 0.1878745 0.4034364 0.1871539 0.4070596 0.2178607 0.3943402 0.1080124 0.2737155 0.0687552 0.276169 0.0687552 0.2737155 0.1080124 0.276169 0.0687552 0.2786228 0.0687552 0.276169 0.1080124 0.2786228 0.0687552 0.281076 0.0687552 0.2786228 0.1080124 0.281076 0.0687552 0.2835297 0.0687552 0.281076 0.1080124 0.2835297 0.0687552 0.2859833 0.0687552 0.2835297 0.1080124 0.2859833 0.0687552 0.288437 0.0687552 0.2859833 0.1080124 0.288437 0.0687552 0.2908906 0.0687552 0.288437 0.1080124 0.2908906 0.0687552 0.2933443 0.0687552 0.2908906 0.1080124 0.2933443 0.0687552 0.295798 0.0687552 0.2933443 0.1080124 0.295798 0.0687552 0.2982512 0.0687552 0.295798 0.1080124 0.2982512 0.0687552 0.3007048 0.0687552 0.2982512 0.1080124 0.3007048 0.0687552 0.3031585 0.0687552 0.3007048 0.1080124 0.3031585 0.0687552 0.3056122 0.0687552 0.3031585 0.1080124 0.3056122 0.0687552 0.3080657 0.0687552 0.3056122 0.1080124 0.3080657 0.0687552 0.3105193 0.0687552 0.3080657 0.1080124 0.3105193 0.0687552 0.3129729 0.0687552 0.3105193 0.1080124 0.3129729 0.0687552 0.3154264 0.0687552 0.3129729 0.1080124 0.3154264 0.0687552 0.31788 0.0687552 0.3154264 0.1080124 0.31788 0.0687552 0.3203335 0.0687552 0.31788 0.1080124 0.3203335 0.0687552 0.3227872 0.0687552 0.3203335 0.1080124 0.3227872 0.0687552 0.3252408 0.0687552 0.3227872 0.1080124 0.3252408 0.0687552 0.3276945 0.0687552 0.3252408 0.1080124 0.3276945 0.0687552 0.3301477 0.0687552 0.3276945 0.1080124 0.3301477 0.0687552 0.3326014 0.0687552 0.3301477 0.1080124 0.3326014 0.0687552 0.335055 0.0687552 0.3326014 0.1080124 0.335055 0.0687552 0.3375087 0.0687552 0.335055 0.1080124 0.3375087 0.0687552 0.3399623 0.0687552 0.3375087 0.1080124 0.3399623 0.0687552 0.3424161 0.0687552 0.3399623 0.1080124 0.3424161 0.0687552 0.3448697 0.0687552 0.3424161 0.1080124 0.3448697 0.0687552 0.347323 0.0687552 0.3448697 0.1062608 0.4480686 0.1062608 0.4517623 0.08566087 0.4311625 0.1080124 0.347323 0.0687552 0.3497766 0.0687552 0.347323 0.1080124 0.3497766 0.0687552 0.3522303 0.0687552 0.3497766 0.2220854 0.4444454 0.2213647 0.4480686 0.2520717 0.4353492 0.1474788 0.2737155 0.1082213 0.276169 0.1082213 0.2737155 0.1474788 0.276169 0.1082213 0.2786228 0.1082213 0.276169 0.1474788 0.2786228 0.1082213 0.281076 0.1082213 0.2786228 0.1474788 0.281076 0.1082213 0.2835297 0.1082213 0.281076 0.1474788 0.2835297 0.1082213 0.2859833 0.1082213 0.2835297 0.1474788 0.2859833 0.1082213 0.288437 0.1082213 0.2859833 0.1474788 0.288437 0.1082213 0.2908906 0.1082213 0.288437 0.1474788 0.2908906 0.1082213 0.2933443 0.1082213 0.2908906 0.1474788 0.2933443 0.1082213 0.295798 0.1082213 0.2933443 0.1474788 0.295798 0.1082213 0.2982512 0.1082213 0.295798 0.1474788 0.2982512 0.1082213 0.3007048 0.1082213 0.2982512 0.1474788 0.3007048 0.1082213 0.3031585 0.1082213 0.3007048 0.1474788 0.3031585 0.1082213 0.3056122 0.1082213 0.3031585 0.1474788 0.3056122 0.1082213 0.3080657 0.1082213 0.3056122 0.1474788 0.3080657 0.1082213 0.3105193 0.1082213 0.3080657 0.1474788 0.3105193 0.1082213 0.3129729 0.1082213 0.3105193 0.1474788 0.3129729 0.1082213 0.3154264 0.1082213 0.3129729 0.1474788 0.3154264 0.1082213 0.31788 0.1082213 0.3154264 0.1474788 0.31788 0.1082213 0.3203335 0.1082213 0.31788 0.1474788 0.3203335 0.1082213 0.3227872 0.1082213 0.3203335 0.1474788 0.3227872 0.1082213 0.3252408 0.1082213 0.3227872 0.1474788 0.3252408 0.1082213 0.3276945 0.1082213 0.3252408 0.1474788 0.3276945 0.1082213 0.3301477 0.1082213 0.3276945 0.1474788 0.3301477 0.1082213 0.3326014 0.1082213 0.3301477 0.1474788 0.3326014 0.1082213 0.335055 0.1082213 0.3326014 0.1474788 0.335055 0.1082213 0.3375087 0.1082213 0.335055 0.1474788 0.3375087 0.1082213 0.3399623 0.1082213 0.3375087 0.1474788 0.3399623 0.1082213 0.3424161 0.1082213 0.3399623 0.1474788 0.3424161 0.1082213 0.3448697 0.1082213 0.3424161 0.1474788 0.3448697 0.1082213 0.347323 0.1082213 0.3448697 0.1457269 0.4480686 0.1457269 0.4517623 0.1251272 0.4311625 0.1474788 0.347323 0.1082213 0.3497766 0.1082213 0.347323 0.1474788 0.3497766 0.1082213 0.3522303 0.1082213 0.3497766 0.03000956 0.4821599 0.02928906 0.4857831 0.059996 0.4730637 0.06854629 0.352439 0.02928906 0.3548926 0.02928906 0.352439 0.06854629 0.3548926 0.02928906 0.3573463 0.02928906 0.3548926 0.06854629 0.3573463 0.02928906 0.3597999 0.02928906 0.3573463 0.06854629 0.3597999 0.02928906 0.3622536 0.02928906 0.3597999 0.06854629 0.3622536 0.02928906 0.3647069 0.02928906 0.3622536 0.06854629 0.3647069 0.02928906 0.3671605 0.02928906 0.3647069 0.06854629 0.3671605 0.02928906 0.3696142 0.02928906 0.3671605 0.06854629 0.3696142 0.02928906 0.3720678 0.02928906 0.3696142 0.06854629 0.3720678 0.02928906 0.3745215 0.02928906 0.3720678 0.06854629 0.3745215 0.02928906 0.3769749 0.02928906 0.3745215 0.06854629 0.3769749 0.02928906 0.3794284 0.02928906 0.3769749 0.06854629 0.3794284 0.02928906 0.3818821 0.02928906 0.3794284 0.06854629 0.3818821 0.02928906 0.3843358 0.02928906 0.3818821 0.06854629 0.3843358 0.02928906 0.3867892 0.02928906 0.3843358 0.06854629 0.3867892 0.02928906 0.3892428 0.02928906 0.3867892 0.06854629 0.3892428 0.02928906 0.3916965 0.02928906 0.3892428 0.06854629 0.3916965 0.02928906 0.3941501 0.02928906 0.3916965 0.06854629 0.3941501 0.02928906 0.3966034 0.02928906 0.3941501 0.06854629 0.3966034 0.02928906 0.399057 0.02928906 0.3966034 0.06854629 0.399057 0.02928906 0.4015107 0.02928906 0.399057 0.06854629 0.4015107 0.02928906 0.4039644 0.02928906 0.4015107 0.06854629 0.4039644 0.02928906 0.406418 0.02928906 0.4039644 0.06854629 0.406418 0.02928906 0.4088717 0.02928906 0.406418 0.06854629 0.4088717 0.02928906 0.4113253 0.02928906 0.4088717 0.06854629 0.4113253 0.02928906 0.4137786 0.02928906 0.4113253 0.06854629 0.4137786 0.02928906 0.4162324 0.02928906 0.4137786 0.06854629 0.4162324 0.02928906 0.4186859 0.02928906 0.4162324 0.06854629 0.4186859 0.02928906 0.4211395 0.02928906 0.4186859 0.06854629 0.4211395 0.02928906 0.423593 0.02928906 0.4211395 0.06854629 0.423593 0.02928906 0.4260466 0.02928906 0.423593 0.1834415 0.4480686 0.1834415 0.4517623 0.1628416 0.4311625 0.06854629 0.4260466 0.02928906 0.4285003 0.02928906 0.4260466 0.06854629 0.4285003 0.02928906 0.4309538 0.02928906 0.4285003 0.06772416 0.4821599 0.06700336 0.4857831 0.09771031 0.4730637 0.1080124 0.352439 0.0687552 0.3548926 0.0687552 0.352439 0.1080124 0.3548926 0.0687552 0.3573463 0.0687552 0.3548926 0.1080124 0.3573463 0.0687552 0.3597999 0.0687552 0.3573463 0.1080124 0.3597999 0.0687552 0.3622536 0.0687552 0.3597999 0.1080124 0.3622536 0.0687552 0.3647069 0.0687552 0.3622536 0.1080124 0.3647069 0.0687552 0.3671605 0.0687552 0.3647069 0.1080124 0.3671605 0.0687552 0.3696142 0.0687552 0.3671605 0.1080124 0.3696142 0.0687552 0.3720678 0.0687552 0.3696142 0.1080124 0.3720678 0.0687552 0.3745215 0.0687552 0.3720678 0.1080124 0.3745215 0.0687552 0.3769749 0.0687552 0.3745215 0.1080124 0.3769749 0.0687552 0.3794284 0.0687552 0.3769749 0.1080124 0.3794284 0.0687552 0.3818821 0.0687552 0.3794284 0.1080124 0.3818821 0.0687552 0.3843358 0.0687552 0.3818821 0.1080124 0.3843358 0.0687552 0.3867892 0.0687552 0.3843358 0.1080124 0.3867892 0.0687552 0.3892428 0.0687552 0.3867892 0.1080124 0.3892428 0.0687552 0.3916965 0.0687552 0.3892428 0.1080124 0.3916965 0.0687552 0.3941501 0.0687552 0.3916965 0.1080124 0.3941501 0.0687552 0.3966034 0.0687552 0.3941501 0.1080124 0.3966034 0.0687552 0.399057 0.0687552 0.3966034 0.1080124 0.399057 0.0687552 0.4015107 0.0687552 0.399057 0.1080124 0.4015107 0.0687552 0.4039644 0.0687552 0.4015107 0.1080124 0.4039644 0.0687552 0.406418 0.0687552 0.4039644 0.1080124 0.406418 0.0687552 0.4088717 0.0687552 0.406418 0.1080124 0.4088717 0.0687552 0.4113253 0.0687552 0.4088717 0.1080124 0.4113253 0.0687552 0.4137786 0.0687552 0.4113253 0.1080124 0.4137786 0.0687552 0.4162324 0.0687552 0.4137786 0.1080124 0.4162324 0.0687552 0.4186859 0.0687552 0.4162324 0.1080124 0.4186859 0.0687552 0.4211395 0.0687552 0.4186859 0.1080124 0.4211395 0.0687552 0.423593 0.0687552 0.4211395 0.1080124 0.423593 0.0687552 0.4260466 0.0687552 0.423593 0.221156 0.4480686 0.2211559 0.4517623 0.200556 0.4311625 0.1080124 0.4260466 0.0687552 0.4285003 0.0687552 0.4260466 0.1080124 0.4285003 0.0687552 0.4309538 0.0687552 0.4285003 0.1071903 0.4821599 0.1064696 0.4857831 0.1371766 0.4730637 0.1474788 0.352439 0.1082213 0.3548926 0.1082213 0.352439 0.1474788 0.3548926 0.1082213 0.3573463 0.1082213 0.3548926 0.1474788 0.3573463 0.1082213 0.3597999 0.1082213 0.3573463 0.1474788 0.3597999 0.1082213 0.3622536 0.1082213 0.3597999 0.1474788 0.3622536 0.1082213 0.3647069 0.1082213 0.3622536 0.1474788 0.3647069 0.1082213 0.3671605 0.1082213 0.3647069 0.1474788 0.3671605 0.1082213 0.3696142 0.1082213 0.3671605 0.1474788 0.3696142 0.1082213 0.3720678 0.1082213 0.3696142 0.1474788 0.3720678 0.1082213 0.3745215 0.1082213 0.3720678 0.1474788 0.3745215 0.1082213 0.3769749 0.1082213 0.3745215 0.1474788 0.3769749 0.1082213 0.3794284 0.1082213 0.3769749 0.1474788 0.3794284 0.1082213 0.3818821 0.1082213 0.3794284 0.1474788 0.3818821 0.1082213 0.3843358 0.1082213 0.3818821 0.1474788 0.3843358 0.1082213 0.3867892 0.1082213 0.3843358 0.1474788 0.3867892 0.1082213 0.3892428 0.1082213 0.3867892 0.1474788 0.3892428 0.1082213 0.3916965 0.1082213 0.3892428 0.1474788 0.3916965 0.1082213 0.3941501 0.1082213 0.3916965 0.1474788 0.3941501 0.1082213 0.3966034 0.1082213 0.3941501 0.1474788 0.3966034 0.1082213 0.399057 0.1082213 0.3966034 0.1474788 0.399057 0.1082213 0.4015107 0.1082213 0.399057 0.1474788 0.4015107 0.1082213 0.4039644 0.1082213 0.4015107 0.1474788 0.4039644 0.1082213 0.406418 0.1082213 0.4039644 0.1474788 0.406418 0.1082213 0.4088717 0.1082213 0.406418 0.1474788 0.4088717 0.1082213 0.4113253 0.1082213 0.4088717 0.1474788 0.4113253 0.1082213 0.4137786 0.1082213 0.4113253 0.1474788 0.4137786 0.1082213 0.4162324 0.1082213 0.4137786 0.1474788 0.4162324 0.1082213 0.4186859 0.1082213 0.4162324 0.1474788 0.4186859 0.1082213 0.4211395 0.1082213 0.4186859 0.1474788 0.4211395 0.1082213 0.423593 0.1082213 0.4211395 0.1474788 0.423593 0.1082213 0.4260466 0.1082213 0.423593 0.2246595 0.2906213 0.2246595 0.2943153 0.2040597 0.2737155 0.1474788 0.4260466 0.1082213 0.4285003 0.1082213 0.4260466 0.1474788 0.4285003 0.1082213 0.4309538 0.1082213 0.4285003 0.1466564 0.4821599 0.1459357 0.4857831 0.1766429 0.4730637 0.1869451 0.2737155 0.1476876 0.276169 0.1476876 0.2737155 0.1869451 0.276169 0.1476876 0.2786228 0.1476876 0.276169 0.1869451 0.2786228 0.1476876 0.281076 0.1476876 0.2786228 0.1869451 0.281076 0.1476876 0.2835297 0.1476876 0.281076 0.1869451 0.2835297 0.1476876 0.2859833 0.1476876 0.2835297 0.1869451 0.2859833 0.1476876 0.288437 0.1476876 0.2859833 0.1869451 0.288437 0.1476876 0.2908906 0.1476876 0.288437 0.1869451 0.2908906 0.1476876 0.2933443 0.1476876 0.2908906 0.1869451 0.2933443 0.1476876 0.295798 0.1476876 0.2933443 0.1869451 0.295798 0.1476876 0.2982512 0.1476876 0.295798 0.1869451 0.2982512 0.1476876 0.3007048 0.1476876 0.2982512 0.1869451 0.3007048 0.1476876 0.3031585 0.1476876 0.3007048 0.1869451 0.3031585 0.1476876 0.3056122 0.1476876 0.3031585 0.1869451 0.3056122 0.1476876 0.3080657 0.1476876 0.3056122 0.1869451 0.3080657 0.1476876 0.3105193 0.1476876 0.3080657 0.1869451 0.3105193 0.1476876 0.3129729 0.1476876 0.3105193 0.1869451 0.3129729 0.1476876 0.3154264 0.1476876 0.3129729 0.1869451 0.3154264 0.1476876 0.31788 0.1476876 0.3154264 0.1869451 0.31788 0.1476876 0.3203335 0.1476876 0.31788 0.1869451 0.3203335 0.1476876 0.3227872 0.1476876 0.3203335 0.1869451 0.3227872 0.1476876 0.3252408 0.1476876 0.3227872 0.1869451 0.3252408 0.1476876 0.3276945 0.1476876 0.3252408 0.1869451 0.3276945 0.1476876 0.3301477 0.1476876 0.3276945 0.1869451 0.3301477 0.1476876 0.3326014 0.1476876 0.3301477 0.1869451 0.3326014 0.1476876 0.335055 0.1476876 0.3326014 0.1869451 0.335055 0.1476876 0.3375087 0.1476876 0.335055 0.1869451 0.3375087 0.1476876 0.3399623 0.1476876 0.3375087 0.1869451 0.3399623 0.1476876 0.3424161 0.1476876 0.3399623 0.1869451 0.3424161 0.1476876 0.3448697 0.1476876 0.3424161 0.1869451 0.3448697 0.1476876 0.347323 0.1476876 0.3448697 0.2246595 0.3283357 0.2246595 0.3320298 0.2040597 0.3114299 0.1869451 0.347323 0.1476876 0.3497766 0.1476876 0.347323 0.1869451 0.3497766 0.1476876 0.3522303 0.1476876 0.3497766 0.1843709 0.4821599 0.1836503 0.4857831 0.2143573 0.4730637 0.1869451 0.352439 0.1476876 0.3548926 0.1476876 0.352439 0.1869451 0.3548926 0.1476876 0.3573463 0.1476876 0.3548926 0.1869451 0.3573463 0.1476876 0.3597999 0.1476876 0.3573463 0.1869451 0.3597999 0.1476876 0.3622536 0.1476876 0.3597999 0.1869451 0.3622536 0.1476876 0.3647069 0.1476876 0.3622536 0.1869451 0.3647069 0.1476876 0.3671605 0.1476876 0.3647069 0.1869451 0.3671605 0.1476876 0.3696142 0.1476876 0.3671605 0.1869451 0.3696142 0.1476876 0.3720678 0.1476876 0.3696142 0.1869451 0.3720678 0.1476876 0.3745215 0.1476876 0.3720678 0.1869451 0.3745215 0.1476876 0.3769749 0.1476876 0.3745215 0.1869451 0.3769749 0.1476876 0.3794284 0.1476876 0.3769749 0.1869451 0.3794284 0.1476876 0.3818821 0.1476876 0.3794284 0.1869451 0.3818821 0.1476876 0.3843358 0.1476876 0.3818821 0.1869451 0.3843358 0.1476876 0.3867892 0.1476876 0.3843358 0.1869451 0.3867892 0.1476876 0.3892428 0.1476876 0.3867892 0.1869451 0.3892428 0.1476876 0.3916965 0.1476876 0.3892428 0.1869451 0.3916965 0.1476876 0.3941501 0.1476876 0.3916965 0.1869451 0.3941501 0.1476876 0.3966034 0.1476876 0.3941501 0.1869451 0.3966034 0.1476876 0.399057 0.1476876 0.3966034 0.1869451 0.399057 0.1476876 0.4015107 0.1476876 0.399057 0.1869451 0.4015107 0.1476876 0.4039644 0.1476876 0.4015107 0.1869451 0.4039644 0.1476876 0.406418 0.1476876 0.4039644 0.1869451 0.406418 0.1476876 0.4088717 0.1476876 0.406418 0.1869451 0.4088717 0.1476876 0.4113253 0.1476876 0.4088717 0.1869451 0.4113253 0.1476876 0.4137786 0.1476876 0.4113253 0.1869451 0.4137786 0.1476876 0.4162324 0.1476876 0.4137786 0.1869451 0.4162324 0.1476876 0.4186859 0.1476876 0.4162324 0.1869451 0.4186859 0.1476876 0.4211395 0.1476876 0.4186859 0.1869451 0.4211395 0.1476876 0.423593 0.1476876 0.4211395 0.1869451 0.423593 0.1476876 0.4260466 0.1476876 0.423593 0.2246595 0.3693447 0.2246595 0.3730388 0.2040597 0.352439 0.1869451 0.4260466 0.1476876 0.4285003 0.1476876 0.4260466 0.1869451 0.4285003 0.1476876 0.4309538 0.1476876 0.4285003 0.2220854 0.4821599 0.2213647 0.4857831 0.2520717 0.4730637 0.7876291 0.5065029 0.7711581 0.3747343 0.7876291 0.3747343 0.7711581 0.5065029 0.754687 0.3747343 0.7711581 0.3747343 0.754687 0.5065029 0.7382159 0.3747343 0.754687 0.3747343 0.7382159 0.5065029 0.7217448 0.3747343 0.7382159 0.3747343 0.7217448 0.5065029 0.7052738 0.3747343 0.7217448 0.3747343 0.7052738 0.5065029 0.6888027 0.3747343 0.7052738 0.3747343 0.6888027 0.5065029 0.6723316 0.3747343 0.6888027 0.3747343 0.6723316 0.5065029 0.6558606 0.3747343 0.6723316 0.3747343 0.6558606 0.5065029 0.6393895 0.3747343 0.6558606 0.3747343 0.6393895 0.5065029 0.6229183 0.3747343 0.6393895 0.3747343 0.6229183 0.5065029 0.6064473 0.3747343 0.6229183 0.3747343 0.6064473 0.5065029 0.5899763 0.3747343 0.6064473 0.3747343 0.5899763 0.5065029 0.5735051 0.3747343 0.5899763 0.3747343 0.5735051 0.5065029 0.557034 0.3747343 0.5735051 0.3747343 0.6336622 0.3441658 0.6384376 0.3201586 0.6384376 0.337019 0.557034 0.5065029 0.540563 0.3747343 0.557034 0.3747343 0.540563 0.5065029 0.5240918 0.3747343 0.540563 0.3747343 0.6436271 0.337019 0.6484024 0.3441658 0.6436271 0.3201586 0.7056843 0.2639958 0.6125414 0.1708528 0.6125414 0.2639958 0.7988276 0.2639958 0.7056843 0.1708528 0.7056843 0.2639958 0.8919706 0.2639958 0.7988276 0.1708528 0.7988276 0.2639958 0.9851137 0.2639958 0.8919706 0.1708528 0.8919706 0.2639958 0.8919706 0.3571389 0.7988276 0.2639958 0.7988276 0.3571389 0.8919706 0.1708528 0.7988276 0.07770967 0.7988276 0.1708528 0.7876291 0.5065029 0.7711581 0.3747343 0.7876291 0.3747343 0.7711581 0.5065029 0.754687 0.3747343 0.7711581 0.3747343 0.754687 0.5065029 0.7382159 0.3747343 0.754687 0.3747343 0.7382159 0.5065029 0.7217448 0.3747343 0.7382159 0.3747343 0.7217448 0.5065029 0.7052738 0.3747343 0.7217448 0.3747343 0.7052738 0.5065029 0.6888027 0.3747343 0.7052738 0.3747343 0.6888027 0.5065029 0.6723316 0.3747343 0.6888027 0.3747343 0.6723316 0.5065029 0.6558606 0.3747343 0.6723316 0.3747343 0.6558606 0.5065029 0.6393895 0.3747343 0.6558606 0.3747343 0.6393895 0.5065029 0.6229183 0.3747343 0.6393895 0.3747343 0.6229183 0.5065029 0.6064473 0.3747343 0.6229183 0.3747343 0.6064473 0.5065029 0.5899763 0.3747343 0.6064473 0.3747343 0.5899763 0.5065029 0.5735051 0.3747343 0.5899763 0.3747343 0.5735051 0.5065029 0.557034 0.3747343 0.5735051 0.3747343 0.6336622 0.3441658 0.6384376 0.3201586 0.6384376 0.337019 0.557034 0.5065029 0.540563 0.3747343 0.557034 0.3747343 0.540563 0.5065029 0.5240918 0.3747343 0.540563 0.3747343 0.6436271 0.337019 0.6484024 0.3441658 0.6436271 0.3201586 0.7876291 0.5065029 0.7711581 0.3747343 0.7876291 0.3747343 0.7711581 0.5065029 0.754687 0.3747343 0.7711581 0.3747343 0.754687 0.5065029 0.7382159 0.3747343 0.754687 0.3747343 0.7382159 0.5065029 0.7217448 0.3747343 0.7382159 0.3747343 0.7217448 0.5065029 0.7052738 0.3747343 0.7217448 0.3747343 0.7052738 0.5065029 0.6888027 0.3747343 0.7052738 0.3747343 0.6888027 0.5065029 0.6723316 0.3747343 0.6888027 0.3747343 0.6723316 0.5065029 0.6558606 0.3747343 0.6723316 0.3747343 0.6558606 0.5065029 0.6393895 0.3747343 0.6558606 0.3747343 0.6393895 0.5065029 0.6229183 0.3747343 0.6393895 0.3747343 0.6229183 0.5065029 0.6064473 0.3747343 0.6229183 0.3747343 0.6064473 0.5065029 0.5899763 0.3747343 0.6064473 0.3747343 0.5899763 0.5065029 0.5735051 0.3747343 0.5899763 0.3747343 0.5735051 0.5065029 0.557034 0.3747343 0.5735051 0.3747343 0.6336622 0.3441658 0.6384376 0.3201586 0.6384376 0.337019 0.557034 0.5065029 0.540563 0.3747343 0.557034 0.3747343 0.540563 0.5065029 0.5240918 0.3747343 0.540563 0.3747343 0.6436271 0.337019 0.6484024 0.3441658 0.6436271 0.3201586 0.7876291 0.5065029 0.7711581 0.3747343 0.7876291 0.3747343 0.7711581 0.5065029 0.754687 0.3747343 0.7711581 0.3747343 0.754687 0.5065029 0.7382159 0.3747343 0.754687 0.3747343 0.7382159 0.5065029 0.7217448 0.3747343 0.7382159 0.3747343 0.7217448 0.5065029 0.7052738 0.3747343 0.7217448 0.3747343 0.7052738 0.5065029 0.6888027 0.3747343 0.7052738 0.3747343 0.6888027 0.5065029 0.6723316 0.3747343 0.6888027 0.3747343 0.6723316 0.5065029 0.6558606 0.3747343 0.6723316 0.3747343 0.6558606 0.5065029 0.6393895 0.3747343 0.6558606 0.3747343 0.6393895 0.5065029 0.6229183 0.3747343 0.6393895 0.3747343 0.6229183 0.5065029 0.6064473 0.3747343 0.6229183 0.3747343 0.6064473 0.5065029 0.5899763 0.3747343 0.6064473 0.3747343 0.5899763 0.5065029 0.5735051 0.3747343 0.5899763 0.3747343 0.5735051 0.5065029 0.557034 0.3747343 0.5735051 0.3747343 0.6336622 0.3441658 0.6384376 0.3201586 0.6384376 0.337019 0.557034 0.5065029 0.540563 0.3747343 0.557034 0.3747343 0.540563 0.5065029 0.5240918 0.3747343 0.540563 0.3747343 0.6436271 0.337019 0.6484024 0.3441658 0.6436271 0.3201586 0.8830742 0.5371637 0.8830742 0.6446613 0.7755767 0.6446613 0.8830742 0.6446613 0.8830742 0.7521589 0.7755767 0.7521589 0.8830742 0.7521589 0.8830742 0.8596563 0.7755767 0.8596563 0.8830742 0.8596563 0.8830742 0.967154 0.7755767 0.967154 0.6916907 0.7749035 0.7007842 0.7699149 0.7015116 0.7715112 0.7116964 0.7878147 0.712424 0.7864776 0.7215175 0.7914665 0.7215175 0.7914665 0.7226087 0.7928034 0.72079 0.7928034 0.7226087 0.7928034 0.7226087 0.802781 0.72079 0.7928034 0.72079 0.7928034 0.7116964 0.7878147 0.7215175 0.7914665 0.72079 0.8027811 0.72079 0.7928034 0.7226087 0.802781 0.7116964 0.8077699 0.72079 0.8027811 0.7215175 0.8043774 0.72079 0.8027811 0.7226087 0.802781 0.7215175 0.8043774 0.7053052 0.7893851 0.7059861 0.7909474 0.7026028 0.7928034 0.7007842 0.7928034 0.7015116 0.7914666 0.7026028 0.7928034 0.7015116 0.7914666 0.7053052 0.7893851 0.7026028 0.7928034 0.7015116 0.8043774 0.7007842 0.8027811 0.7026028 0.8027811 0.7007842 0.8027811 0.7007842 0.7928034 0.7026028 0.8027811 0.7116964 0.8206809 0.7106053 0.8193438 0.7124238 0.8193438 0.7106053 0.8193438 0.7106053 0.8093662 0.7124238 0.8193438 0.7007842 0.7928034 0.7026028 0.7928034 0.7026028 0.8027811 0.7124238 0.8093662 0.7124238 0.8193438 0.7106053 0.8093662 0.7015116 0.8043774 0.7026028 0.8027811 0.7106053 0.8093662 0.7026028 0.8027811 0.7116964 0.8077699 0.7106053 0.8093662 0.7124238 0.8093662 0.7106053 0.8093662 0.7116964 0.8077699 0.740796 0.7928034 0.7317023 0.7878146 0.7415234 0.7914665 0.7317023 0.7878146 0.7324298 0.7864776 0.7415234 0.7914665 0.7415234 0.7914665 0.7426146 0.7928034 0.740796 0.7928034 0.7426146 0.8027811 0.7517083 0.8077697 0.7506169 0.8093662 0.7517083 0.8077697 0.7524357 0.8093662 0.7506169 0.8093662 0.7407959 0.8027811 0.740796 0.7928034 0.7426146 0.8027811 0.740796 0.7928034 0.7426146 0.7928034 0.7426146 0.8027811 0.7317023 0.8077697 0.7407959 0.8027811 0.7415234 0.8043774 0.7407959 0.8027811 0.7426146 0.8027811 0.7415234 0.8043774 0.7524357 0.8093662 0.7524357 0.8193438 0.7506169 0.8193438 0.7524357 0.8193438 0.7517083 0.8206809 0.7506169 0.8193438 0.7517083 0.8206809 0.7426146 0.8256697 0.7506169 0.8193438 0.7426146 0.8256697 0.7415234 0.8243326 0.7506169 0.8193438 0.7124238 0.8093662 0.7116964 0.8077699 0.7215175 0.8043774 0.7215175 0.8043774 0.7226087 0.802781 0.7306112 0.8093662 0.7226087 0.802781 0.7317023 0.8077697 0.7306112 0.8093662 0.7524357 0.8093662 0.7506169 0.8193438 0.7506169 0.8093662 0.7306112 0.8093662 0.7317023 0.8077697 0.7324298 0.8093662 0.7324298 0.8093662 0.7317023 0.8077697 0.7415234 0.8043774 0.7226087 0.8256697 0.7215175 0.8243326 0.7306112 0.8193438 0.7426146 0.8027811 0.7506169 0.8093662 0.7415234 0.8043774 0.7317023 0.8206809 0.7226087 0.8256697 0.7306112 0.8193438 0.7324298 0.8093662 0.7324298 0.8193438 0.7306112 0.8093662 0.7324298 0.8193438 0.7317023 0.8206809 0.7306112 0.8193438 0.7215175 0.7715112 0.7124238 0.7765001 0.7116964 0.7749035 0.7426146 0.7928034 0.7415234 0.7914665 0.7506169 0.7864776 0.7506169 0.7765001 0.7415234 0.7715112 0.7426146 0.7699149 0.7415234 0.7715112 0.740796 0.7699149 0.7426146 0.7699149 0.7517083 0.7878146 0.7426146 0.7928034 0.7506169 0.7864776 0.7517083 0.7878146 0.7506169 0.7864776 0.7524357 0.7864776 0.7506169 0.7864776 0.7506169 0.7765001 0.7524357 0.7864776 0.7524357 0.7765001 0.7524357 0.7864776 0.7506169 0.7765001 0.7426146 0.7699149 0.7517083 0.7749035 0.7506169 0.7765001 0.7517083 0.7749035 0.7524357 0.7765001 0.7506169 0.7765001 0.7226087 0.7699149 0.7317023 0.7749035 0.7306112 0.7765001 0.7317023 0.7749035 0.7324298 0.7765001 0.7306112 0.7765001 0.7324298 0.7765001 0.7324298 0.7864776 0.7306112 0.7864776 0.7324298 0.7864776 0.7317023 0.7878146 0.7306112 0.7864776 0.7317023 0.7878146 0.7226087 0.7928034 0.7306112 0.7864776 0.7226087 0.7928034 0.7215175 0.7914665 0.7306112 0.7864776 0.7426146 0.7699149 0.740796 0.7699149 0.7407959 0.7599372 0.7426146 0.7599373 0.7426146 0.7699149 0.7407959 0.7599372 0.7426146 0.7599373 0.7407959 0.7599372 0.7517083 0.7549485 0.7407959 0.7599372 0.7317023 0.7549484 0.7517083 0.7549485 0.7615292 0.7715112 0.7608018 0.7699149 0.7706229 0.7765001 0.7608018 0.7699149 0.7608018 0.7599373 0.7706229 0.7765001 0.7608018 0.7928034 0.7615292 0.7914665 0.7706229 0.7864776 0.7524357 0.8093662 0.7517083 0.8077697 0.7615292 0.8043774 0.7517083 0.8077697 0.7608018 0.8027811 0.7615292 0.8043774 0.7608018 0.8027811 0.7608018 0.7928034 0.7706229 0.7864776 0.7706229 0.8093662 0.7615292 0.8043774 0.7608018 0.8027811 0.7706229 0.8093662 0.7608018 0.8027811 0.7706229 0.7864776 0.7306112 0.7765001 0.7215175 0.7715112 0.7226087 0.7699149 0.7215175 0.7715112 0.72079 0.7699149 0.7226087 0.7699149 0.7324298 0.7765001 0.7306112 0.7864776 0.7306112 0.7765001 0.7026028 0.7699149 0.7116964 0.7749035 0.7106053 0.7765001 0.7116964 0.7749035 0.7124238 0.7765001 0.7106053 0.7765001 0.7124238 0.7765001 0.712424 0.7864776 0.7106053 0.7864776 0.712424 0.7864776 0.7116964 0.7878147 0.7106053 0.7864776 0.7116964 0.7878147 0.7059861 0.7909474 0.7106053 0.7864776 0.7059861 0.7909474 0.7053052 0.7893851 0.7106053 0.7864776 0.7226087 0.7599373 0.7226087 0.7699149 0.72079 0.7699149 0.7226087 0.7599373 0.72079 0.7699149 0.72079 0.7599373 0.7317023 0.7549484 0.7226087 0.7599373 0.72079 0.7599373 0.7317023 0.7549484 0.72079 0.7599373 0.7116964 0.7549485 0.7106053 0.7765001 0.7015116 0.7715112 0.7026028 0.7699149 0.7015116 0.7715112 0.7007842 0.7699149 0.7026028 0.7699149 0.7124238 0.7765001 0.7106053 0.7864776 0.7106053 0.7765001 0.682597 0.7699149 0.6916907 0.7749035 0.6905995 0.7765001 0.6916907 0.7749035 0.6924195 0.7764993 0.6924181 0.7765001 0.6916907 0.7749035 0.6924181 0.7765001 0.6905995 0.7765001 0.6924181 0.7864776 0.7015116 0.7914666 0.6916907 0.7878146 0.7015116 0.7914666 0.7007842 0.7928034 0.6916907 0.7878146 0.6916907 0.7878146 0.6905993 0.7864776 0.6924181 0.7864776 0.7026028 0.7599373 0.7026028 0.7699149 0.7007842 0.7699149 0.7026028 0.7599373 0.7007842 0.7699149 0.7007842 0.7599373 0.7116964 0.7549485 0.7026028 0.7599373 0.7007842 0.7599373 0.7116964 0.7549485 0.7007842 0.7599373 0.6916907 0.7549484 0.6924181 0.7765001 0.6924181 0.7864776 0.6905993 0.7864776 0.6924181 0.7765001 0.6905993 0.7864776 0.6905995 0.7765001 0.682597 0.7699149 0.6905995 0.7765001 0.6815058 0.7715112 0.682597 0.7599373 0.682597 0.7699149 0.6815058 0.7715112 0.682597 0.7599373 0.6815058 0.7715112 0.6724122 0.7765001 0.6724122 0.7864776 0.6815058 0.7914666 0.6815058 0.8043774 0.6815058 0.7914666 0.682597 0.7928034 0.682597 0.8027811 0.6815058 0.7914666 0.682597 0.8027811 0.6815058 0.8043774 0.6916907 0.8077697 0.7007842 0.8027811 0.7015116 0.8043774 0.6924181 0.8093662 0.6924181 0.8193438 0.6905995 0.8193438 0.6924181 0.8193438 0.6916907 0.8206809 0.6905995 0.8193438 0.6916907 0.8077697 0.7015116 0.8043774 0.6924181 0.8093662 0.682597 0.8027811 0.6916907 0.8077697 0.6905993 0.8093662 0.6916907 0.8077697 0.6924181 0.8093662 0.6905993 0.8093662 0.6924181 0.8093662 0.6905995 0.8193438 0.6905993 0.8093662 0.682597 0.8027811 0.6905993 0.8093662 0.6815058 0.8043774 0.6724122 0.7864776 0.6815058 0.8043774 0.6724122 0.8093662 0.6724122 0.8193438 0.6815058 0.8243326 0.6815058 0.8372436 0.6815058 0.8243326 0.682597 0.8256697 0.682597 0.8356472 0.6815058 0.8243326 0.682597 0.8356472 0.6815058 0.8372436 0.6916907 0.840636 0.7007842 0.8356472 0.7015116 0.8372436 0.7015116 0.8372436 0.6924181 0.8422324 0.6916907 0.840636 0.6924181 0.8422324 0.6905995 0.8422324 0.6916907 0.840636 0.682597 0.8356472 0.6916907 0.840636 0.6905995 0.8422324 0.682597 0.8356472 0.6905995 0.8422324 0.6815058 0.8372436 0.6724122 0.8422324 0.6724122 0.8522101 0.6680789 0.8596563 0.6724122 0.8193438 0.6815058 0.8372436 0.6724122 0.8422324 0.6724122 0.8093662 0.6724122 0.8193438 0.6680789 0.8596563 0.6724122 0.8193438 0.6724122 0.8422324 0.6680789 0.8596563 0.6680789 0.8596563 0.6680789 0.7521589 0.6724122 0.8093662 0.7755767 0.7521589 0.7755767 0.8596563 0.7706229 0.8093662 0.7755767 0.8596563 0.7706229 0.8522101 0.7706229 0.8422324 0.7755767 0.8596563 0.7706229 0.8422324 0.7706229 0.8193438 0.7706229 0.8093662 0.7755767 0.8596563 0.7706229 0.8193438 0.6724122 0.7864776 0.6724122 0.8093662 0.6680789 0.7521589 0.7615292 0.8372436 0.7524357 0.8422324 0.7517083 0.840636 0.7615292 0.8372436 0.7517083 0.840636 0.7608018 0.8356472 0.6724122 0.7765001 0.6724122 0.7864776 0.6680789 0.7521589 0.682597 0.7599373 0.6724122 0.7765001 0.6680789 0.7521589 0.7706229 0.8422324 0.7615292 0.8372436 0.7608018 0.8356472 0.7608018 0.8256697 0.7517083 0.8206809 0.7615292 0.8243326 0.7517083 0.8206809 0.7524357 0.8193438 0.7615292 0.8243326 0.7706229 0.8422324 0.7608018 0.8356472 0.7706229 0.8193438 0.7608018 0.8356472 0.7608018 0.8256697 0.7706229 0.8193438 0.6916907 0.7549484 0.682597 0.7599373 0.6680789 0.7521589 0.7116964 0.7549485 0.6916907 0.7549484 0.6680789 0.7521589 0.7608018 0.8256697 0.7615292 0.8243326 0.7706229 0.8193438 0.7116964 0.7549485 0.6680789 0.7521589 0.7317023 0.7549484 0.6680789 0.7521589 0.7755767 0.7521589 0.7317023 0.7549484 0.7517083 0.7549485 0.7317023 0.7549484 0.7755767 0.7521589 0.7608018 0.7599373 0.7517083 0.7549485 0.7755767 0.7521589 0.7755767 0.7521589 0.7706229 0.8093662 0.7706229 0.7864776 0.7706229 0.7765001 0.7608018 0.7599373 0.7755767 0.7521589 0.7615292 0.7914665 0.7608018 0.7928034 0.7517083 0.7878146 0.7517083 0.7749035 0.7608018 0.7699149 0.7615292 0.7715112 0.7415234 0.7715112 0.7324298 0.7765001 0.7317023 0.7749035 0.6905995 0.8193438 0.6916907 0.8206809 0.682597 0.8256697 0.6905993 0.7864776 0.6916907 0.7878146 0.682597 0.7928034 0.7215175 0.8372436 0.7124238 0.8422324 0.7116964 0.840636 0.7215175 0.8243326 0.72079 0.8256697 0.7116964 0.8206809 0.7317023 0.840636 0.740796 0.8356472 0.7415234 0.8372436 0.7015116 0.8243326 0.7106053 0.8193438 0.7026028 0.8256697 0.7106053 0.8193438 0.7116964 0.8206809 0.7026028 0.8256697 0.6916907 0.8206809 0.6924181 0.8193438 0.7015116 0.8243326 0.7015116 0.8372436 0.7007842 0.8356472 0.7026028 0.8356472 0.7007842 0.8356472 0.7007842 0.8256697 0.7026028 0.8356472 0.7007842 0.8256697 0.6916907 0.8206809 0.7015116 0.8243326 0.7015116 0.8243326 0.7026028 0.8256697 0.7007842 0.8256697 0.7026028 0.8256697 0.7026028 0.8356472 0.7007842 0.8256697 0.7026028 0.8356472 0.7116964 0.840636 0.7106053 0.8422324 0.7116964 0.840636 0.7124238 0.8422324 0.7106053 0.8422324 0.6905995 0.8422324 0.6924181 0.8422324 0.6924181 0.8522101 0.6905993 0.8522101 0.6905995 0.8422324 0.6924181 0.8522101 0.6905993 0.8522101 0.6924181 0.8522101 0.6815058 0.8571988 0.6924181 0.8522101 0.7015116 0.8571988 0.6815058 0.8571988 0.6680789 0.8596563 0.6724122 0.8522101 0.6815058 0.8571988 0.6680789 0.8596563 0.6815058 0.8571988 0.7015116 0.8571988 0.7615292 0.8571989 0.7706229 0.8522101 0.7755767 0.8596563 0.7517083 0.840636 0.7524357 0.8422324 0.7506169 0.8422324 0.7524357 0.8422324 0.7524357 0.8522101 0.7506169 0.8522101 0.7615292 0.8571989 0.7755767 0.8596563 0.7415234 0.8571989 0.7755767 0.8596563 0.6680789 0.8596563 0.7215175 0.8571989 0.7415234 0.8571989 0.7755767 0.8596563 0.7215175 0.8571989 0.7306112 0.8422324 0.7215175 0.8372436 0.7226087 0.8356472 0.7215175 0.8372436 0.72079 0.8356472 0.7226087 0.8356472 0.72079 0.8356472 0.72079 0.8256697 0.7226087 0.8356472 0.72079 0.8256697 0.7215175 0.8243326 0.7226087 0.8256697 0.7226087 0.8356472 0.72079 0.8256697 0.7226087 0.8256697 0.7226087 0.8356472 0.7317023 0.840636 0.7306112 0.8422324 0.7317023 0.840636 0.7324298 0.8422324 0.7306112 0.8422324 0.7506169 0.8422324 0.7415234 0.8372436 0.7426146 0.8356472 0.7415234 0.8372436 0.740796 0.8356472 0.7426146 0.8356472 0.740796 0.8256697 0.7317023 0.8206809 0.7415234 0.8243326 0.7317023 0.8206809 0.7324298 0.8193438 0.7415234 0.8243326 0.7306112 0.8522101 0.7306112 0.8422324 0.7324298 0.8422324 0.7306112 0.8522101 0.7324298 0.8422324 0.7324298 0.8522101 0.7215175 0.8571989 0.7306112 0.8522101 0.7324298 0.8522101 0.7215175 0.8571989 0.7324298 0.8522101 0.7415234 0.8571989 0.7415234 0.8243326 0.7426146 0.8256697 0.740796 0.8256697 0.7426146 0.8256697 0.7426146 0.8356472 0.740796 0.8256697 0.7106053 0.8422324 0.7015116 0.8372436 0.7026028 0.8356472 0.740796 0.8356472 0.740796 0.8256697 0.7426146 0.8356472 0.7106053 0.8422324 0.7124238 0.8422324 0.712424 0.8522101 0.7106053 0.8522101 0.7106053 0.8422324 0.712424 0.8522101 0.7106053 0.8522101 0.712424 0.8522101 0.7015116 0.8571988 0.712424 0.8522101 0.7215175 0.8571989 0.7015116 0.8571988 0.7015116 0.8571988 0.7215175 0.8571989 0.6680789 0.8596563 0.7506169 0.8422324 0.7426146 0.8356472 0.7517083 0.840636 0.7506169 0.8522101 0.7506169 0.8422324 0.7524357 0.8422324 0.7415234 0.8571989 0.7506169 0.8522101 0.7524357 0.8522101 0.9760536 0.8256697 0.96696 0.8206809 0.9680513 0.8193438 0.9760536 0.7928034 0.96696 0.7878146 0.9680513 0.7864776 0.96696 0.7749035 0.9662328 0.7765001 0.9571389 0.7715112 0.9571389 0.8243326 0.9662328 0.8193438 0.96696 0.8206809 0.9578667 0.8256697 0.9578664 0.8356472 0.9560479 0.8256697 0.9578664 0.8356472 0.9571389 0.8372436 0.9560479 0.8356472 0.9560479 0.8256697 0.9578664 0.8356472 0.9560479 0.8356472 0.9571389 0.8243326 0.96696 0.8206809 0.9578667 0.8256697 0.9469543 0.8206809 0.9480454 0.8193438 0.9560479 0.8256697 0.9480454 0.8193438 0.9571389 0.8243326 0.9560479 0.8256697 0.9571389 0.8243326 0.9578667 0.8256697 0.9560479 0.8256697 0.9462268 0.8422324 0.9469543 0.840636 0.9480454 0.8422324 0.9469543 0.840636 0.9560479 0.8356472 0.9480454 0.8422324 0.9560479 0.8356472 0.9571389 0.8372436 0.9480454 0.8422324 0.9378607 0.8356472 0.9371333 0.8372436 0.9360421 0.8356472 0.9371333 0.8372436 0.9280397 0.8422324 0.9360421 0.8356472 0.9371333 0.8243326 0.9378607 0.8256697 0.9360421 0.8256697 0.9378607 0.8256697 0.9378607 0.8356472 0.9360421 0.8256697 0.9269483 0.8206809 0.9280397 0.8193438 0.9360421 0.8256697 0.9280397 0.8193438 0.9371333 0.8243326 0.9360421 0.8256697 0.9462268 0.8422324 0.9480454 0.8422324 0.9480454 0.8522101 0.9462268 0.8522101 0.9462268 0.8422324 0.9480454 0.8522101 0.9571389 0.8571988 0.9662328 0.8522101 0.9771448 0.8571989 0.9662328 0.8522101 0.9680513 0.8522101 0.9771448 0.8571989 0.9462268 0.8522101 0.9480454 0.8522101 0.9571389 0.8571988 0.9371333 0.8571989 0.9462268 0.8522101 0.9571389 0.8571988 0.9771448 0.8571989 0.9862385 0.8522101 0.9905717 0.8596563 0.8830742 0.8596563 0.8880279 0.8522101 0.8971214 0.8571989 0.906215 0.8522101 0.906215 0.8422324 0.9080338 0.8522101 0.906215 0.8422324 0.9069426 0.840636 0.9080338 0.8422324 0.9080338 0.8522101 0.906215 0.8422324 0.9080338 0.8422324 0.9905717 0.8596563 0.8830742 0.8596563 0.9371333 0.8571989 0.8830742 0.8596563 0.8971214 0.8571989 0.9171273 0.8571989 0.9571389 0.8571988 0.9771448 0.8571989 0.9905717 0.8596563 0.9371333 0.8571989 0.9571389 0.8571988 0.9905717 0.8596563 0.9160363 0.8356472 0.9160363 0.8256697 0.9178549 0.8256697 0.9160363 0.8256697 0.9171273 0.8243326 0.9178549 0.8256697 0.9178549 0.8256697 0.9178549 0.8356472 0.9160363 0.8356472 0.9178549 0.8356472 0.9171273 0.8372436 0.9160363 0.8356472 0.9171273 0.8372436 0.9080338 0.8422324 0.9160363 0.8356472 0.9262209 0.8422324 0.9269483 0.840636 0.9280397 0.8422324 0.9269483 0.840636 0.9360421 0.8356472 0.9280397 0.8422324 0.9360421 0.8356472 0.9360421 0.8256697 0.9378607 0.8356472 0.9262209 0.8522101 0.9262209 0.8422324 0.9280397 0.8422324 0.9262209 0.8522101 0.9280397 0.8422324 0.9280397 0.8522101 0.9171273 0.8571989 0.9262209 0.8522101 0.9371333 0.8571989 0.9262209 0.8522101 0.9280397 0.8522101 0.9371333 0.8571989 0.9171273 0.8571989 0.9371333 0.8571989 0.8830742 0.8596563 0.9069426 0.840636 0.9160363 0.8356472 0.9080338 0.8422324 0.906215 0.8522101 0.9080338 0.8522101 0.9171273 0.8571989 0.9578667 0.7928034 0.9578667 0.802781 0.9560479 0.7928034 0.9578667 0.802781 0.9571389 0.8043774 0.9560479 0.8027811 0.9560479 0.7928034 0.9578667 0.802781 0.9560479 0.8027811 0.9480454 0.8093662 0.9480454 0.8193438 0.9462268 0.8193438 0.9480454 0.8193438 0.9469543 0.8206809 0.9462268 0.8193438 0.9662328 0.7864776 0.96696 0.7878146 0.9571393 0.7914666 0.96696 0.7878146 0.9578667 0.7928034 0.9571393 0.7914666 0.9560479 0.7928034 0.9571393 0.7914666 0.9578667 0.7928034 0.9469543 0.8206809 0.9378607 0.8256697 0.9371333 0.8243326 0.9469543 0.8206809 0.9371333 0.8243326 0.9462268 0.8193438 0.9480454 0.8093662 0.9462268 0.8193438 0.9462268 0.8093662 0.9571389 0.8043774 0.9480454 0.8093662 0.9560479 0.8027811 0.9480454 0.8093662 0.9462268 0.8093662 0.9469543 0.8077699 0.9560479 0.8027811 0.9480454 0.8093662 0.9469543 0.8077699 0.9469543 0.8077699 0.9462268 0.8093662 0.9371333 0.8043774 0.9378607 0.8027811 0.9469543 0.8077699 0.9371333 0.8043774 0.9280397 0.8093662 0.9280397 0.8193438 0.9262209 0.8193438 0.9280397 0.8193438 0.9269483 0.8206809 0.9262209 0.8193438 0.9378607 0.8027811 0.9371333 0.8043774 0.936042 0.8027811 0.9371333 0.8043774 0.9280397 0.8093662 0.936042 0.8027811 0.9462268 0.7864776 0.9469543 0.7878147 0.9371333 0.7914666 0.9469543 0.7878147 0.9378607 0.7928034 0.9371333 0.7914666 0.9280397 0.8093662 0.9262209 0.8193438 0.9262209 0.8093662 0.936042 0.8027811 0.936042 0.7928034 0.9378607 0.7928034 0.936042 0.7928034 0.9371333 0.7914666 0.9378607 0.7928034 0.9280397 0.8093662 0.9262209 0.8093662 0.9269483 0.8077697 0.936042 0.8027811 0.9378607 0.7928034 0.9378607 0.8027811 0.9269483 0.8077697 0.936042 0.8027811 0.9280397 0.8093662 0.9080338 0.8193438 0.9171273 0.8243326 0.9160363 0.8256697 0.9160363 0.8256697 0.9069426 0.8206809 0.9080338 0.8193438 0.9069426 0.8206809 0.906215 0.8193438 0.9080338 0.8193438 0.906215 0.8193438 0.906215 0.8093662 0.9080338 0.8093662 0.906215 0.8093662 0.9069426 0.8077699 0.9080338 0.8093662 0.9080338 0.8093662 0.9080338 0.8193438 0.906215 0.8193438 0.9069426 0.7878147 0.8978489 0.7928034 0.8971214 0.7914665 0.9069426 0.7878147 0.8971214 0.7914665 0.906215 0.7864776 0.9160363 0.7928034 0.9069426 0.7878147 0.9080338 0.7864776 0.9069426 0.7878147 0.906215 0.7864776 0.9080338 0.7864776 0.906215 0.7765001 0.8971214 0.7715112 0.9069426 0.7749035 0.8971214 0.7715112 0.8978489 0.7699149 0.9069426 0.7749035 0.9171273 0.8043774 0.9080338 0.8093662 0.9160363 0.8027811 0.9080338 0.8093662 0.9069426 0.8077699 0.9160363 0.8027811 0.9171273 0.7914665 0.9178549 0.7928034 0.9160363 0.7928034 0.9178549 0.7928034 0.9178549 0.8027811 0.9160363 0.7928034 0.9178549 0.8027811 0.9269483 0.8077697 0.9171273 0.8043774 0.9269483 0.8077697 0.9262209 0.8093662 0.9171273 0.8043774 0.9171273 0.8043774 0.9160363 0.8027811 0.9178549 0.8027811 0.9269483 0.7749035 0.9262209 0.7765001 0.9171273 0.7715112 0.9160363 0.7699149 0.9178549 0.7699149 0.9171273 0.7715112 0.9178549 0.7699149 0.9269483 0.7749035 0.9171273 0.7715112 0.9160363 0.7699149 0.9171273 0.7715112 0.9080338 0.7765001 0.906215 0.7765001 0.9069426 0.7749035 0.9080338 0.7765001 0.9069426 0.7749035 0.9160363 0.7699149 0.9080338 0.7765001 0.9178549 0.8027811 0.9160363 0.8027811 0.9160363 0.7928034 0.906215 0.7765001 0.9080338 0.7765001 0.9080338 0.7864776 0.9080338 0.7864776 0.9171273 0.7914665 0.9160363 0.7928034 0.9371333 0.7715112 0.9378607 0.7699149 0.9469543 0.7749035 0.9469543 0.840636 0.9462268 0.8422324 0.9371333 0.8372436 0.9269483 0.840636 0.9262209 0.8422324 0.9171273 0.8372436 0.9269483 0.8206809 0.9178549 0.8256697 0.9171273 0.8243326 0.9262209 0.7864776 0.9262209 0.7765001 0.9280397 0.7765001 0.9262209 0.7765001 0.9269483 0.7749035 0.9280397 0.7765001 0.9178549 0.7928034 0.9171273 0.7914665 0.9269483 0.7878146 0.9171273 0.7914665 0.9262209 0.7864776 0.9269483 0.7878146 0.9371333 0.7914666 0.936042 0.7928034 0.9280397 0.7864776 0.936042 0.7928034 0.9269483 0.7878146 0.9280397 0.7864776 0.9178549 0.7599373 0.9178549 0.7699149 0.9160363 0.7699149 0.9178549 0.7599373 0.9160363 0.7699149 0.9160363 0.7599373 0.9269483 0.7549485 0.9178549 0.7599373 0.9160363 0.7599373 0.9269483 0.7549485 0.9160363 0.7599373 0.9069426 0.7549485 0.8978489 0.7599372 0.8978489 0.7699149 0.8880279 0.7765001 0.8978489 0.7699149 0.8971214 0.7715112 0.8880279 0.7765001 0.8880279 0.7864776 0.8971214 0.7914665 0.8978489 0.7928034 0.8978491 0.8027811 0.9069426 0.8077699 0.8971214 0.8043774 0.9069426 0.8077699 0.906215 0.8093662 0.8971214 0.8043774 0.8880279 0.7864776 0.8978489 0.7928034 0.8978491 0.8027811 0.8978491 0.8027811 0.8971214 0.8043774 0.8880279 0.8093662 0.8880279 0.7864776 0.8978491 0.8027811 0.8880279 0.8093662 0.9269483 0.7878146 0.9262209 0.7864776 0.9280397 0.7864776 0.9378607 0.7699149 0.9371333 0.7715112 0.9360421 0.7699149 0.9371333 0.7715112 0.9280397 0.7765001 0.9360421 0.7699149 0.9280397 0.7765001 0.9280397 0.7864776 0.9262209 0.7864776 0.8971213 0.8243326 0.906215 0.8193438 0.9069426 0.8206809 0.8971213 0.8243326 0.9069426 0.8206809 0.8978491 0.8256697 0.8880279 0.8193438 0.8971213 0.8243326 0.8978491 0.8256697 0.8978491 0.8356472 0.9069426 0.840636 0.8971214 0.8372436 0.9069426 0.840636 0.906215 0.8422324 0.8971214 0.8372436 0.8880279 0.8193438 0.8978491 0.8256697 0.8978491 0.8356472 0.8880279 0.8422324 0.8880279 0.8522101 0.8830742 0.8596563 0.8978491 0.8356472 0.8971214 0.8372436 0.8880279 0.8422324 0.8880279 0.8193438 0.8978491 0.8356472 0.8880279 0.8422324 0.8880279 0.8422324 0.8830742 0.8596563 0.8880279 0.8193438 0.8830742 0.8596563 0.8830742 0.7521589 0.8880279 0.8093662 0.8880279 0.8193438 0.8830742 0.8596563 0.8880279 0.8093662 0.9905717 0.7521589 0.9905717 0.8596563 0.9862385 0.8093662 0.9905717 0.8596563 0.9862385 0.8522101 0.9862385 0.8422324 0.9905717 0.8596563 0.9862385 0.8422324 0.9862385 0.8193438 0.9862385 0.8093662 0.9905717 0.8596563 0.9862385 0.8193438 0.9680513 0.8422324 0.9680513 0.8522101 0.9662328 0.8522101 0.9662328 0.8422324 0.9571389 0.8372436 0.9669602 0.840636 0.9571389 0.8372436 0.9578664 0.8356472 0.9669602 0.840636 0.9680513 0.8422324 0.9662328 0.8522101 0.9662328 0.8422324 0.9771448 0.8372436 0.9680513 0.8422324 0.9760536 0.8356472 0.9680513 0.8422324 0.9662328 0.8422324 0.9669602 0.840636 0.9760536 0.8356472 0.9680513 0.8422324 0.9669602 0.840636 0.9760536 0.8356472 0.9760536 0.8256697 0.9771448 0.8243326 0.9760536 0.8356472 0.9771448 0.8243326 0.9771448 0.8372436 0.9771448 0.8243326 0.9862385 0.8193438 0.9771448 0.8372436 0.8880279 0.7864776 0.8880279 0.8093662 0.8830742 0.7521589 0.8880279 0.7765001 0.8880279 0.7864776 0.8830742 0.7521589 0.9862385 0.8422324 0.9771448 0.8372436 0.9862385 0.8193438 0.8978489 0.7599372 0.8880279 0.7765001 0.8830742 0.7521589 0.9069426 0.7549485 0.8978489 0.7599372 0.8830742 0.7521589 0.9069426 0.7549485 0.8830742 0.7521589 0.9269483 0.7549485 0.8830742 0.7521589 0.9905717 0.7521589 0.9269483 0.7549485 0.9680513 0.8093662 0.9680513 0.8193438 0.9662328 0.8193438 0.9680513 0.8193438 0.96696 0.8206809 0.9662328 0.8193438 0.9662328 0.8193438 0.9662328 0.8093662 0.9680513 0.8093662 0.9662328 0.8093662 0.9571389 0.8043774 0.96696 0.8077697 0.9571389 0.8043774 0.9578667 0.802781 0.96696 0.8077697 0.9771448 0.8043774 0.9680513 0.8093662 0.9760536 0.8027811 0.9680513 0.8093662 0.9662328 0.8093662 0.96696 0.8077697 0.9760536 0.8027811 0.9680513 0.8093662 0.96696 0.8077697 0.9760536 0.8027811 0.9760536 0.7928034 0.9771448 0.7914666 0.9760536 0.8027811 0.9771448 0.7914666 0.9771448 0.8043774 0.9771448 0.7914666 0.9862385 0.7864776 0.9771448 0.8043774 0.9462268 0.7765001 0.9469543 0.7749035 0.9480454 0.7765001 0.9469543 0.7749035 0.9560479 0.7699149 0.9480454 0.7765001 0.9469543 0.7878147 0.9462268 0.7864776 0.9480454 0.7864776 0.9462268 0.7864776 0.9462268 0.7765001 0.9480454 0.7864776 0.9571393 0.7914666 0.9560479 0.7928034 0.9480454 0.7864776 0.9560479 0.7928034 0.9469543 0.7878147 0.9480454 0.7864776 0.9280397 0.7765001 0.9269483 0.7749035 0.9360421 0.7699149 0.9378607 0.7599373 0.9378607 0.7699149 0.9360421 0.7699149 0.9378607 0.7599373 0.9360421 0.7699149 0.936042 0.7599373 0.9469543 0.7549485 0.9378607 0.7599373 0.9269483 0.7549485 0.9378607 0.7599373 0.936042 0.7599373 0.9269483 0.7549485 0.9862385 0.8093662 0.9771448 0.8043774 0.9862385 0.7864776 0.9469543 0.7549485 0.9269483 0.7549485 0.9905717 0.7521589 0.9905717 0.7521589 0.9862385 0.8093662 0.9862385 0.7864776 0.9905717 0.7521589 0.9862385 0.7864776 0.9862385 0.7765001 0.9578664 0.7699149 0.9571389 0.7715112 0.9560479 0.7699149 0.9571389 0.7715112 0.9480454 0.7765001 0.9560479 0.7699149 0.9480454 0.7765001 0.9480454 0.7864776 0.9462268 0.7765001 0.9662328 0.7765001 0.96696 0.7749035 0.9680513 0.7765001 0.96696 0.7749035 0.9760536 0.7699149 0.9680513 0.7765001 0.96696 0.7878146 0.9662328 0.7864776 0.9680513 0.7864776 0.9662328 0.7864776 0.9662328 0.7765001 0.9680513 0.7765001 0.9680513 0.7765001 0.9680513 0.7864776 0.9662328 0.7864776 0.9905717 0.7521589 0.9862385 0.7765001 0.9760536 0.7599373 0.9862385 0.7765001 0.9771448 0.7715112 0.9760536 0.7599373 0.9578667 0.7599373 0.9578664 0.7699149 0.9560479 0.7699149 0.9578667 0.7599373 0.9560479 0.7699149 0.9560478 0.7599372 0.9669602 0.7549484 0.9578667 0.7599373 0.9560478 0.7599372 0.9771448 0.7715112 0.9680513 0.7765001 0.9760536 0.7699149 0.9669602 0.7549484 0.9560478 0.7599372 0.9469543 0.7549485 0.9771448 0.7715112 0.9760536 0.7699149 0.9760536 0.7599373 0.9669602 0.7549484 0.9469543 0.7549485 0.9905717 0.7521589 0.3355668 0.5470865 0.3355668 0.5822256 0.3625472 0.5822257 0.3355668 0.6173651 0.3625472 0.6173651 0.3625472 0.5822257 0.3355668 0.6525043 0.3625472 0.6525043 0.3625472 0.6173651 0.3355668 0.6876436 0.3625472 0.6876436 0.3625472 0.6525043 0.3355668 0.6876436 0.3355668 0.7227829 0.3625472 0.7227829 0.3355668 0.7227829 0.3355668 0.7579222 0.3625472 0.7579222 0.3629911 0.5470865 0.3629911 0.5822256 0.3899714 0.5822257 0.3629911 0.6173651 0.3899714 0.6173651 0.3899714 0.5822257 0.3629911 0.6525043 0.3899714 0.6525043 0.3899714 0.6173651 0.3629911 0.6876436 0.3899714 0.6876436 0.3899714 0.6525043 0.3629911 0.6876436 0.3629911 0.7227829 0.3899714 0.7227829 0.3629911 0.7227829 0.3629911 0.7579222 0.3899714 0.7579222 0.3904153 0.5470865 0.3904153 0.5822256 0.4173957 0.5822257 0.3904153 0.6173651 0.4173957 0.6173651 0.4173957 0.5822257 0.3904153 0.6525043 0.4173957 0.6525043 0.4173957 0.6173651 0.3904153 0.6876436 0.4173957 0.6876436 0.4173957 0.6525043 0.3904153 0.6876436 0.3904153 0.7227829 0.4173957 0.7227829 0.3904153 0.7227829 0.3904153 0.7579222 0.4173957 0.7579222 0.4178395 0.5470865 0.4178395 0.5822256 0.4448199 0.5822257 0.4178395 0.6173651 0.4448199 0.6173651 0.4448199 0.5822257 0.4178395 0.6525043 0.4448199 0.6525043 0.4448199 0.6173651 0.4178395 0.6876436 0.4448199 0.6876436 0.4448199 0.6525043 0.4178395 0.6876436 0.4178395 0.7227829 0.4448199 0.7227829 0.4178395 0.7227829 0.4178395 0.7579222 0.4448199 0.7579222 0.4452638 0.5470865 0.4452638 0.5822256 0.4722442 0.5822257 0.4452638 0.6173651 0.4722442 0.6173651 0.4722442 0.5822257 0.4452638 0.6525043 0.4722442 0.6525043 0.4722442 0.6173651 0.4452638 0.6876436 0.4722442 0.6876436 0.4722442 0.6525043 0.4452638 0.6876436 0.4452638 0.7227829 0.4722442 0.7227829 0.4452638 0.7227829 0.4452638 0.7579222 0.4722442 0.7579222 0.472688 0.5470865 0.472688 0.5822256 0.4996684 0.5822257 0.472688 0.6173651 0.4996684 0.6173651 0.4996684 0.5822257 0.472688 0.6525043 0.4996684 0.6525043 0.4996684 0.6173651 0.472688 0.6876436 0.4996684 0.6876436 0.4996684 0.6525043 0.472688 0.6876436 0.472688 0.7227829 0.4996684 0.7227829 0.472688 0.7227829 0.472688 0.7579222 0.4996684 0.7579222 0.5001122 0.5470865 0.5001122 0.5822257 0.5270928 0.5822256 0.5001122 0.6173651 0.5270928 0.6173651 0.5270928 0.5822256 0.5001122 0.6525043 0.5270928 0.6525043 0.5270928 0.6173651 0.5001122 0.6876436 0.5270928 0.6876436 0.5270928 0.6525043 0.5001122 0.6876436 0.5001122 0.7227829 0.5270928 0.7227829 0.5001122 0.7227829 0.5001122 0.7579222 0.5270928 0.7579222 0.5275364 0.5470865 0.5275364 0.5822256 0.554517 0.5822256 0.5275364 0.6173651 0.554517 0.6173651 0.554517 0.5822256 0.5275364 0.6525043 0.554517 0.6525043 0.554517 0.6173651 0.5275364 0.6876436 0.554517 0.6876436 0.554517 0.6525043 0.5275364 0.6876436 0.5275364 0.7227829 0.554517 0.7227829 0.5275364 0.7227829 0.5275364 0.7579222 0.554517 0.7579222 0.5549607 0.5470865 0.5549607 0.5822256 0.5819413 0.5822256 0.554961 0.6173651 0.5819413 0.6173651 0.5819413 0.5822256 0.554961 0.6525043 0.5819413 0.6525043 0.5819413 0.6173651 0.554961 0.6876436 0.5819413 0.6876436 0.5819413 0.6525043 0.554961 0.6876436 0.554961 0.7227829 0.5819413 0.7227829 0.554961 0.7227829 0.554961 0.7579222 0.5819413 0.7579222 0.01746535 0.542943 0.01746535 0.6154952 0.07317203 0.6154952 0.01746541 0.6880474 0.07317203 0.6880474 0.07317203 0.6154952 0.01746541 0.7605998 0.07317203 0.7605998 0.07317203 0.6880474 0.01746541 0.8331519 0.07317203 0.8331519 0.07317203 0.7605998 0.01746541 0.8331519 0.01746541 0.9057043 0.07317203 0.9057043 0.01746541 0.9057043 0.01746541 0.9782566 0.07317203 0.9782566 0.07408839 0.542943 0.07408839 0.6154952 0.129795 0.6154952 0.07408839 0.6880474 0.129795 0.6880474 0.129795 0.6154952 0.07408839 0.7605998 0.129795 0.7605998 0.129795 0.6880474 0.07408839 0.8331519 0.129795 0.8331519 0.129795 0.7605998 0.07408839 0.8331519 0.07408839 0.9057043 0.129795 0.9057043 0.07408839 0.9057043 0.07408839 0.9782566 0.129795 0.9782566 0.1307113 0.542943 0.1307113 0.6154952 0.186418 0.6154952 0.1307113 0.6880474 0.186418 0.6880474 0.186418 0.6154952 0.1307113 0.7605998 0.186418 0.7605996 0.186418 0.6880474 0.1307113 0.8331519 0.186418 0.8331519 0.186418 0.7605996 0.1307113 0.8331519 0.1307113 0.9057043 0.186418 0.9057043 0.1307113 0.9057043 0.1307113 0.9782566 0.186418 0.9782566 0.1873343 0.542943 0.1873343 0.6154952 0.243041 0.6154952 0.1873343 0.6880474 0.243041 0.6880474 0.243041 0.6154952 0.1873343 0.7605998 0.243041 0.7605998 0.243041 0.6880474 0.1873343 0.8331519 0.243041 0.8331519 0.243041 0.7605998 0.1873343 0.8331519 0.1873343 0.9057043 0.243041 0.9057043 0.1873343 0.9057043 0.1873343 0.9782566 0.243041 0.9782566 0.2439573 0.542943 0.2439574 0.6154952 0.299664 0.6154952 0.2439574 0.6880474 0.299664 0.6880474 0.299664 0.6154952 0.2439574 0.7605996 0.299664 0.7605998 0.299664 0.6880474 0.2439574 0.8331519 0.299664 0.8331519 0.299664 0.7605998 0.2439574 0.8331519 0.2439574 0.9057043 0.299664 0.9057043 0.2439574 0.9057043 0.2439574 0.9782566 0.299664 0.9782566 0.3355668 0.7583661 0.3355668 0.7935053 0.3625472 0.7935054 0.3355668 0.8286446 0.3625472 0.8286446 0.3625472 0.7935054 0.3355668 0.8637839 0.3625472 0.8637839 0.3625472 0.8286446 0.3355668 0.8989232 0.3625472 0.8989232 0.3625472 0.8637839 0.3355668 0.8989232 0.3355668 0.9340626 0.3625472 0.9340626 0.3355668 0.9340626 0.3355668 0.9692018 0.3625472 0.9692018 0.3629911 0.7583661 0.3629911 0.7935053 0.3899714 0.7935054 0.3629911 0.8286446 0.3899714 0.8286446 0.3899714 0.7935054 0.3629911 0.8637839 0.3899714 0.8637839 0.3899714 0.8286446 0.3629911 0.8989232 0.3899714 0.8989232 0.3899714 0.8637839 0.3629911 0.8989232 0.3629911 0.9340626 0.3899714 0.9340626 0.3899714 0.9692018 0.3899714 0.9340626 0.3629911 0.9471353 0.3899714 0.9340626 0.3629911 0.9340626 0.3629911 0.9471353 0.3904153 0.7583659 0.3904153 0.7935053 0.4173957 0.7935054 0.3904153 0.8286446 0.4173957 0.8286446 0.4173957 0.7935054 0.3904153 0.8637839 0.4173957 0.8637839 0.4173957 0.8286446 0.3904153 0.8989232 0.4173957 0.8989232 0.4173957 0.8637839 0.3904153 0.8989232 0.3904153 0.9340626 0.4173957 0.9340626 0.3904153 0.9340626 0.3904153 0.9692018 0.4173957 0.9692018 0.4178395 0.7583659 0.4178395 0.7935053 0.4448199 0.7935054 0.4178395 0.8286446 0.4448199 0.8286446 0.4448199 0.7935054 0.4178395 0.8637839 0.4448199 0.8637839 0.4448199 0.8286446 0.4178395 0.8989232 0.4448199 0.8989232 0.4448199 0.8637839 0.4178395 0.8989232 0.4178395 0.9340626 0.4448199 0.9340626 0.4178395 0.9340626 0.4178395 0.9692018 0.4448199 0.9692018 0.4452638 0.7583659 0.4452638 0.7935053 0.4722442 0.7935054 0.4452638 0.8286446 0.4722442 0.8286446 0.4722442 0.7935054 0.4452638 0.8637839 0.4722442 0.8637839 0.4722442 0.8286446 0.4452638 0.8989232 0.4722442 0.8989232 0.4722442 0.8637839 0.4452638 0.8989232 0.4452638 0.9340626 0.4722442 0.9340626 0.4452638 0.9340626 0.4452638 0.9692018 0.4722442 0.9692018 0.472688 0.7583659 0.472688 0.7935053 0.4996684 0.7935054 0.472688 0.8286446 0.4996684 0.8286446 0.4996684 0.7935054 0.4996684 0.8286446 0.472688 0.8286446 0.472688 0.8491244 0.472688 0.8491244 0.472688 0.8637839 0.4996684 0.8637839 0.472688 0.8989232 0.4996684 0.8989232 0.4996684 0.8637839 0.472688 0.8989232 0.472688 0.9340626 0.4996684 0.9340626 0.4996684 0.9692018 0.4996684 0.9340626 0.472688 0.9340676 0.4996684 0.9340626 0.472688 0.9340626 0.472688 0.9340676 0.5001122 0.7583659 0.5001122 0.7935053 0.5270928 0.7935054 0.5001122 0.8286446 0.5270928 0.8286446 0.5270928 0.7935054 0.5001122 0.8637839 0.5270928 0.8637839 0.5270928 0.8286446 0.5001122 0.8989232 0.5270928 0.8989232 0.5270928 0.8637839 0.5001122 0.8989232 0.5001122 0.9340626 0.5270928 0.9340626 0.5001122 0.9340626 0.5001122 0.9692018 0.5270928 0.9692018 0.5275364 0.7583659 0.5275364 0.7935053 0.554517 0.7935054 0.5275364 0.8286446 0.554517 0.8286446 0.554517 0.7935054 0.5275364 0.8637839 0.554517 0.8637839 0.554517 0.8286446 0.5275364 0.8989232 0.554517 0.8989232 0.554517 0.8637839 0.5275364 0.8989232 0.5275364 0.9340626 0.554517 0.9340626 0.5275364 0.9340626 0.5275367 0.9692018 0.554517 0.9692018 0.5549607 0.7583659 0.5549607 0.7935053 0.5819413 0.7935053 0.5549607 0.8286446 0.5819413 0.8286446 0.5819413 0.7935053 0.5549607 0.8637839 0.5819413 0.8637839 0.5819413 0.8286446 0.5549607 0.8989232 0.5819413 0.8989232 0.5819413 0.8637839 0.5549607 0.8989232 0.5549607 0.9340626 0.5819413 0.9340626 0.5549607 0.9340626 0.5549607 0.9692018 0.5819413 0.9692018 0.5823852 0.5470865 0.5823852 0.5822256 0.6093655 0.5822256 0.5823852 0.6173651 0.6093655 0.6173651 0.6093655 0.5822256 0.5823852 0.6525043 0.6093655 0.6525043 0.6093655 0.6173651 0.5823852 0.6876436 0.6093655 0.6876436 0.6093655 0.6525043 0.5823852 0.6876436 0.5823852 0.7227829 0.6093655 0.7227829 0.5823852 0.7227829 0.5823852 0.7579222 0.6093655 0.7579222 0.5823849 0.7583659 0.5823849 0.7935053 0.6093655 0.7935053 0.5823849 0.8286446 0.6093655 0.8286446 0.6093655 0.7935053 0.5823849 0.8637839 0.6093655 0.8637839 0.6093655 0.8286446 0.5823849 0.8989232 0.6093655 0.8989232 0.6093655 0.8637839 0.5823849 0.8989232 0.5823849 0.9340626 0.6093655 0.9340626 0.5823849 0.9340626 0.5823849 0.9692018 0.6093655 0.9692018 0.6098094 0.5470865 0.6098094 0.5822256 0.6367898 0.5822257 0.6098094 0.6173651 0.6367898 0.6173651 0.6367898 0.5822257 0.6098094 0.6525043 0.6367898 0.6525043 0.6367898 0.6173651 0.6098094 0.6876437 0.6367898 0.6876436 0.6367898 0.6525043 0.6098094 0.6876437 0.6098094 0.7227829 0.6367898 0.7227829 0.6098094 0.7227829 0.6098094 0.7579223 0.6367898 0.7579223 0.6098094 0.7583659 0.6098094 0.7935053 0.6367898 0.7935053 0.6098094 0.8286446 0.6367898 0.8286445 0.6367898 0.7935053 0.6098094 0.8637839 0.6367898 0.8637839 0.6367898 0.8286445 0.6098094 0.8989232 0.6367898 0.8989232 0.6367898 0.8637839 0.6098094 0.8989232 0.6098094 0.9340626 0.6367898 0.9340626 0.6098094 0.9340626 0.6098094 0.9692018 0.6367898 0.9692018 0.4965105 0.1496902 0.4965105 0.06654256 0.3630295 0.06654256 0.4965105 0.1496902 0.3630295 0.1496902 0.3630295 0.2901237 0.4965105 0.2901237 0.579658 0.2901237 0.5796583 0.1496902 0.4965105 0.5137047 0.4965105 0.3732712 0.3630295 0.3732712 0.3630295 0.1496902 0.2798818 0.1496902 0.2798816 0.2901237 0.3630295 0.2901237 0.3630295 0.3732712 0.4965105 0.3732712 0.06854629 0.2737155 0.06854629 0.276169 0.02928906 0.276169 0.06854629 0.276169 0.06854629 0.2786228 0.02928906 0.2786228 0.06854629 0.2786228 0.06854629 0.281076 0.02928906 0.281076 0.06854629 0.281076 0.06854629 0.2835297 0.02928906 0.2835297 0.06854629 0.2835297 0.06854629 0.2859833 0.02928906 0.2859833 0.06854629 0.2859833 0.06854629 0.288437 0.02928906 0.288437 0.06854629 0.288437 0.06854629 0.2908906 0.02928906 0.2908906 0.06854629 0.2908906 0.06854629 0.2933443 0.02928906 0.2933443 0.06854629 0.2933443 0.06854629 0.295798 0.02928906 0.295798 0.06854629 0.295798 0.06854629 0.2982512 0.02928906 0.2982512 0.06854629 0.2982512 0.06854629 0.3007048 0.02928906 0.3007048 0.06854629 0.3007048 0.06854629 0.3031585 0.02928906 0.3031585 0.06854629 0.3031585 0.06854629 0.3056122 0.02928906 0.3056122 0.06854629 0.3056122 0.06854629 0.3080657 0.02928906 0.3080657 0.06854629 0.3080657 0.06854629 0.3105193 0.02928906 0.3105193 0.06854629 0.3105193 0.06854629 0.3129729 0.02928906 0.3129729 0.06854629 0.3129729 0.06854629 0.3154264 0.02928906 0.3154264 0.06854629 0.3154264 0.06854629 0.31788 0.02928906 0.31788 0.06854629 0.31788 0.06854629 0.3203335 0.02928906 0.3203335 0.06854629 0.3203335 0.06854629 0.3227872 0.02928906 0.3227872 0.06854629 0.3227872 0.06854629 0.3252408 0.02928906 0.3252408 0.06854629 0.3252408 0.06854629 0.3276945 0.02928906 0.3276945 0.06854629 0.3276945 0.06854629 0.3301477 0.02928906 0.3301477 0.06854629 0.3301477 0.06854629 0.3326014 0.02928906 0.3326014 0.06854629 0.3326014 0.06854629 0.335055 0.02928906 0.335055 0.06854629 0.335055 0.06854629 0.3375087 0.02928906 0.3375087 0.06854629 0.3375087 0.06854629 0.3399623 0.02928906 0.3399623 0.06854629 0.3399623 0.06854629 0.3424161 0.02928906 0.3424161 0.06854629 0.3424161 0.06854629 0.3448697 0.02928906 0.3448697 0.06854629 0.3448697 0.06854629 0.347323 0.02928906 0.347323 0.06607395 0.4553855 0.06466025 0.4587983 0.03608745 0.4353492 0.06466025 0.4587983 0.06260806 0.4618698 0.03347551 0.4379612 0.06260806 0.4618698 0.059996 0.4644818 0.03142315 0.4410328 0.059996 0.4644818 0.05692446 0.466534 0.03000956 0.4444454 0.05692446 0.466534 0.05351173 0.4679476 0.03000956 0.4444454 0.05351173 0.4679476 0.04988878 0.468668 0.02928906 0.4480686 0.03000956 0.4444454 0.05351173 0.4679476 0.02928906 0.4480686 0.04988878 0.468668 0.04619479 0.468668 0.02928906 0.4517623 0.04619479 0.468668 0.04257166 0.4679476 0.03000956 0.4553855 0.02928906 0.4517623 0.04619479 0.468668 0.03000956 0.4553855 0.04257166 0.4679476 0.03915894 0.466534 0.03142315 0.4587983 0.03915894 0.466534 0.03608745 0.4644818 0.03347551 0.4618698 0.03142315 0.4587983 0.03915894 0.466534 0.03347551 0.4618698 0.03142315 0.4587983 0.03000956 0.4553855 0.04257166 0.4679476 0.02928906 0.4517623 0.02928906 0.4480686 0.04988878 0.468668 0.03000956 0.4444454 0.03142315 0.4410328 0.059996 0.4644818 0.03142315 0.4410328 0.03347551 0.4379612 0.06260806 0.4618698 0.03347551 0.4379612 0.03608745 0.4353492 0.06466025 0.4587983 0.03608745 0.4353492 0.03915894 0.433297 0.06607395 0.4553855 0.03915894 0.433297 0.04257166 0.4318833 0.06607395 0.4553855 0.04257166 0.4318833 0.04619479 0.4311625 0.06679451 0.4517623 0.06607395 0.4553855 0.04257166 0.4318833 0.06679451 0.4517623 0.04619479 0.4311625 0.04988878 0.4311625 0.06679451 0.4480686 0.04988878 0.4311625 0.05351173 0.4318833 0.06607395 0.4444454 0.06679451 0.4480686 0.04988878 0.4311625 0.06607395 0.4444454 0.05351173 0.4318833 0.05692464 0.433297 0.06466025 0.4410328 0.05692464 0.433297 0.059996 0.4353492 0.06260806 0.4379612 0.06466025 0.4410328 0.05692464 0.433297 0.06260806 0.4379612 0.06466025 0.4410328 0.06607395 0.4444454 0.05351173 0.4318833 0.06854629 0.347323 0.06854629 0.3497766 0.02928906 0.3497766 0.06854629 0.3497766 0.06854629 0.3522303 0.02928906 0.3522303 0.1871539 0.4107533 0.1878745 0.4143761 0.2239388 0.4034364 0.1878745 0.4143761 0.189288 0.4177891 0.2246595 0.4070596 0.189288 0.4177891 0.1913404 0.4208604 0.2246595 0.4070596 0.1913404 0.4208604 0.1939523 0.4234727 0.2246595 0.4107533 0.2246595 0.4070596 0.1913404 0.4208604 0.2246595 0.4107533 0.1939523 0.4234727 0.1970237 0.4255247 0.222525 0.4177891 0.1970237 0.4255247 0.2004365 0.4269385 0.2204728 0.4208604 0.2004365 0.4269385 0.2040597 0.427659 0.2204728 0.4208604 0.2040597 0.427659 0.2077536 0.427659 0.2178607 0.4234727 0.2204728 0.4208604 0.2040597 0.427659 0.2178607 0.4234727 0.2077536 0.427659 0.2113766 0.4269385 0.2147894 0.4255247 0.2147894 0.4255247 0.2178607 0.4234727 0.2077536 0.427659 0.2204728 0.4208604 0.222525 0.4177891 0.1970237 0.4255247 0.222525 0.4177891 0.2239388 0.4143761 0.1939523 0.4234727 0.2239388 0.4143761 0.2246595 0.4107533 0.1939523 0.4234727 0.2246595 0.4070596 0.2239388 0.4034364 0.1878745 0.4143761 0.2239388 0.4034364 0.222525 0.4000236 0.1871539 0.4107533 0.222525 0.4000236 0.2204728 0.3969521 0.1871539 0.4107533 0.2204728 0.3969521 0.2178607 0.3943402 0.1871539 0.4070596 0.1871539 0.4107533 0.2204728 0.3969521 0.1871539 0.4070596 0.2178607 0.3943402 0.2147894 0.3922878 0.189288 0.4000236 0.2147894 0.3922878 0.2113766 0.3908741 0.1913404 0.3969521 0.2113766 0.3908741 0.2077536 0.3901535 0.1913404 0.3969521 0.2077536 0.3901535 0.2040597 0.3901535 0.1939523 0.3943402 0.1913404 0.3969521 0.2077536 0.3901535 0.1939523 0.3943402 0.2040597 0.3901535 0.2004365 0.3908741 0.1970237 0.3922878 0.1970237 0.3922878 0.1939523 0.3943402 0.2040597 0.3901535 0.1913404 0.3969521 0.189288 0.4000236 0.2147894 0.3922878 0.189288 0.4000236 0.1878745 0.4034364 0.2178607 0.3943402 0.1080124 0.2737155 0.1080124 0.276169 0.0687552 0.276169 0.1080124 0.276169 0.1080124 0.2786228 0.0687552 0.2786228 0.1080124 0.2786228 0.1080124 0.281076 0.0687552 0.281076 0.1080124 0.281076 0.1080124 0.2835297 0.0687552 0.2835297 0.1080124 0.2835297 0.1080124 0.2859833 0.0687552 0.2859833 0.1080124 0.2859833 0.1080124 0.288437 0.0687552 0.288437 0.1080124 0.288437 0.1080124 0.2908906 0.0687552 0.2908906 0.1080124 0.2908906 0.1080124 0.2933443 0.0687552 0.2933443 0.1080124 0.2933443 0.1080124 0.295798 0.0687552 0.295798 0.1080124 0.295798 0.1080124 0.2982512 0.0687552 0.2982512 0.1080124 0.2982512 0.1080124 0.3007048 0.0687552 0.3007048 0.1080124 0.3007048 0.1080124 0.3031585 0.0687552 0.3031585 0.1080124 0.3031585 0.1080124 0.3056122 0.0687552 0.3056122 0.1080124 0.3056122 0.1080124 0.3080657 0.0687552 0.3080657 0.1080124 0.3080657 0.1080124 0.3105193 0.0687552 0.3105193 0.1080124 0.3105193 0.1080124 0.3129729 0.0687552 0.3129729 0.1080124 0.3129729 0.1080124 0.3154264 0.0687552 0.3154264 0.1080124 0.3154264 0.1080124 0.31788 0.0687552 0.31788 0.1080124 0.31788 0.1080124 0.3203335 0.0687552 0.3203335 0.1080124 0.3203335 0.1080124 0.3227872 0.0687552 0.3227872 0.1080124 0.3227872 0.1080124 0.3252408 0.0687552 0.3252408 0.1080124 0.3252408 0.1080124 0.3276945 0.0687552 0.3276945 0.1080124 0.3276945 0.1080124 0.3301477 0.0687552 0.3301477 0.1080124 0.3301477 0.1080124 0.3326014 0.0687552 0.3326014 0.1080124 0.3326014 0.1080124 0.335055 0.0687552 0.335055 0.1080124 0.335055 0.1080124 0.3375087 0.0687552 0.3375087 0.1080124 0.3375087 0.1080124 0.3399623 0.0687552 0.3399623 0.1080124 0.3399623 0.1080124 0.3424161 0.0687552 0.3424161 0.1080124 0.3424161 0.1080124 0.3448697 0.0687552 0.3448697 0.1080124 0.3448697 0.1080124 0.347323 0.0687552 0.347323 0.1055402 0.4553855 0.1041264 0.4587983 0.07555377 0.4353492 0.1041264 0.4587983 0.1020742 0.4618698 0.07294178 0.4379612 0.1020742 0.4618698 0.09946221 0.4644818 0.07088947 0.4410328 0.09946221 0.4644818 0.09639084 0.4665341 0.06947576 0.4444454 0.09639084 0.4665341 0.09297794 0.4679476 0.06947576 0.4444454 0.09297794 0.4679476 0.08935487 0.468668 0.0687552 0.4480686 0.06947576 0.4444454 0.09297794 0.4679476 0.0687552 0.4480686 0.08935487 0.468668 0.08566087 0.468668 0.0687552 0.4517623 0.08566087 0.468668 0.08203786 0.4679476 0.06947576 0.4553855 0.0687552 0.4517623 0.08566087 0.468668 0.06947576 0.4553855 0.08203786 0.4679476 0.07862514 0.4665341 0.07088947 0.4587983 0.07862514 0.4665341 0.07555377 0.4644818 0.07294178 0.4618698 0.07088947 0.4587983 0.07862514 0.4665341 0.07294178 0.4618698 0.07088947 0.4587983 0.06947576 0.4553855 0.08203786 0.4679476 0.0687552 0.4517623 0.0687552 0.4480686 0.08935487 0.468668 0.06947576 0.4444454 0.07088947 0.4410328 0.09946221 0.4644818 0.07088947 0.4410328 0.07294178 0.4379612 0.1020742 0.4618698 0.07294178 0.4379612 0.07555377 0.4353492 0.1041264 0.4587983 0.07555377 0.4353492 0.07862526 0.433297 0.1055402 0.4553855 0.07862526 0.433297 0.08203798 0.4318833 0.1055402 0.4553855 0.08203798 0.4318833 0.08566087 0.4311625 0.1062608 0.4517623 0.1055402 0.4553855 0.08203798 0.4318833 0.1062608 0.4517623 0.08566087 0.4311625 0.08935487 0.4311625 0.1062608 0.4480686 0.08935487 0.4311625 0.09297794 0.4318833 0.1055402 0.4444454 0.1062608 0.4480686 0.08935487 0.4311625 0.1055402 0.4444454 0.09297794 0.4318833 0.09639084 0.433297 0.1020742 0.4379612 0.09639084 0.433297 0.09946221 0.4353492 0.1020742 0.4379612 0.1020742 0.4379612 0.1041264 0.4410328 0.09297794 0.4318833 0.1041264 0.4410328 0.1055402 0.4444454 0.09297794 0.4318833 0.1080124 0.347323 0.1080124 0.3497766 0.0687552 0.3497766 0.1080124 0.3497766 0.1080124 0.3522303 0.0687552 0.3522303 0.2213647 0.4517623 0.2220854 0.4553855 0.2581497 0.4444454 0.2220854 0.4553855 0.2234989 0.4587983 0.2588704 0.4480682 0.2234989 0.4587983 0.2255512 0.4618698 0.2588704 0.4480682 0.2255512 0.4618698 0.2281633 0.4644818 0.2588704 0.4517623 0.2588704 0.4480682 0.2255512 0.4618698 0.2588704 0.4517623 0.2281633 0.4644818 0.2312347 0.466534 0.256736 0.4587983 0.2312347 0.466534 0.2346475 0.4679476 0.2546838 0.4618698 0.2346475 0.4679476 0.2382706 0.468668 0.2546838 0.4618698 0.2382706 0.468668 0.2419646 0.468668 0.2520717 0.4644818 0.2546838 0.4618698 0.2382706 0.468668 0.2520717 0.4644818 0.2419646 0.468668 0.2455876 0.4679476 0.2490001 0.466534 0.2490001 0.466534 0.2520717 0.4644818 0.2419646 0.468668 0.2546838 0.4618698 0.256736 0.4587983 0.2312347 0.466534 0.256736 0.4587983 0.2581497 0.4553855 0.2281633 0.4644818 0.2581497 0.4553855 0.2588704 0.4517623 0.2281633 0.4644818 0.2588704 0.4480682 0.2581497 0.4444454 0.2220854 0.4553855 0.2581497 0.4444454 0.256736 0.4410328 0.2213647 0.4517623 0.256736 0.4410328 0.2546838 0.4379612 0.2213647 0.4517623 0.2546838 0.4379612 0.2520717 0.4353492 0.2213647 0.4480686 0.2213647 0.4517623 0.2546838 0.4379612 0.2213647 0.4480686 0.2520717 0.4353492 0.2490001 0.433297 0.2234989 0.4410328 0.2490001 0.433297 0.2455874 0.4318833 0.2255512 0.4379612 0.2455874 0.4318833 0.2419646 0.4311625 0.2255512 0.4379612 0.2419646 0.4311625 0.2382706 0.4311625 0.2281633 0.4353492 0.2255512 0.4379612 0.2419646 0.4311625 0.2281633 0.4353492 0.2382706 0.4311625 0.2346475 0.4318833 0.2312347 0.433297 0.2312347 0.433297 0.2281633 0.4353492 0.2382706 0.4311625 0.2255512 0.4379612 0.2234989 0.4410328 0.2490001 0.433297 0.2234989 0.4410328 0.2220854 0.4444454 0.2520717 0.4353492 0.1474788 0.2737155 0.1474788 0.276169 0.1082213 0.276169 0.1474788 0.276169 0.1474788 0.2786228 0.1082213 0.2786228 0.1474788 0.2786228 0.1474788 0.281076 0.1082213 0.281076 0.1474788 0.281076 0.1474788 0.2835297 0.1082213 0.2835297 0.1474788 0.2835297 0.1474788 0.2859833 0.1082213 0.2859833 0.1474788 0.2859833 0.1474788 0.288437 0.1082213 0.288437 0.1474788 0.288437 0.1474788 0.2908906 0.1082213 0.2908906 0.1474788 0.2908906 0.1474788 0.2933443 0.1082213 0.2933443 0.1474788 0.2933443 0.1474788 0.295798 0.1082213 0.295798 0.1474788 0.295798 0.1474788 0.2982512 0.1082213 0.2982512 0.1474788 0.2982512 0.1474788 0.3007048 0.1082213 0.3007048 0.1474788 0.3007048 0.1474788 0.3031585 0.1082213 0.3031585 0.1474788 0.3031585 0.1474788 0.3056122 0.1082213 0.3056122 0.1474788 0.3056122 0.1474788 0.3080657 0.1082213 0.3080657 0.1474788 0.3080657 0.1474788 0.3105193 0.1082213 0.3105193 0.1474788 0.3105193 0.1474788 0.3129729 0.1082213 0.3129729 0.1474788 0.3129729 0.1474788 0.3154264 0.1082213 0.3154264 0.1474788 0.3154264 0.1474788 0.31788 0.1082213 0.31788 0.1474788 0.31788 0.1474788 0.3203335 0.1082213 0.3203335 0.1474788 0.3203335 0.1474788 0.3227872 0.1082213 0.3227872 0.1474788 0.3227872 0.1474788 0.3252408 0.1082213 0.3252408 0.1474788 0.3252408 0.1474788 0.3276945 0.1082213 0.3276945 0.1474788 0.3276945 0.1474788 0.3301477 0.1082213 0.3301477 0.1474788 0.3301477 0.1474788 0.3326014 0.1082213 0.3326014 0.1474788 0.3326014 0.1474788 0.335055 0.1082213 0.335055 0.1474788 0.335055 0.1474788 0.3375087 0.1082213 0.3375087 0.1474788 0.3375087 0.1474788 0.3399623 0.1082213 0.3399623 0.1474788 0.3399623 0.1474788 0.3424161 0.1082213 0.3424161 0.1474788 0.3424161 0.1474788 0.3448697 0.1082213 0.3448697 0.1474788 0.3448697 0.1474788 0.347323 0.1082213 0.347323 0.1450062 0.4553855 0.1435928 0.4587983 0.11502 0.4353492 0.1435928 0.4587983 0.1415404 0.4618698 0.1124079 0.4379612 0.1415404 0.4618698 0.1389284 0.4644818 0.1103556 0.4410328 0.1389284 0.4644818 0.135857 0.4665341 0.1089421 0.4444454 0.135857 0.4665341 0.1324442 0.4679476 0.1089421 0.4444454 0.1324442 0.4679476 0.1288211 0.468668 0.1082213 0.4480686 0.1089421 0.4444454 0.1324442 0.4679476 0.1082213 0.4480686 0.1288211 0.468668 0.1251272 0.468668 0.1082213 0.4517623 0.1251272 0.468668 0.1215042 0.4679476 0.1089421 0.4553855 0.1082213 0.4517623 0.1251272 0.468668 0.1089421 0.4553855 0.1215042 0.4679476 0.1180915 0.466534 0.1124079 0.4618698 0.1180915 0.466534 0.11502 0.4644818 0.1124079 0.4618698 0.1124079 0.4618698 0.1103556 0.4587983 0.1215042 0.4679476 0.1103556 0.4587983 0.1089421 0.4553855 0.1215042 0.4679476 0.1082213 0.4517623 0.1082213 0.4480686 0.1288211 0.468668 0.1089421 0.4444454 0.1103556 0.4410328 0.1389284 0.4644818 0.1103556 0.4410328 0.1124079 0.4379612 0.1415404 0.4618698 0.1124079 0.4379612 0.11502 0.4353492 0.1435928 0.4587983 0.11502 0.4353492 0.1180915 0.433297 0.1450062 0.4553855 0.1180915 0.433297 0.1215042 0.4318833 0.1450062 0.4553855 0.1215042 0.4318833 0.1251272 0.4311625 0.1457269 0.4517623 0.1450062 0.4553855 0.1215042 0.4318833 0.1457269 0.4517623 0.1251272 0.4311625 0.1288211 0.4311625 0.1457269 0.4480686 0.1288211 0.4311625 0.1324442 0.4318833 0.1450062 0.4444454 0.1457269 0.4480686 0.1288211 0.4311625 0.1450062 0.4444454 0.1324442 0.4318833 0.135857 0.433297 0.1415404 0.4379612 0.135857 0.433297 0.1389284 0.4353492 0.1415404 0.4379612 0.1415404 0.4379612 0.1435928 0.4410328 0.1324442 0.4318833 0.1435928 0.4410328 0.1450062 0.4444454 0.1324442 0.4318833 0.1474788 0.347323 0.1474788 0.3497766 0.1082213 0.3497766 0.1474788 0.3497766 0.1474788 0.3522303 0.1082213 0.3522303 0.02928906 0.4894769 0.03000956 0.4931001 0.06607395 0.4821599 0.03000956 0.4931001 0.03142315 0.4965128 0.06679451 0.4857831 0.03142315 0.4965128 0.03347551 0.4995843 0.06679451 0.4857831 0.03347551 0.4995843 0.03608745 0.5021961 0.06679451 0.4894769 0.06679451 0.4857831 0.03347551 0.4995843 0.06679451 0.4894769 0.03608745 0.5021961 0.03915894 0.5042482 0.06466025 0.4965128 0.03915894 0.5042482 0.04257166 0.5056621 0.06260806 0.4995843 0.04257166 0.5056621 0.04619479 0.5063825 0.06260806 0.4995843 0.04619479 0.5063825 0.04988878 0.5063825 0.059996 0.5021961 0.06260806 0.4995843 0.04619479 0.5063825 0.059996 0.5021961 0.04988878 0.5063825 0.05351173 0.5056621 0.05692446 0.5042482 0.05692446 0.5042482 0.059996 0.5021961 0.04988878 0.5063825 0.06260806 0.4995843 0.06466025 0.4965128 0.03915894 0.5042482 0.06466025 0.4965128 0.06607395 0.4931001 0.03608745 0.5021961 0.06607395 0.4931001 0.06679451 0.4894769 0.03608745 0.5021961 0.06679451 0.4857831 0.06607395 0.4821599 0.03000956 0.4931001 0.06607395 0.4821599 0.06466025 0.4787471 0.02928906 0.4894769 0.06466025 0.4787471 0.06260806 0.4756757 0.02928906 0.4894769 0.06260806 0.4756757 0.059996 0.4730637 0.02928906 0.4857831 0.02928906 0.4894769 0.06260806 0.4756757 0.02928906 0.4857831 0.059996 0.4730637 0.05692464 0.4710115 0.03142315 0.4787471 0.05692464 0.4710115 0.05351173 0.4695978 0.03347551 0.4756757 0.05351173 0.4695978 0.04988878 0.468877 0.03347551 0.4756757 0.04988878 0.468877 0.04619479 0.468877 0.03608745 0.4730637 0.03347551 0.4756757 0.04988878 0.468877 0.03608745 0.4730637 0.04619479 0.468877 0.04257166 0.4695978 0.03915894 0.4710115 0.03915894 0.4710115 0.03608745 0.4730637 0.04619479 0.468877 0.03347551 0.4756757 0.03142315 0.4787471 0.05692464 0.4710115 0.03142315 0.4787471 0.03000956 0.4821599 0.059996 0.4730637 0.06854629 0.352439 0.06854629 0.3548926 0.02928906 0.3548926 0.06854629 0.3548926 0.06854629 0.3573463 0.02928906 0.3573463 0.06854629 0.3573463 0.06854629 0.3597999 0.02928906 0.3597999 0.06854629 0.3597999 0.06854629 0.3622536 0.02928906 0.3622536 0.06854629 0.3622536 0.06854629 0.3647069 0.02928906 0.3647069 0.06854629 0.3647069 0.06854629 0.3671605 0.02928906 0.3671605 0.06854629 0.3671605 0.06854629 0.3696142 0.02928906 0.3696142 0.06854629 0.3696142 0.06854629 0.3720678 0.02928906 0.3720678 0.06854629 0.3720678 0.06854629 0.3745215 0.02928906 0.3745215 0.06854629 0.3745215 0.06854629 0.3769749 0.02928906 0.3769749 0.06854629 0.3769749 0.06854629 0.3794284 0.02928906 0.3794284 0.06854629 0.3794284 0.06854629 0.3818821 0.02928906 0.3818821 0.06854629 0.3818821 0.06854629 0.3843358 0.02928906 0.3843358 0.06854629 0.3843358 0.06854629 0.3867892 0.02928906 0.3867892 0.06854629 0.3867892 0.06854629 0.3892428 0.02928906 0.3892428 0.06854629 0.3892428 0.06854629 0.3916965 0.02928906 0.3916965 0.06854629 0.3916965 0.06854629 0.3941501 0.02928906 0.3941501 0.06854629 0.3941501 0.06854629 0.3966034 0.02928906 0.3966034 0.06854629 0.3966034 0.06854629 0.399057 0.02928906 0.399057 0.06854629 0.399057 0.06854629 0.4015107 0.02928906 0.4015107 0.06854629 0.4015107 0.06854629 0.4039644 0.02928906 0.4039644 0.06854629 0.4039644 0.06854629 0.406418 0.02928906 0.406418 0.06854629 0.406418 0.06854629 0.4088717 0.02928906 0.4088717 0.06854629 0.4088717 0.06854629 0.4113253 0.02928906 0.4113253 0.06854629 0.4113253 0.06854629 0.4137786 0.02928906 0.4137786 0.06854629 0.4137786 0.06854629 0.4162324 0.02928906 0.4162324 0.06854629 0.4162324 0.06854629 0.4186859 0.02928906 0.4186859 0.06854629 0.4186859 0.06854629 0.4211395 0.02928906 0.4211395 0.06854629 0.4211395 0.06854629 0.423593 0.02928906 0.423593 0.06854629 0.423593 0.06854629 0.4260466 0.02928906 0.4260466 0.1827209 0.4553855 0.1813071 0.4587983 0.1527343 0.4353492 0.1813071 0.4587983 0.1792548 0.4618698 0.1501224 0.4379612 0.1792548 0.4618698 0.1766429 0.4644818 0.1480701 0.4410328 0.1766429 0.4644818 0.1735715 0.4665341 0.1466564 0.4444454 0.1735715 0.4665341 0.1701586 0.4679476 0.1466564 0.4444454 0.1701586 0.4679476 0.1665356 0.468668 0.1459358 0.4480686 0.1466564 0.4444454 0.1701586 0.4679476 0.1459358 0.4480686 0.1665356 0.468668 0.1628416 0.468668 0.1459358 0.4517623 0.1628416 0.468668 0.1592187 0.4679476 0.1466564 0.4553855 0.1459358 0.4517623 0.1628416 0.468668 0.1466564 0.4553855 0.1592187 0.4679476 0.1558058 0.4665341 0.1480701 0.4587983 0.1558058 0.4665341 0.1527343 0.4644818 0.1501224 0.4618698 0.1480701 0.4587983 0.1558058 0.4665341 0.1501224 0.4618698 0.1480701 0.4587983 0.1466564 0.4553855 0.1592187 0.4679476 0.1459358 0.4517623 0.1459358 0.4480686 0.1665356 0.468668 0.1466564 0.4444454 0.1480701 0.4410328 0.1766429 0.4644818 0.1480701 0.4410328 0.1501224 0.4379612 0.1792548 0.4618698 0.1501224 0.4379612 0.1527343 0.4353492 0.1813071 0.4587983 0.1527343 0.4353492 0.1558058 0.433297 0.1827209 0.4553855 0.1558058 0.433297 0.1592187 0.4318833 0.1827209 0.4553855 0.1592187 0.4318833 0.1628416 0.4311625 0.1834415 0.4517623 0.1827209 0.4553855 0.1592187 0.4318833 0.1834415 0.4517623 0.1628416 0.4311625 0.1665356 0.4311625 0.1834415 0.4480686 0.1665356 0.4311625 0.1701586 0.4318833 0.1827209 0.4444454 0.1834415 0.4480686 0.1665356 0.4311625 0.1827209 0.4444454 0.1701586 0.4318833 0.1735715 0.433297 0.1792548 0.4379612 0.1735715 0.433297 0.1766429 0.4353492 0.1792548 0.4379612 0.1792548 0.4379612 0.1813071 0.4410328 0.1701586 0.4318833 0.1813071 0.4410328 0.1827209 0.4444454 0.1701586 0.4318833 0.06854629 0.4260466 0.06854629 0.4285003 0.02928906 0.4285003 0.06854629 0.4285003 0.06854629 0.4309538 0.02928906 0.4309538 0.06700336 0.4894769 0.06772416 0.4931001 0.1037883 0.4821599 0.06772416 0.4931001 0.06913763 0.4965128 0.1045089 0.4857831 0.06913763 0.4965128 0.07118993 0.4995843 0.1045089 0.4857831 0.07118993 0.4995843 0.07380199 0.5021961 0.1045089 0.4894769 0.1045089 0.4857831 0.07118993 0.4995843 0.1045089 0.4894769 0.07380199 0.5021961 0.07687336 0.5042486 0.1023747 0.4965128 0.07687336 0.5042486 0.0802862 0.5056621 0.1003225 0.4995843 0.0802862 0.5056621 0.08390921 0.5063825 0.1003225 0.4995843 0.08390921 0.5063825 0.08760321 0.5063825 0.09771031 0.5021961 0.1003225 0.4995843 0.08390921 0.5063825 0.09771031 0.5021961 0.08760321 0.5063825 0.0912261 0.5056621 0.094639 0.5042482 0.094639 0.5042482 0.09771031 0.5021961 0.08760321 0.5063825 0.1003225 0.4995843 0.1023747 0.4965128 0.07687336 0.5042486 0.1023747 0.4965128 0.1037883 0.4931001 0.07380199 0.5021961 0.1037883 0.4931001 0.1045089 0.4894769 0.07380199 0.5021961 0.1045089 0.4857831 0.1037883 0.4821599 0.06772416 0.4931001 0.1037883 0.4821599 0.1023747 0.4787471 0.06700336 0.4894769 0.1023747 0.4787471 0.1003225 0.4756757 0.06700336 0.4894769 0.1003225 0.4756757 0.09771031 0.4730637 0.06700336 0.4857831 0.06700336 0.4894769 0.1003225 0.4756757 0.06700336 0.4857831 0.09771031 0.4730637 0.094639 0.4710115 0.06913763 0.4787471 0.094639 0.4710115 0.0912261 0.4695978 0.07118993 0.4756757 0.0912261 0.4695978 0.08760321 0.468877 0.07118993 0.4756757 0.08760321 0.468877 0.08390921 0.468877 0.07380187 0.4730637 0.07118993 0.4756757 0.08760321 0.468877 0.07380187 0.4730637 0.08390921 0.468877 0.0802862 0.4695978 0.07687336 0.4710115 0.07687336 0.4710115 0.07380187 0.4730637 0.08390921 0.468877 0.07118993 0.4756757 0.06913763 0.4787471 0.094639 0.4710115 0.06913763 0.4787471 0.06772416 0.4821599 0.09771031 0.4730637 0.1080124 0.352439 0.1080124 0.3548926 0.0687552 0.3548926 0.1080124 0.3548926 0.1080124 0.3573463 0.0687552 0.3573463 0.1080124 0.3573463 0.1080124 0.3597999 0.0687552 0.3597999 0.1080124 0.3597999 0.1080124 0.3622536 0.0687552 0.3622536 0.1080124 0.3622536 0.1080124 0.3647069 0.0687552 0.3647069 0.1080124 0.3647069 0.1080124 0.3671605 0.0687552 0.3671605 0.1080124 0.3671605 0.1080124 0.3696142 0.0687552 0.3696142 0.1080124 0.3696142 0.1080124 0.3720678 0.0687552 0.3720678 0.1080124 0.3720678 0.1080124 0.3745215 0.0687552 0.3745215 0.1080124 0.3745215 0.1080124 0.3769749 0.0687552 0.3769749 0.1080124 0.3769749 0.1080124 0.3794284 0.0687552 0.3794284 0.1080124 0.3794284 0.1080124 0.3818821 0.0687552 0.3818821 0.1080124 0.3818821 0.1080124 0.3843358 0.0687552 0.3843358 0.1080124 0.3843358 0.1080124 0.3867892 0.0687552 0.3867892 0.1080124 0.3867892 0.1080124 0.3892428 0.0687552 0.3892428 0.1080124 0.3892428 0.1080124 0.3916965 0.0687552 0.3916965 0.1080124 0.3916965 0.1080124 0.3941501 0.0687552 0.3941501 0.1080124 0.3941501 0.1080124 0.3966034 0.0687552 0.3966034 0.1080124 0.3966034 0.1080124 0.399057 0.0687552 0.399057 0.1080124 0.399057 0.1080124 0.4015107 0.0687552 0.4015107 0.1080124 0.4015107 0.1080124 0.4039644 0.0687552 0.4039644 0.1080124 0.4039644 0.1080124 0.406418 0.0687552 0.406418 0.1080124 0.406418 0.1080124 0.4088717 0.0687552 0.4088717 0.1080124 0.4088717 0.1080124 0.4113253 0.0687552 0.4113253 0.1080124 0.4113253 0.1080124 0.4137786 0.0687552 0.4137786 0.1080124 0.4137786 0.1080124 0.4162324 0.0687552 0.4162324 0.1080124 0.4162324 0.1080124 0.4186859 0.0687552 0.4186859 0.1080124 0.4186859 0.1080124 0.4211395 0.0687552 0.4211395 0.1080124 0.4211395 0.1080124 0.423593 0.0687552 0.423593 0.1080124 0.423593 0.1080124 0.4260466 0.0687552 0.4260466 0.2204353 0.4553855 0.2190217 0.4587983 0.1904488 0.4353492 0.2190217 0.4587983 0.2169694 0.4618698 0.187837 0.4379612 0.2169694 0.4618698 0.2143573 0.4644818 0.1857845 0.4410328 0.2143573 0.4644818 0.2112859 0.4665341 0.1843709 0.4444454 0.2112859 0.4665341 0.2078731 0.4679476 0.1843709 0.4444454 0.2078731 0.4679476 0.2042502 0.468668 0.1836503 0.4480686 0.1843709 0.4444454 0.2078731 0.4679476 0.1836503 0.4480686 0.2042502 0.468668 0.200556 0.468668 0.1836503 0.4517623 0.200556 0.468668 0.196933 0.4679476 0.1843709 0.4553855 0.1836503 0.4517623 0.200556 0.468668 0.1843709 0.4553855 0.196933 0.4679476 0.1935204 0.466534 0.1857845 0.4587983 0.1935204 0.466534 0.1904488 0.4644818 0.187837 0.4618698 0.1857845 0.4587983 0.1935204 0.466534 0.187837 0.4618698 0.1857845 0.4587983 0.1843709 0.4553855 0.196933 0.4679476 0.1836503 0.4517623 0.1836503 0.4480686 0.2042502 0.468668 0.1843709 0.4444454 0.1857845 0.4410328 0.2143573 0.4644818 0.1857845 0.4410328 0.187837 0.4379612 0.2169694 0.4618698 0.187837 0.4379612 0.1904488 0.4353492 0.2190217 0.4587983 0.1904488 0.4353492 0.1935204 0.433297 0.2204353 0.4553855 0.1935204 0.433297 0.196933 0.4318833 0.2204353 0.4553855 0.196933 0.4318833 0.200556 0.4311625 0.2211559 0.4517623 0.2204353 0.4553855 0.196933 0.4318833 0.2211559 0.4517623 0.200556 0.4311625 0.2042502 0.4311625 0.221156 0.4480686 0.2042502 0.4311625 0.2078731 0.4318833 0.2204353 0.4444454 0.221156 0.4480686 0.2042502 0.4311625 0.2204353 0.4444454 0.2078731 0.4318833 0.2112859 0.433297 0.2169694 0.4379612 0.2112859 0.433297 0.2143573 0.4353492 0.2169694 0.4379612 0.2169694 0.4379612 0.2190217 0.4410328 0.2078731 0.4318833 0.2190217 0.4410328 0.2204353 0.4444454 0.2078731 0.4318833 0.1080124 0.4260466 0.1080124 0.4285003 0.0687552 0.4285003 0.1080124 0.4285003 0.1080124 0.4309538 0.0687552 0.4309538 0.1064696 0.4894769 0.1071903 0.4931001 0.1432546 0.4821599 0.1071903 0.4931001 0.1086038 0.4965128 0.1439753 0.4857831 0.1086038 0.4965128 0.1106561 0.4995843 0.1439753 0.4857831 0.1106561 0.4995843 0.1132682 0.5021961 0.1439753 0.4894769 0.1439753 0.4857831 0.1106561 0.4995843 0.1439753 0.4894769 0.1132682 0.5021961 0.1163396 0.5042486 0.1418409 0.4965128 0.1163396 0.5042486 0.1197525 0.5056621 0.1397887 0.4995843 0.1197525 0.5056621 0.1233754 0.5063825 0.1397887 0.4995843 0.1233754 0.5063825 0.1270694 0.5063825 0.1371766 0.5021961 0.1397887 0.4995843 0.1233754 0.5063825 0.1371766 0.5021961 0.1270694 0.5063825 0.1306924 0.5056621 0.1341051 0.5042486 0.1341051 0.5042486 0.1371766 0.5021961 0.1270694 0.5063825 0.1397887 0.4995843 0.1418409 0.4965128 0.1163396 0.5042486 0.1418409 0.4965128 0.1432546 0.4931001 0.1132682 0.5021961 0.1432546 0.4931001 0.1439753 0.4894769 0.1132682 0.5021961 0.1439753 0.4857831 0.1432546 0.4821599 0.1071903 0.4931001 0.1432546 0.4821599 0.1418409 0.4787471 0.1064696 0.4894769 0.1418409 0.4787471 0.1397887 0.4756757 0.1064696 0.4894769 0.1397887 0.4756757 0.1371766 0.4730637 0.1064696 0.4857831 0.1064696 0.4894769 0.1397887 0.4756757 0.1064696 0.4857831 0.1371766 0.4730637 0.1341051 0.4710115 0.1086038 0.4787471 0.1341051 0.4710115 0.1306924 0.4695978 0.1106561 0.4756757 0.1306924 0.4695978 0.1270694 0.468877 0.1106561 0.4756757 0.1270694 0.468877 0.1233754 0.468877 0.1132682 0.4730637 0.1106561 0.4756757 0.1270694 0.468877 0.1132682 0.4730637 0.1233754 0.468877 0.1197525 0.4695978 0.1163396 0.4710115 0.1163396 0.4710115 0.1132682 0.4730637 0.1233754 0.468877 0.1106561 0.4756757 0.1086038 0.4787471 0.1341051 0.4710115 0.1086038 0.4787471 0.1071903 0.4821599 0.1371766 0.4730637 0.1474788 0.352439 0.1474788 0.3548926 0.1082213 0.3548926 0.1474788 0.3548926 0.1474788 0.3573463 0.1082213 0.3573463 0.1474788 0.3573463 0.1474788 0.3597999 0.1082213 0.3597999 0.1474788 0.3597999 0.1474788 0.3622536 0.1082213 0.3622536 0.1474788 0.3622536 0.1474788 0.3647069 0.1082213 0.3647069 0.1474788 0.3647069 0.1474788 0.3671605 0.1082213 0.3671605 0.1474788 0.3671605 0.1474788 0.3696142 0.1082213 0.3696142 0.1474788 0.3696142 0.1474788 0.3720678 0.1082213 0.3720678 0.1474788 0.3720678 0.1474788 0.3745215 0.1082213 0.3745215 0.1474788 0.3745215 0.1474788 0.3769749 0.1082213 0.3769749 0.1474788 0.3769749 0.1474788 0.3794284 0.1082213 0.3794284 0.1474788 0.3794284 0.1474788 0.3818821 0.1082213 0.3818821 0.1474788 0.3818821 0.1474788 0.3843358 0.1082213 0.3843358 0.1474788 0.3843358 0.1474788 0.3867892 0.1082213 0.3867892 0.1474788 0.3867892 0.1474788 0.3892428 0.1082213 0.3892428 0.1474788 0.3892428 0.1474788 0.3916965 0.1082213 0.3916965 0.1474788 0.3916965 0.1474788 0.3941501 0.1082213 0.3941501 0.1474788 0.3941501 0.1474788 0.3966034 0.1082213 0.3966034 0.1474788 0.3966034 0.1474788 0.399057 0.1082213 0.399057 0.1474788 0.399057 0.1474788 0.4015107 0.1082213 0.4015107 0.1474788 0.4015107 0.1474788 0.4039644 0.1082213 0.4039644 0.1474788 0.4039644 0.1474788 0.406418 0.1082213 0.406418 0.1474788 0.406418 0.1474788 0.4088717 0.1082213 0.4088717 0.1474788 0.4088717 0.1474788 0.4113253 0.1082213 0.4113253 0.1474788 0.4113253 0.1474788 0.4137786 0.1082213 0.4137786 0.1474788 0.4137786 0.1474788 0.4162324 0.1082213 0.4162324 0.1474788 0.4162324 0.1474788 0.4186859 0.1082213 0.4186859 0.1474788 0.4186859 0.1474788 0.4211395 0.1082213 0.4211395 0.1474788 0.4211395 0.1474788 0.423593 0.1082213 0.423593 0.1474788 0.423593 0.1474788 0.4260466 0.1082213 0.4260466 0.2239388 0.2979383 0.2225251 0.301351 0.1939523 0.277902 0.2225251 0.301351 0.2204728 0.3044224 0.1913404 0.2805141 0.2204728 0.3044224 0.2178608 0.3070347 0.189288 0.2835856 0.2178608 0.3070347 0.2147894 0.3090869 0.1878745 0.2869982 0.2147894 0.3090869 0.2113766 0.3105006 0.1878745 0.2869982 0.2113766 0.3105006 0.2077536 0.3112212 0.1871539 0.2906213 0.1878745 0.2869982 0.2113766 0.3105006 0.1871539 0.2906213 0.2077536 0.3112212 0.2040597 0.3112212 0.1871539 0.2943153 0.2040597 0.3112212 0.2004365 0.3105004 0.1878745 0.2979383 0.1871539 0.2943153 0.2040597 0.3112212 0.1878745 0.2979383 0.2004365 0.3105004 0.1970237 0.3090869 0.189288 0.301351 0.1970237 0.3090869 0.1939523 0.3070347 0.1913404 0.3044224 0.189288 0.301351 0.1970237 0.3090869 0.1913404 0.3044224 0.189288 0.301351 0.1878745 0.2979383 0.2004365 0.3105004 0.1871539 0.2943153 0.1871539 0.2906213 0.2077536 0.3112212 0.1878745 0.2869982 0.189288 0.2835856 0.2178608 0.3070347 0.189288 0.2835856 0.1913404 0.2805141 0.2204728 0.3044224 0.1913404 0.2805141 0.1939523 0.277902 0.2225251 0.301351 0.1939523 0.277902 0.1970237 0.2758498 0.2239388 0.2979383 0.1970237 0.2758498 0.2004365 0.2744361 0.2239388 0.2979383 0.2004365 0.2744361 0.2040597 0.2737155 0.2246595 0.2943153 0.2239388 0.2979383 0.2004365 0.2744361 0.2246595 0.2943153 0.2040597 0.2737155 0.2077536 0.2737155 0.2246595 0.2906213 0.2077536 0.2737155 0.2113766 0.2744361 0.2239388 0.2869982 0.2246595 0.2906213 0.2077536 0.2737155 0.2239388 0.2869982 0.2113766 0.2744361 0.2147894 0.2758498 0.2204728 0.2805141 0.2147894 0.2758498 0.2178608 0.277902 0.2204728 0.2805141 0.2204728 0.2805141 0.2225251 0.2835856 0.2113766 0.2744361 0.2225251 0.2835856 0.2239388 0.2869982 0.2113766 0.2744361 0.1474788 0.4260466 0.1474788 0.4285003 0.1082213 0.4285003 0.1474788 0.4285003 0.1474788 0.4309538 0.1082213 0.4309538 0.1459357 0.4894769 0.1466564 0.4931001 0.1827208 0.4821599 0.1466564 0.4931001 0.1480701 0.4965128 0.1834415 0.4857831 0.1480701 0.4965128 0.1501224 0.4995843 0.1834415 0.4857831 0.1501224 0.4995843 0.1527343 0.5021961 0.1834415 0.4894769 0.1834415 0.4857831 0.1501224 0.4995843 0.1834415 0.4894769 0.1527343 0.5021961 0.1558058 0.5042486 0.1813071 0.4965128 0.1558058 0.5042486 0.1592187 0.5056621 0.1792547 0.4995843 0.1592187 0.5056621 0.1628416 0.5063825 0.1792547 0.4995843 0.1628416 0.5063825 0.1665356 0.5063825 0.1766429 0.5021961 0.1792547 0.4995843 0.1628416 0.5063825 0.1766429 0.5021961 0.1665356 0.5063825 0.1701586 0.5056621 0.1735715 0.5042486 0.1735715 0.5042486 0.1766429 0.5021961 0.1665356 0.5063825 0.1792547 0.4995843 0.1813071 0.4965128 0.1558058 0.5042486 0.1813071 0.4965128 0.1827208 0.4931001 0.1527343 0.5021961 0.1827208 0.4931001 0.1834415 0.4894769 0.1527343 0.5021961 0.1834415 0.4857831 0.1827208 0.4821599 0.1466564 0.4931001 0.1827208 0.4821599 0.1813071 0.4787471 0.1459357 0.4894769 0.1813071 0.4787471 0.1792547 0.4756757 0.1459357 0.4894769 0.1792547 0.4756757 0.1766429 0.4730637 0.1459357 0.4857831 0.1459357 0.4894769 0.1792547 0.4756757 0.1459357 0.4857831 0.1766429 0.4730637 0.1735713 0.4710115 0.1480701 0.4787471 0.1735713 0.4710115 0.1701586 0.4695978 0.1501224 0.4756757 0.1701586 0.4695978 0.1665356 0.468877 0.1501224 0.4756757 0.1665356 0.468877 0.1628416 0.468877 0.1527343 0.4730637 0.1501224 0.4756757 0.1665356 0.468877 0.1527343 0.4730637 0.1628416 0.468877 0.1592187 0.4695978 0.1558058 0.4710115 0.1558058 0.4710115 0.1527343 0.4730637 0.1628416 0.468877 0.1501224 0.4756757 0.1480701 0.4787471 0.1735713 0.4710115 0.1480701 0.4787471 0.1466564 0.4821599 0.1766429 0.4730637 0.1869451 0.2737155 0.1869451 0.276169 0.1476876 0.276169 0.1869451 0.276169 0.1869451 0.2786228 0.1476876 0.2786228 0.1869451 0.2786228 0.1869451 0.281076 0.1476876 0.281076 0.1869451 0.281076 0.1869451 0.2835297 0.1476876 0.2835297 0.1869451 0.2835297 0.1869451 0.2859833 0.1476876 0.2859833 0.1869451 0.2859833 0.1869451 0.288437 0.1476876 0.288437 0.1869451 0.288437 0.1869451 0.2908906 0.1476876 0.2908906 0.1869451 0.2908906 0.1869451 0.2933443 0.1476876 0.2933443 0.1869451 0.2933443 0.1869451 0.295798 0.1476876 0.295798 0.1869451 0.295798 0.1869451 0.2982512 0.1476876 0.2982512 0.1869451 0.2982512 0.1869451 0.3007048 0.1476876 0.3007048 0.1869451 0.3007048 0.1869451 0.3031585 0.1476876 0.3031585 0.1869451 0.3031585 0.1869451 0.3056122 0.1476876 0.3056122 0.1869451 0.3056122 0.1869451 0.3080657 0.1476876 0.3080657 0.1869451 0.3080657 0.1869451 0.3105193 0.1476876 0.3105193 0.1869451 0.3105193 0.1869451 0.3129729 0.1476876 0.3129729 0.1869451 0.3129729 0.1869451 0.3154264 0.1476876 0.3154264 0.1869451 0.3154264 0.1869451 0.31788 0.1476876 0.31788 0.1869451 0.31788 0.1869451 0.3203335 0.1476876 0.3203335 0.1869451 0.3203335 0.1869451 0.3227872 0.1476876 0.3227872 0.1869451 0.3227872 0.1869451 0.3252408 0.1476876 0.3252408 0.1869451 0.3252408 0.1869451 0.3276945 0.1476876 0.3276945 0.1869451 0.3276945 0.1869451 0.3301477 0.1476876 0.3301477 0.1869451 0.3301477 0.1869451 0.3326014 0.1476876 0.3326014 0.1869451 0.3326014 0.1869451 0.335055 0.1476876 0.335055 0.1869451 0.335055 0.1869451 0.3375087 0.1476876 0.3375087 0.1869451 0.3375087 0.1869451 0.3399623 0.1476876 0.3399623 0.1869451 0.3399623 0.1869451 0.3424161 0.1476876 0.3424161 0.1869451 0.3424161 0.1869451 0.3448697 0.1476876 0.3448697 0.1869451 0.3448697 0.1869451 0.347323 0.1476876 0.347323 0.2239388 0.3356525 0.222525 0.3390656 0.1939523 0.3156165 0.222525 0.3390656 0.2204728 0.3421369 0.1913404 0.3182284 0.2204728 0.3421369 0.2178607 0.3447492 0.189288 0.3213001 0.2178607 0.3447492 0.2147894 0.3468012 0.1878745 0.3247127 0.2147894 0.3468012 0.2113766 0.3482147 0.1878745 0.3247127 0.2113766 0.3482147 0.2077536 0.3489355 0.1871539 0.3283357 0.1878745 0.3247127 0.2113766 0.3482147 0.1871539 0.3283357 0.2077536 0.3489355 0.2040597 0.3489355 0.1871539 0.3320298 0.2040597 0.3489355 0.2004365 0.3482147 0.1878745 0.3356525 0.1871539 0.3320298 0.2040597 0.3489355 0.1878745 0.3356525 0.2004365 0.3482147 0.1970237 0.3468012 0.189288 0.3390656 0.1970237 0.3468012 0.1939523 0.3447492 0.1913404 0.3421369 0.189288 0.3390656 0.1970237 0.3468012 0.1913404 0.3421369 0.189288 0.3390656 0.1878745 0.3356525 0.2004365 0.3482147 0.1871539 0.3320298 0.1871539 0.3283357 0.2077536 0.3489355 0.1878745 0.3247127 0.189288 0.3213001 0.2178607 0.3447492 0.189288 0.3213001 0.1913404 0.3182284 0.2204728 0.3421369 0.1913404 0.3182284 0.1939523 0.3156165 0.222525 0.3390656 0.1939523 0.3156165 0.1970237 0.3135643 0.2239388 0.3356525 0.1970237 0.3135643 0.2004365 0.3121505 0.2239388 0.3356525 0.2004365 0.3121505 0.2040597 0.3114299 0.2246595 0.3320298 0.2239388 0.3356525 0.2004365 0.3121505 0.2246595 0.3320298 0.2040597 0.3114299 0.2077536 0.3114299 0.2246595 0.3283357 0.2077536 0.3114299 0.2113766 0.3121505 0.2239388 0.3247127 0.2246595 0.3283357 0.2077536 0.3114299 0.2239388 0.3247127 0.2113766 0.3121505 0.2147894 0.3135643 0.2204728 0.3182284 0.2147894 0.3135643 0.2178608 0.3156165 0.2204728 0.3182284 0.2204728 0.3182284 0.2225251 0.3213001 0.2113766 0.3121505 0.2225251 0.3213001 0.2239388 0.3247127 0.2113766 0.3121505 0.1869451 0.347323 0.1869451 0.3497766 0.1476876 0.3497766 0.1869451 0.3497766 0.1869451 0.3522303 0.1476876 0.3522303 0.1836503 0.4894769 0.1843709 0.4931001 0.2204353 0.4821599 0.1843709 0.4931001 0.1857845 0.4965128 0.221156 0.4857831 0.1857845 0.4965128 0.187837 0.4995843 0.221156 0.4857831 0.187837 0.4995843 0.1904488 0.5021961 0.221156 0.4894769 0.221156 0.4857831 0.187837 0.4995843 0.221156 0.4894769 0.1904488 0.5021961 0.1935204 0.5042486 0.2190217 0.4965128 0.1935204 0.5042486 0.196933 0.5056621 0.2169694 0.4995843 0.196933 0.5056621 0.200556 0.5063825 0.2169694 0.4995843 0.200556 0.5063825 0.2042502 0.5063825 0.2143573 0.5021961 0.2169694 0.4995843 0.200556 0.5063825 0.2143573 0.5021961 0.2042502 0.5063825 0.2078731 0.5056621 0.2112859 0.5042482 0.2112859 0.5042482 0.2143573 0.5021961 0.2042502 0.5063825 0.2169694 0.4995843 0.2190217 0.4965128 0.1935204 0.5042486 0.2190217 0.4965128 0.2204353 0.4931001 0.1904488 0.5021961 0.2204353 0.4931001 0.221156 0.4894769 0.1904488 0.5021961 0.221156 0.4857831 0.2204353 0.4821599 0.1843709 0.4931001 0.2204353 0.4821599 0.2190217 0.4787471 0.1836503 0.4894769 0.2190217 0.4787471 0.2169694 0.4756757 0.1836503 0.4894769 0.2169694 0.4756757 0.2143573 0.4730637 0.1836503 0.4857831 0.1836503 0.4894769 0.2169694 0.4756757 0.1836503 0.4857831 0.2143573 0.4730637 0.2112859 0.4710115 0.1857845 0.4787471 0.2112859 0.4710115 0.2078731 0.4695978 0.187837 0.4756757 0.2078731 0.4695978 0.2042502 0.468877 0.187837 0.4756757 0.2042502 0.468877 0.200556 0.468877 0.1904488 0.4730637 0.187837 0.4756757 0.2042502 0.468877 0.1904488 0.4730637 0.200556 0.468877 0.196933 0.4695978 0.1935204 0.4710115 0.1935204 0.4710115 0.1904488 0.4730637 0.200556 0.468877 0.187837 0.4756757 0.1857845 0.4787471 0.2112859 0.4710115 0.1857845 0.4787471 0.1843709 0.4821599 0.2143573 0.4730637 0.1869451 0.352439 0.1869451 0.3548926 0.1476876 0.3548926 0.1869451 0.3548926 0.1869451 0.3573463 0.1476876 0.3573463 0.1869451 0.3573463 0.1869451 0.3597999 0.1476876 0.3597999 0.1869451 0.3597999 0.1869451 0.3622536 0.1476876 0.3622536 0.1869451 0.3622536 0.1869451 0.3647069 0.1476876 0.3647069 0.1869451 0.3647069 0.1869451 0.3671605 0.1476876 0.3671605 0.1869451 0.3671605 0.1869451 0.3696142 0.1476876 0.3696142 0.1869451 0.3696142 0.1869451 0.3720678 0.1476876 0.3720678 0.1869451 0.3720678 0.1869451 0.3745215 0.1476876 0.3745215 0.1869451 0.3745215 0.1869451 0.3769749 0.1476876 0.3769749 0.1869451 0.3769749 0.1869451 0.3794284 0.1476876 0.3794284 0.1869451 0.3794284 0.1869451 0.3818821 0.1476876 0.3818821 0.1869451 0.3818821 0.1869451 0.3843358 0.1476876 0.3843358 0.1869451 0.3843358 0.1869451 0.3867892 0.1476876 0.3867892 0.1869451 0.3867892 0.1869451 0.3892428 0.1476876 0.3892428 0.1869451 0.3892428 0.1869451 0.3916965 0.1476876 0.3916965 0.1869451 0.3916965 0.1869451 0.3941501 0.1476876 0.3941501 0.1869451 0.3941501 0.1869451 0.3966034 0.1476876 0.3966034 0.1869451 0.3966034 0.1869451 0.399057 0.1476876 0.399057 0.1869451 0.399057 0.1869451 0.4015107 0.1476876 0.4015107 0.1869451 0.4015107 0.1869451 0.4039644 0.1476876 0.4039644 0.1869451 0.4039644 0.1869451 0.406418 0.1476876 0.406418 0.1869451 0.406418 0.1869451 0.4088717 0.1476876 0.4088717 0.1869451 0.4088717 0.1869451 0.4113253 0.1476876 0.4113253 0.1869451 0.4113253 0.1869451 0.4137786 0.1476876 0.4137786 0.1869451 0.4137786 0.1869451 0.4162324 0.1476876 0.4162324 0.1869451 0.4162324 0.1869451 0.4186859 0.1476876 0.4186859 0.1869451 0.4186859 0.1869451 0.4211395 0.1476876 0.4211395 0.1869451 0.4211395 0.1869451 0.423593 0.1476876 0.423593 0.1869451 0.423593 0.1869451 0.4260466 0.1476876 0.4260466 0.2239388 0.376662 0.222525 0.3800746 0.1939523 0.3566254 0.222525 0.3800746 0.2204728 0.3831459 0.1913404 0.3592376 0.2204728 0.3831459 0.2178607 0.3857582 0.189288 0.3623092 0.2178607 0.3857582 0.2147894 0.3878105 0.1878745 0.3657219 0.2147894 0.3878105 0.2113766 0.3892242 0.1878745 0.3657219 0.2113766 0.3892242 0.2077536 0.3899446 0.1871539 0.3693447 0.1878745 0.3657219 0.2113766 0.3892242 0.1871539 0.3693447 0.2077536 0.3899446 0.2040597 0.3899446 0.1871539 0.3730388 0.2040597 0.3899446 0.2004365 0.3892242 0.1878745 0.3766618 0.1871539 0.3730388 0.2040597 0.3899446 0.1878745 0.3766618 0.2004365 0.3892242 0.1970237 0.3878105 0.189288 0.3800746 0.1970237 0.3878105 0.1939523 0.3857582 0.1913404 0.3831459 0.189288 0.3800746 0.1970237 0.3878105 0.1913404 0.3831459 0.189288 0.3800746 0.1878745 0.3766618 0.2004365 0.3892242 0.1871539 0.3730388 0.1871539 0.3693447 0.2077536 0.3899446 0.1878745 0.3657219 0.189288 0.3623092 0.2178607 0.3857582 0.189288 0.3623092 0.1913404 0.3592376 0.2204728 0.3831459 0.1913404 0.3592376 0.1939523 0.3566254 0.222525 0.3800746 0.1939523 0.3566254 0.1970237 0.3545733 0.2239388 0.376662 0.1970237 0.3545733 0.2004365 0.3531596 0.2239388 0.376662 0.2004365 0.3531596 0.2040597 0.352439 0.2246595 0.3730388 0.2239388 0.376662 0.2004365 0.3531596 0.2246595 0.3730388 0.2040597 0.352439 0.2077536 0.352439 0.2246595 0.3693447 0.2077536 0.352439 0.2113766 0.3531596 0.2239388 0.3657219 0.2246595 0.3693447 0.2077536 0.352439 0.2239388 0.3657219 0.2113766 0.3531596 0.2147894 0.3545733 0.2204728 0.3592376 0.2147894 0.3545733 0.2178608 0.3566254 0.2204728 0.3592376 0.2204728 0.3592376 0.2225251 0.3623092 0.2113766 0.3531596 0.2225251 0.3623092 0.2239388 0.3657219 0.2113766 0.3531596 0.1869451 0.4260466 0.1869451 0.4285003 0.1476876 0.4285003 0.1869451 0.4285003 0.1869451 0.4309538 0.1476876 0.4309538 0.2213647 0.4894769 0.2220854 0.4931001 0.2581497 0.4821599 0.2220854 0.4931001 0.2234989 0.4965128 0.2588704 0.4857831 0.2234989 0.4965128 0.2255512 0.4995843 0.2588704 0.4857831 0.2255512 0.4995843 0.2281633 0.5021961 0.2588704 0.4894769 0.2588704 0.4857831 0.2255512 0.4995843 0.2588704 0.4894769 0.2281633 0.5021961 0.2312347 0.5042486 0.256736 0.4965128 0.2312347 0.5042486 0.2346475 0.5056621 0.2546838 0.4995843 0.2346475 0.5056621 0.2382706 0.5063825 0.2546838 0.4995843 0.2382706 0.5063825 0.2419646 0.5063825 0.2520717 0.5021961 0.2546838 0.4995843 0.2382706 0.5063825 0.2520717 0.5021961 0.2419646 0.5063825 0.2455876 0.5056621 0.2490001 0.5042486 0.2490001 0.5042486 0.2520717 0.5021961 0.2419646 0.5063825 0.2546838 0.4995843 0.256736 0.4965128 0.2312347 0.5042486 0.256736 0.4965128 0.2581497 0.4931001 0.2281633 0.5021961 0.2581497 0.4931001 0.2588704 0.4894769 0.2281633 0.5021961 0.2588704 0.4857831 0.2581497 0.4821599 0.2220854 0.4931001 0.2581497 0.4821599 0.256736 0.4787471 0.2213647 0.4894769 0.256736 0.4787471 0.2546838 0.4756757 0.2213647 0.4894769 0.2546838 0.4756757 0.2520717 0.4730637 0.2213647 0.4857831 0.2213647 0.4894769 0.2546838 0.4756757 0.2213647 0.4857831 0.2520717 0.4730637 0.2490001 0.4710115 0.2234989 0.4787471 0.2490001 0.4710115 0.2455874 0.4695978 0.2255512 0.4756757 0.2455874 0.4695978 0.2419646 0.468877 0.2255512 0.4756757 0.2419646 0.468877 0.2382706 0.468877 0.2281633 0.4730637 0.2255512 0.4756757 0.2419646 0.468877 0.2281633 0.4730637 0.2382706 0.468877 0.2346475 0.4695978 0.2312347 0.4710115 0.2312347 0.4710115 0.2281633 0.4730637 0.2382706 0.468877 0.2255512 0.4756757 0.2234989 0.4787471 0.2490001 0.4710115 0.2234989 0.4787471 0.2220854 0.4821599 0.2520717 0.4730637 0.7876291 0.5065029 0.7711581 0.5065029 0.7711581 0.3747343 0.7711581 0.5065029 0.754687 0.5065029 0.754687 0.3747343 0.754687 0.5065029 0.7382159 0.5065029 0.7382159 0.3747343 0.7382159 0.5065029 0.7217448 0.5065029 0.7217448 0.3747343 0.7217448 0.5065029 0.7052738 0.5065029 0.7052738 0.3747343 0.7052738 0.5065029 0.6888027 0.5065029 0.6888027 0.3747343 0.6888027 0.5065029 0.6723316 0.5065029 0.6723316 0.3747343 0.6723316 0.5065029 0.6558606 0.5065029 0.6558606 0.3747343 0.6558606 0.5065029 0.6393895 0.5065029 0.6393895 0.3747343 0.6393895 0.5065029 0.6229183 0.5065029 0.6229183 0.3747343 0.6229183 0.5065029 0.6064473 0.5065029 0.6064473 0.3747343 0.6064473 0.5065029 0.5899763 0.5065029 0.5899763 0.3747343 0.5899763 0.5065029 0.5735051 0.5065029 0.5735051 0.3747343 0.5735051 0.5065029 0.557034 0.5065029 0.557034 0.3747343 0.6336622 0.3441658 0.6265154 0.3489411 0.6265154 0.3082364 0.6265154 0.3489411 0.6180853 0.3506181 0.6180853 0.3065595 0.6180853 0.3506181 0.6096551 0.3489411 0.6096551 0.3082364 0.6096551 0.3489411 0.6025082 0.3441658 0.6025082 0.3130117 0.6025082 0.3441658 0.5977328 0.337019 0.6025082 0.3130117 0.5977328 0.337019 0.5960559 0.3285888 0.5977328 0.3201586 0.6025082 0.3130117 0.5977328 0.337019 0.5977328 0.3201586 0.6025082 0.3130117 0.6096551 0.3082364 0.6096551 0.3489411 0.6096551 0.3082364 0.6180853 0.3065595 0.6180853 0.3506181 0.6180853 0.3065595 0.6265154 0.3082364 0.6265154 0.3489411 0.6265154 0.3082364 0.6336622 0.3130117 0.6336622 0.3441658 0.6336622 0.3130117 0.6384376 0.3201586 0.6336622 0.3441658 0.6384376 0.3201586 0.6401145 0.3285888 0.6384376 0.337019 0.557034 0.5065029 0.540563 0.5065029 0.540563 0.3747343 0.540563 0.5065029 0.5240918 0.5065029 0.5240918 0.3747343 0.6555492 0.3489411 0.6639795 0.3506181 0.6639795 0.3065595 0.6639795 0.3506181 0.6724098 0.3489411 0.6724098 0.3082364 0.6724098 0.3489411 0.6795566 0.3441658 0.6724098 0.3082364 0.6795566 0.3441658 0.6843319 0.337019 0.6795566 0.3130117 0.6724098 0.3082364 0.6795566 0.3441658 0.6795566 0.3130117 0.6843319 0.337019 0.6860088 0.3285888 0.6843319 0.3201586 0.6843319 0.3201586 0.6795566 0.3130117 0.6843319 0.337019 0.6724098 0.3082364 0.6639795 0.3065595 0.6639795 0.3506181 0.6639795 0.3065595 0.6555492 0.3082364 0.6555492 0.3489411 0.6555492 0.3082364 0.6484024 0.3130117 0.6555492 0.3489411 0.6484024 0.3130117 0.6436271 0.3201586 0.6484024 0.3441658 0.6555492 0.3489411 0.6484024 0.3130117 0.6484024 0.3441658 0.6436271 0.3201586 0.6419504 0.3285888 0.6436271 0.337019 0.7056843 0.2639958 0.7056843 0.1708528 0.6125414 0.1708528 0.7988276 0.2639958 0.7988276 0.1708528 0.7056843 0.1708528 0.8919706 0.2639958 0.8919706 0.1708528 0.7988276 0.1708528 0.9851137 0.2639958 0.9851137 0.1708528 0.8919706 0.1708528 0.8919706 0.3571389 0.8919706 0.2639958 0.7988276 0.2639958 0.8919706 0.1708528 0.8919706 0.07770967 0.7988276 0.07770967 0.7876291 0.5065029 0.7711581 0.5065029 0.7711581 0.3747343 0.7711581 0.5065029 0.754687 0.5065029 0.754687 0.3747343 0.754687 0.5065029 0.7382159 0.5065029 0.7382159 0.3747343 0.7382159 0.5065029 0.7217448 0.5065029 0.7217448 0.3747343 0.7217448 0.5065029 0.7052738 0.5065029 0.7052738 0.3747343 0.7052738 0.5065029 0.6888027 0.5065029 0.6888027 0.3747343 0.6888027 0.5065029 0.6723316 0.5065029 0.6723316 0.3747343 0.6723316 0.5065029 0.6558606 0.5065029 0.6558606 0.3747343 0.6558606 0.5065029 0.6393895 0.5065029 0.6393895 0.3747343 0.6393895 0.5065029 0.6229183 0.5065029 0.6229183 0.3747343 0.6229183 0.5065029 0.6064473 0.5065029 0.6064473 0.3747343 0.6064473 0.5065029 0.5899763 0.5065029 0.5899763 0.3747343 0.5899763 0.5065029 0.5735051 0.5065029 0.5735051 0.3747343 0.5735051 0.5065029 0.557034 0.5065029 0.557034 0.3747343 0.6336622 0.3441658 0.6265154 0.3489411 0.6265154 0.3082364 0.6265154 0.3489411 0.6180853 0.3506181 0.6180853 0.3065595 0.6180853 0.3506181 0.6096551 0.3489411 0.6096551 0.3082364 0.6096551 0.3489411 0.6025082 0.3441658 0.6025082 0.3130117 0.6025082 0.3441658 0.5977328 0.337019 0.6025082 0.3130117 0.5977328 0.337019 0.5960559 0.3285888 0.5977328 0.3201586 0.6025082 0.3130117 0.5977328 0.337019 0.5977328 0.3201586 0.6025082 0.3130117 0.6096551 0.3082364 0.6096551 0.3489411 0.6096551 0.3082364 0.6180853 0.3065595 0.6180853 0.3506181 0.6180853 0.3065595 0.6265154 0.3082364 0.6265154 0.3489411 0.6265154 0.3082364 0.6336622 0.3130117 0.6336622 0.3441658 0.6336622 0.3130117 0.6384376 0.3201586 0.6336622 0.3441658 0.6384376 0.3201586 0.6401145 0.3285888 0.6384376 0.337019 0.557034 0.5065029 0.540563 0.5065029 0.540563 0.3747343 0.540563 0.5065029 0.5240918 0.5065029 0.5240918 0.3747343 0.6555492 0.3489411 0.6639795 0.3506181 0.6639795 0.3065595 0.6639795 0.3506181 0.6724098 0.3489411 0.6724098 0.3082364 0.6724098 0.3489411 0.6795566 0.3441658 0.6724098 0.3082364 0.6795566 0.3441658 0.6843319 0.337019 0.6795566 0.3130117 0.6724098 0.3082364 0.6795566 0.3441658 0.6795566 0.3130117 0.6843319 0.337019 0.6860088 0.3285888 0.6843319 0.3201586 0.6843319 0.3201586 0.6795566 0.3130117 0.6843319 0.337019 0.6724098 0.3082364 0.6639795 0.3065595 0.6639795 0.3506181 0.6639795 0.3065595 0.6555492 0.3082364 0.6555492 0.3489411 0.6555492 0.3082364 0.6484024 0.3130117 0.6555492 0.3489411 0.6484024 0.3130117 0.6436271 0.3201586 0.6484024 0.3441658 0.6555492 0.3489411 0.6484024 0.3130117 0.6484024 0.3441658 0.6436271 0.3201586 0.6419504 0.3285888 0.6436271 0.337019 0.7876291 0.5065029 0.7711581 0.5065029 0.7711581 0.3747343 0.7711581 0.5065029 0.754687 0.5065029 0.754687 0.3747343 0.754687 0.5065029 0.7382159 0.5065029 0.7382159 0.3747343 0.7382159 0.5065029 0.7217448 0.5065029 0.7217448 0.3747343 0.7217448 0.5065029 0.7052738 0.5065029 0.7052738 0.3747343 0.7052738 0.5065029 0.6888027 0.5065029 0.6888027 0.3747343 0.6888027 0.5065029 0.6723316 0.5065029 0.6723316 0.3747343 0.6723316 0.5065029 0.6558606 0.5065029 0.6558606 0.3747343 0.6558606 0.5065029 0.6393895 0.5065029 0.6393895 0.3747343 0.6393895 0.5065029 0.6229183 0.5065029 0.6229183 0.3747343 0.6229183 0.5065029 0.6064473 0.5065029 0.6064473 0.3747343 0.6064473 0.5065029 0.5899763 0.5065029 0.5899763 0.3747343 0.5899763 0.5065029 0.5735051 0.5065029 0.5735051 0.3747343 0.5735051 0.5065029 0.557034 0.5065029 0.557034 0.3747343 0.6336622 0.3441658 0.6265154 0.3489411 0.6265154 0.3082364 0.6265154 0.3489411 0.6180853 0.3506181 0.6180853 0.3065595 0.6180853 0.3506181 0.6096551 0.3489411 0.6096551 0.3082364 0.6096551 0.3489411 0.6025082 0.3441658 0.6025082 0.3130117 0.6025082 0.3441658 0.5977328 0.337019 0.6025082 0.3130117 0.5977328 0.337019 0.5960559 0.3285888 0.5977328 0.3201586 0.6025082 0.3130117 0.5977328 0.337019 0.5977328 0.3201586 0.6025082 0.3130117 0.6096551 0.3082364 0.6096551 0.3489411 0.6096551 0.3082364 0.6180853 0.3065595 0.6180853 0.3506181 0.6180853 0.3065595 0.6265154 0.3082364 0.6265154 0.3489411 0.6265154 0.3082364 0.6336622 0.3130117 0.6336622 0.3441658 0.6336622 0.3130117 0.6384376 0.3201586 0.6336622 0.3441658 0.6384376 0.3201586 0.6401145 0.3285888 0.6384376 0.337019 0.557034 0.5065029 0.540563 0.5065029 0.540563 0.3747343 0.540563 0.5065029 0.5240918 0.5065029 0.5240918 0.3747343 0.6555492 0.3489411 0.6639795 0.3506181 0.6639795 0.3065595 0.6639795 0.3506181 0.6724098 0.3489411 0.6724098 0.3082364 0.6724098 0.3489411 0.6795566 0.3441658 0.6724098 0.3082364 0.6795566 0.3441658 0.6843319 0.337019 0.6795566 0.3130117 0.6724098 0.3082364 0.6795566 0.3441658 0.6795566 0.3130117 0.6843319 0.337019 0.6860088 0.3285888 0.6843319 0.3201586 0.6843319 0.3201586 0.6795566 0.3130117 0.6843319 0.337019 0.6724098 0.3082364 0.6639795 0.3065595 0.6639795 0.3506181 0.6639795 0.3065595 0.6555492 0.3082364 0.6555492 0.3489411 0.6555492 0.3082364 0.6484024 0.3130117 0.6555492 0.3489411 0.6484024 0.3130117 0.6436271 0.3201586 0.6484024 0.3441658 0.6555492 0.3489411 0.6484024 0.3130117 0.6484024 0.3441658 0.6436271 0.3201586 0.6419504 0.3285888 0.6436271 0.337019 0.7876291 0.5065029 0.7711581 0.5065029 0.7711581 0.3747343 0.7711581 0.5065029 0.754687 0.5065029 0.754687 0.3747343 0.754687 0.5065029 0.7382159 0.5065029 0.7382159 0.3747343 0.7382159 0.5065029 0.7217448 0.5065029 0.7217448 0.3747343 0.7217448 0.5065029 0.7052738 0.5065029 0.7052738 0.3747343 0.7052738 0.5065029 0.6888027 0.5065029 0.6888027 0.3747343 0.6888027 0.5065029 0.6723316 0.5065029 0.6723316 0.3747343 0.6723316 0.5065029 0.6558606 0.5065029 0.6558606 0.3747343 0.6558606 0.5065029 0.6393895 0.5065029 0.6393895 0.3747343 0.6393895 0.5065029 0.6229183 0.5065029 0.6229183 0.3747343 0.6229183 0.5065029 0.6064473 0.5065029 0.6064473 0.3747343 0.6064473 0.5065029 0.5899763 0.5065029 0.5899763 0.3747343 0.5899763 0.5065029 0.5735051 0.5065029 0.5735051 0.3747343 0.5735051 0.5065029 0.557034 0.5065029 0.557034 0.3747343 0.6336622 0.3441658 0.6265154 0.3489411 0.6265154 0.3082364 0.6265154 0.3489411 0.6180853 0.3506181 0.6180853 0.3065595 0.6180853 0.3506181 0.6096551 0.3489411 0.6096551 0.3082364 0.6096551 0.3489411 0.6025082 0.3441658 0.6025082 0.3130117 0.6025082 0.3441658 0.5977328 0.337019 0.6025082 0.3130117 0.5977328 0.337019 0.5960559 0.3285888 0.5977328 0.3201586 0.6025082 0.3130117 0.5977328 0.337019 0.5977328 0.3201586 0.6025082 0.3130117 0.6096551 0.3082364 0.6096551 0.3489411 0.6096551 0.3082364 0.6180853 0.3065595 0.6180853 0.3506181 0.6180853 0.3065595 0.6265154 0.3082364 0.6265154 0.3489411 0.6265154 0.3082364 0.6336622 0.3130117 0.6336622 0.3441658 0.6336622 0.3130117 0.6384376 0.3201586 0.6336622 0.3441658 0.6384376 0.3201586 0.6401145 0.3285888 0.6384376 0.337019 0.557034 0.5065029 0.540563 0.5065029 0.540563 0.3747343 0.540563 0.5065029 0.5240918 0.5065029 0.5240918 0.3747343 0.6555492 0.3489411 0.6639795 0.3506181 0.6639795 0.3065595 0.6639795 0.3506181 0.6724098 0.3489411 0.6724098 0.3082364 0.6724098 0.3489411 0.6795566 0.3441658 0.6724098 0.3082364 0.6795566 0.3441658 0.6843319 0.337019 0.6795566 0.3130117 0.6724098 0.3082364 0.6795566 0.3441658 0.6795566 0.3130117 0.6843319 0.337019 0.6860088 0.3285888 0.6843319 0.3201586 0.6843319 0.3201586 0.6795566 0.3130117 0.6843319 0.337019 0.6724098 0.3082364 0.6639795 0.3065595 0.6639795 0.3506181 0.6639795 0.3065595 0.6555492 0.3082364 0.6555492 0.3489411 0.6555492 0.3082364 0.6484024 0.3130117 0.6555492 0.3489411 0.6484024 0.3130117 0.6436271 0.3201586 0.6484024 0.3441658 0.6555492 0.3489411 0.6484024 0.3130117 0.6484024 0.3441658 0.6436271 0.3201586 0.6419504 0.3285888 0.6436271 0.337019 - - - - - - - - - - - - - - -

336 124 567 340 124 568 339 124 569 336 17 570 341 17 571 335 17 572 335 2 573 338 2 574 336 2 575 338 5 576 342 5 577 340 5 578 339 22 579 342 22 580 341 22 581 341 125 582 337 125 583 335 125 584 352 17 675 350 17 676 368 17 677 480 17 879 478 17 880 496 17 881 608 17 1083 606 17 1084 624 17 1085 736 17 1287 734 17 1288 752 17 1289 856 270 1401 857 270 1402 855 270 1403 858 271 1404 859 271 1405 857 271 1406 860 272 1407 861 272 1408 859 272 1409 862 273 1410 863 273 1411 861 273 1412 864 274 1413 865 274 1414 863 274 1415 866 275 1416 867 275 1417 865 275 1418 868 276 1419 869 276 1420 867 276 1421 870 277 1422 871 277 1423 869 277 1424 872 278 1425 873 278 1426 871 278 1427 874 279 1428 875 279 1429 873 279 1430 876 280 1431 877 280 1432 875 280 1433 878 281 1434 879 281 1435 877 281 1436 880 282 1437 881 282 1438 879 282 1439 882 283 1440 883 283 1441 881 283 1442 860 17 1443 866 17 1444 862 17 1445 884 284 1446 885 284 1447 883 284 1448 886 285 1449 855 285 1450 885 285 1451 881 5 1452 883 5 1453 877 5 1454 896 286 1473 897 286 1474 895 286 1475 898 287 1476 899 287 1477 897 287 1478 900 272 1479 901 272 1480 899 272 1481 902 273 1482 903 273 1483 901 273 1484 904 288 1485 905 288 1486 903 288 1487 906 275 1488 907 275 1489 905 275 1490 908 276 1491 909 276 1492 907 276 1493 910 277 1494 911 277 1495 909 277 1496 912 289 1497 913 289 1498 911 289 1499 914 279 1500 915 279 1501 913 279 1502 916 280 1503 917 280 1504 915 280 1505 918 281 1506 919 281 1507 917 281 1508 920 290 1509 921 290 1510 919 290 1511 922 283 1512 923 283 1513 921 283 1514 900 17 1515 906 17 1516 902 17 1517 924 284 1518 925 284 1519 923 284 1520 926 291 1521 895 291 1522 925 291 1523 921 5 1524 923 5 1525 917 5 1526 928 286 1527 929 286 1528 927 286 1529 930 287 1530 931 287 1531 929 287 1532 932 272 1533 933 272 1534 931 272 1535 934 273 1536 935 273 1537 933 273 1538 936 288 1539 937 288 1540 935 288 1541 938 275 1542 939 275 1543 937 275 1544 940 276 1545 941 276 1546 939 276 1547 942 277 1548 943 277 1549 941 277 1550 944 289 1551 945 289 1552 943 289 1553 946 279 1554 947 279 1555 945 279 1556 948 280 1557 949 280 1558 947 280 1559 950 281 1560 951 281 1561 949 281 1562 952 290 1563 953 290 1564 951 290 1565 954 283 1566 955 283 1567 953 283 1568 932 17 1569 938 17 1570 934 17 1571 956 284 1572 957 284 1573 955 284 1574 958 291 1575 927 291 1576 957 291 1577 953 5 1578 955 5 1579 949 5 1580 960 270 1581 961 270 1582 959 270 1583 962 271 1584 963 271 1585 961 271 1586 964 272 1587 965 272 1588 963 272 1589 966 273 1590 967 273 1591 965 273 1592 968 274 1593 969 274 1594 967 274 1595 970 275 1596 971 275 1597 969 275 1598 972 276 1599 973 276 1600 971 276 1601 974 277 1602 975 277 1603 973 277 1604 976 278 1605 977 278 1606 975 278 1607 978 279 1608 979 279 1609 977 279 1610 980 280 1611 981 280 1612 979 280 1613 982 281 1614 983 281 1615 981 281 1616 984 282 1617 985 282 1618 983 282 1619 986 283 1620 987 283 1621 985 283 1622 964 17 1623 970 17 1624 966 17 1625 988 284 1626 989 284 1627 987 284 1628 990 285 1629 959 285 1630 989 285 1631 985 5 1632 987 5 1633 981 5 1634 336 124 3390 338 124 3391 340 124 3392 336 17 3393 339 17 3394 341 17 3395 335 2 3396 337 2 3397 338 2 3398 338 5 3399 337 5 3400 342 5 3401 339 22 3402 340 22 3403 342 22 3404 341 125 3405 342 125 3406 337 125 3407 348 17 3498 346 17 3499 374 17 3500 346 17 3501 344 17 3502 376 17 3503 344 17 3504 406 17 3505 378 17 3506 406 17 3507 404 17 3508 380 17 3509 404 17 3510 402 17 3511 380 17 3512 402 518 3513 400 518 3514 382 518 3515 380 17 3516 402 17 3517 382 17 3518 400 17 3519 398 17 3520 384 17 3521 398 17 3522 396 17 3523 386 17 3524 384 17 3525 398 17 3526 386 17 3527 396 17 3528 394 17 3529 388 17 3530 394 17 3531 392 17 3532 390 17 3533 388 519 3534 394 519 3535 390 519 3536 388 17 3537 386 17 3538 396 17 3539 384 17 3540 382 17 3541 400 17 3542 380 17 3543 378 17 3544 406 17 3545 378 17 3546 376 17 3547 344 17 3548 376 17 3549 374 17 3550 346 17 3551 374 17 3552 372 17 3553 348 17 3554 372 17 3555 370 17 3556 348 17 3557 370 520 3558 368 520 3559 350 520 3560 348 17 3561 370 17 3562 350 17 3563 368 17 3564 366 17 3565 352 17 3566 366 17 3567 364 17 3568 354 17 3569 352 17 3570 366 17 3571 354 17 3572 364 17 3573 362 17 3574 356 17 3575 362 17 3576 360 17 3577 358 17 3578 356 521 3579 362 521 3580 358 521 3581 356 17 3582 354 17 3583 364 17 3584 476 17 4038 474 17 4039 502 17 4040 474 17 4041 472 17 4042 504 17 4043 472 17 4044 534 17 4045 506 17 4046 534 17 4047 532 17 4048 508 17 4049 532 17 4050 530 17 4051 508 17 4052 530 518 4053 528 518 4054 510 518 4055 508 17 4056 530 17 4057 510 17 4058 528 17 4059 526 17 4060 512 17 4061 526 17 4062 524 17 4063 514 17 4064 512 17 4065 526 17 4066 514 17 4067 524 578 4068 522 578 4069 518 578 4070 522 17 4071 520 17 4072 518 17 4073 518 17 4074 516 17 4075 524 17 4076 516 17 4077 514 17 4078 524 17 4079 512 17 4080 510 17 4081 528 17 4082 508 17 4083 506 17 4084 534 17 4085 506 17 4086 504 17 4087 472 17 4088 504 17 4089 502 17 4090 474 17 4091 502 17 4092 500 17 4093 476 17 4094 500 17 4095 498 17 4096 476 17 4097 498 520 4098 496 520 4099 478 520 4100 476 17 4101 498 17 4102 478 17 4103 496 17 4104 494 17 4105 480 17 4106 494 17 4107 492 17 4108 482 17 4109 480 17 4110 494 17 4111 482 17 4112 492 521 4113 490 521 4114 486 521 4115 490 17 4116 488 17 4117 486 17 4118 486 17 4119 484 17 4120 492 17 4121 484 17 4122 482 17 4123 492 17 4124 604 17 4578 602 17 4579 630 17 4580 602 17 4581 600 17 4582 632 17 4583 600 17 4584 662 17 4585 634 17 4586 662 17 4587 660 17 4588 636 17 4589 660 17 4590 658 17 4591 636 17 4592 658 617 4593 656 617 4594 638 617 4595 636 17 4596 658 17 4597 638 17 4598 656 17 4599 654 17 4600 640 17 4601 654 17 4602 652 17 4603 642 17 4604 640 17 4605 654 17 4606 642 17 4607 652 17 4608 650 17 4609 644 17 4610 650 17 4611 648 17 4612 646 17 4613 644 578 4614 650 578 4615 646 578 4616 644 17 4617 642 17 4618 652 17 4619 640 17 4620 638 17 4621 656 17 4622 636 17 4623 634 17 4624 662 17 4625 634 17 4626 632 17 4627 600 17 4628 632 17 4629 630 17 4630 602 17 4631 630 17 4632 628 17 4633 604 17 4634 628 17 4635 626 17 4636 604 17 4637 626 618 4638 624 618 4639 606 618 4640 604 17 4641 626 17 4642 606 17 4643 624 17 4644 622 17 4645 608 17 4646 622 17 4647 620 17 4648 610 17 4649 608 17 4650 622 17 4651 610 17 4652 620 521 4653 618 521 4654 614 521 4655 618 17 4656 616 17 4657 614 17 4658 614 17 4659 612 17 4660 620 17 4661 612 17 4662 610 17 4663 620 17 4664 732 17 5118 730 17 5119 758 17 5120 730 17 5121 728 17 5122 760 17 5123 728 17 5124 790 17 5125 762 17 5126 790 17 5127 788 17 5128 764 17 5129 788 17 5130 786 17 5131 764 17 5132 786 617 5133 784 617 5134 766 617 5135 764 17 5136 786 17 5137 766 17 5138 784 17 5139 782 17 5140 768 17 5141 782 17 5142 780 17 5143 770 17 5144 768 17 5145 782 17 5146 770 17 5147 780 17 5148 778 17 5149 772 17 5150 778 17 5151 776 17 5152 774 17 5153 772 519 5154 778 519 5155 774 519 5156 772 17 5157 770 17 5158 780 17 5159 768 17 5160 766 17 5161 784 17 5162 764 17 5163 762 17 5164 790 17 5165 762 17 5166 760 17 5167 728 17 5168 760 17 5169 758 17 5170 730 17 5171 758 17 5172 756 17 5173 732 17 5174 756 17 5175 754 17 5176 732 17 5177 754 618 5178 752 618 5179 734 618 5180 732 17 5181 754 17 5182 734 17 5183 752 17 5184 750 17 5185 736 17 5186 750 17 5187 748 17 5188 738 17 5189 736 17 5190 750 17 5191 738 17 5192 748 521 5193 746 521 5194 742 521 5195 746 17 5196 744 17 5197 742 17 5198 742 17 5199 740 17 5200 748 17 5201 740 17 5202 738 17 5203 748 17 5204 856 665 5568 858 665 5569 857 665 5570 858 666 5571 860 666 5572 859 666 5573 860 667 5574 862 667 5575 861 667 5576 862 668 5577 864 668 5578 863 668 5579 864 288 5580 866 288 5581 865 288 5582 866 669 5583 868 669 5584 867 669 5585 868 670 5586 870 670 5587 869 670 5588 870 671 5589 872 671 5590 871 671 5591 872 672 5592 874 672 5593 873 672 5594 874 673 5595 876 673 5596 875 673 5597 876 674 5598 878 674 5599 877 674 5600 878 281 5601 880 281 5602 879 281 5603 880 282 5604 882 282 5605 881 282 5606 882 675 5607 884 675 5608 883 675 5609 860 17 5610 858 17 5611 870 17 5612 858 676 5613 856 676 5614 872 676 5615 856 17 5616 886 17 5617 874 17 5618 886 677 5619 884 677 5620 876 677 5621 884 17 5622 882 17 5623 876 17 5624 882 17 5625 880 17 5626 878 17 5627 876 17 5628 882 17 5629 878 17 5630 876 17 5631 874 17 5632 886 17 5633 874 678 5634 872 678 5635 856 678 5636 872 17 5637 870 17 5638 858 17 5639 870 679 5640 868 679 5641 860 679 5642 868 17 5643 866 17 5644 860 17 5645 866 17 5646 864 17 5647 862 17 5648 884 680 5649 886 680 5650 885 680 5651 886 681 5652 856 681 5653 855 681 5654 885 5 5655 855 5 5656 871 5 5657 855 682 5658 857 682 5659 869 682 5660 857 5 5661 859 5 5662 869 5 5663 859 5 5664 861 5 5665 867 5 5666 869 5 5667 859 5 5668 867 5 5669 861 5 5670 863 5 5671 865 5 5672 865 5 5673 867 5 5674 861 5 5675 869 5 5676 871 5 5677 855 5 5678 871 683 5679 873 683 5680 885 683 5681 873 5 5682 875 5 5683 885 5 5684 875 5 5685 877 5 5686 883 5 5687 885 5 5688 875 5 5689 883 5 5690 877 5 5691 879 5 5692 881 5 5693 896 665 5712 898 665 5713 897 665 5714 898 666 5715 900 666 5716 899 666 5717 900 667 5718 902 667 5719 901 667 5720 902 273 5721 904 273 5722 903 273 5723 904 288 5724 906 288 5725 905 288 5726 906 669 5727 908 669 5728 907 669 5729 908 684 5730 910 684 5731 909 684 5732 910 685 5733 912 685 5734 911 685 5735 912 289 5736 914 289 5737 913 289 5738 914 673 5739 916 673 5740 915 673 5741 916 674 5742 918 674 5743 917 674 5744 918 686 5745 920 686 5746 919 686 5747 920 282 5748 922 282 5749 921 282 5750 922 675 5751 924 675 5752 923 675 5753 900 17 5754 898 17 5755 910 17 5756 898 676 5757 896 676 5758 912 676 5759 896 17 5760 926 17 5761 914 17 5762 926 677 5763 924 677 5764 916 677 5765 924 17 5766 922 17 5767 916 17 5768 922 17 5769 920 17 5770 918 17 5771 916 17 5772 922 17 5773 918 17 5774 916 17 5775 914 17 5776 926 17 5777 914 678 5778 912 678 5779 896 678 5780 912 17 5781 910 17 5782 898 17 5783 910 679 5784 908 679 5785 900 679 5786 908 17 5787 906 17 5788 900 17 5789 906 17 5790 904 17 5791 902 17 5792 924 680 5793 926 680 5794 925 680 5795 926 291 5796 896 291 5797 895 291 5798 925 5 5799 895 5 5800 911 5 5801 895 682 5802 897 682 5803 909 682 5804 897 5 5805 899 5 5806 909 5 5807 899 5 5808 901 5 5809 907 5 5810 909 5 5811 899 5 5812 907 5 5813 901 5 5814 903 5 5815 905 5 5816 905 5 5817 907 5 5818 901 5 5819 909 5 5820 911 5 5821 895 5 5822 911 683 5823 913 683 5824 925 683 5825 913 5 5826 915 5 5827 925 5 5828 915 5 5829 917 5 5830 923 5 5831 925 5 5832 915 5 5833 923 5 5834 917 5 5835 919 5 5836 921 5 5837 928 665 5838 930 665 5839 929 665 5840 930 666 5841 932 666 5842 931 666 5843 932 667 5844 934 667 5845 933 667 5846 934 273 5847 936 273 5848 935 273 5849 936 288 5850 938 288 5851 937 288 5852 938 669 5853 940 669 5854 939 669 5855 940 684 5856 942 684 5857 941 684 5858 942 685 5859 944 685 5860 943 685 5861 944 289 5862 946 289 5863 945 289 5864 946 673 5865 948 673 5866 947 673 5867 948 674 5868 950 674 5869 949 674 5870 950 686 5871 952 686 5872 951 686 5873 952 282 5874 954 282 5875 953 282 5876 954 675 5877 956 675 5878 955 675 5879 932 17 5880 930 17 5881 942 17 5882 930 676 5883 928 676 5884 944 676 5885 928 17 5886 958 17 5887 946 17 5888 958 677 5889 956 677 5890 948 677 5891 956 17 5892 954 17 5893 948 17 5894 954 17 5895 952 17 5896 950 17 5897 948 17 5898 954 17 5899 950 17 5900 948 17 5901 946 17 5902 958 17 5903 946 687 5904 944 687 5905 928 687 5906 944 17 5907 942 17 5908 930 17 5909 942 679 5910 940 679 5911 932 679 5912 940 17 5913 938 17 5914 932 17 5915 938 17 5916 936 17 5917 934 17 5918 956 680 5919 958 680 5920 957 680 5921 958 291 5922 928 291 5923 927 291 5924 957 5 5925 927 5 5926 943 5 5927 927 688 5928 929 688 5929 941 688 5930 929 5 5931 931 5 5932 941 5 5933 931 5 5934 933 5 5935 939 5 5936 941 5 5937 931 5 5938 939 5 5939 933 5 5940 935 5 5941 937 5 5942 937 5 5943 939 5 5944 933 5 5945 941 5 5946 943 5 5947 927 5 5948 943 683 5949 945 683 5950 957 683 5951 945 5 5952 947 5 5953 957 5 5954 947 5 5955 949 5 5956 955 5 5957 957 5 5958 947 5 5959 955 5 5960 949 5 5961 951 5 5962 953 5 5963 960 665 5964 962 665 5965 961 665 5966 962 666 5967 964 666 5968 963 666 5969 964 667 5970 966 667 5971 965 667 5972 966 668 5973 968 668 5974 967 668 5975 968 288 5976 970 288 5977 969 288 5978 970 669 5979 972 669 5980 971 669 5981 972 670 5982 974 670 5983 973 670 5984 974 671 5985 976 671 5986 975 671 5987 976 672 5988 978 672 5989 977 672 5990 978 673 5991 980 673 5992 979 673 5993 980 674 5994 982 674 5995 981 674 5996 982 281 5997 984 281 5998 983 281 5999 984 282 6000 986 282 6001 985 282 6002 986 675 6003 988 675 6004 987 675 6005 964 17 6006 962 17 6007 974 17 6008 962 676 6009 960 676 6010 976 676 6011 960 17 6012 990 17 6013 978 17 6014 990 677 6015 988 677 6016 980 677 6017 988 17 6018 986 17 6019 980 17 6020 986 17 6021 984 17 6022 982 17 6023 980 17 6024 986 17 6025 982 17 6026 980 17 6027 978 17 6028 990 17 6029 978 687 6030 976 687 6031 960 687 6032 976 17 6033 974 17 6034 962 17 6035 974 679 6036 972 679 6037 964 679 6038 972 17 6039 970 17 6040 964 17 6041 970 17 6042 968 17 6043 966 17 6044 988 680 6045 990 680 6046 989 680 6047 990 681 6048 960 681 6049 959 681 6050 989 5 6051 959 5 6052 975 5 6053 959 688 6054 961 688 6055 973 688 6056 961 5 6057 963 5 6058 973 5 6059 963 5 6060 965 5 6061 971 5 6062 973 5 6063 963 5 6064 971 5 6065 965 5 6066 967 5 6067 969 5 6068 969 5 6069 971 5 6070 965 5 6071 973 5 6072 975 5 6073 959 5 6074 975 683 6075 977 683 6076 989 683 6077 977 5 6078 979 5 6079 989 5 6080 979 5 6081 981 5 6082 987 5 6083 989 5 6084 979 5 6085 987 5 6086 981 5 6087 983 5 6088 985 5 6089

-
- - - - -

344 126 585 345 126 586 343 126 587 346 127 588 347 127 589 345 127 590 348 128 591 349 128 592 347 128 593 350 129 594 351 129 595 349 129 596 352 130 597 353 130 598 351 130 599 354 131 600 355 131 601 353 131 602 356 132 603 357 132 604 355 132 605 358 133 606 359 133 607 357 133 608 360 134 609 361 134 610 359 134 611 362 135 612 363 135 613 361 135 614 364 136 615 365 136 616 363 136 617 366 137 618 367 137 619 365 137 620 368 138 621 369 138 622 367 138 623 370 139 624 371 139 625 369 139 626 372 140 627 373 140 628 371 140 629 374 141 630 375 141 631 373 141 632 376 142 633 377 142 634 375 142 635 378 143 636 379 143 637 377 143 638 380 144 639 381 144 640 379 144 641 382 145 642 383 145 643 381 145 644 384 146 645 385 146 646 383 146 647 386 147 648 387 147 649 385 147 650 388 148 651 389 148 652 387 148 653 390 149 654 391 149 655 389 149 656 392 150 657 393 150 658 391 150 659 394 151 660 395 151 661 393 151 662 396 152 663 397 152 664 395 152 665 398 153 666 399 153 667 397 153 668 400 154 669 401 154 670 399 154 671 402 155 672 403 155 673 401 155 674 404 156 678 405 156 679 403 156 680 406 157 681 343 157 682 405 157 683 401 5 684 403 5 685 381 5 686 408 158 687 409 158 688 407 158 689 410 159 690 411 159 691 409 159 692 412 160 693 413 160 694 411 160 695 414 161 696 415 161 697 413 161 698 416 162 699 417 162 700 415 162 701 418 163 702 419 163 703 417 163 704 420 164 705 421 164 706 419 164 707 422 165 708 423 165 709 421 165 710 424 166 711 425 166 712 423 166 713 426 167 714 427 167 715 425 167 716 428 168 717 429 168 718 427 168 719 430 169 720 431 169 721 429 169 722 432 170 723 433 170 724 431 170 725 434 171 726 435 171 727 433 171 728 436 172 729 437 172 730 435 172 731 438 173 732 439 173 733 437 173 734 440 174 735 441 174 736 439 174 737 442 175 738 443 175 739 441 175 740 444 176 741 445 176 742 443 176 743 446 177 744 447 177 745 445 177 746 448 178 747 449 178 748 447 178 749 450 179 750 451 179 751 449 179 752 452 180 753 453 180 754 451 180 755 454 181 756 455 181 757 453 181 758 456 182 759 457 182 760 455 182 761 458 183 762 459 183 763 457 183 764 460 184 765 461 184 766 459 184 767 462 185 768 463 185 769 461 185 770 464 186 771 465 186 772 463 186 773 466 187 774 467 187 775 465 187 776 416 17 777 414 17 778 432 17 779 468 188 780 469 188 781 467 188 782 470 189 783 407 189 784 469 189 785 465 190 786 467 190 787 445 190 788 472 126 789 473 126 790 471 126 791 474 127 792 475 127 793 473 127 794 476 128 795 477 128 796 475 128 797 478 129 798 479 129 799 477 129 800 480 130 801 481 130 802 479 130 803 482 131 804 483 131 805 481 131 806 484 132 807 485 132 808 483 132 809 486 133 810 487 133 811 485 133 812 488 191 813 489 191 814 487 191 815 490 135 816 491 135 817 489 135 818 492 136 819 493 136 820 491 136 821 494 192 822 495 192 823 493 192 824 496 193 825 497 193 826 495 193 827 498 194 828 499 194 829 497 194 830 500 195 831 501 195 832 499 195 833 502 141 834 503 141 835 501 141 836 504 142 837 505 142 838 503 142 839 506 196 840 507 196 841 505 196 842 508 144 843 509 144 844 507 144 845 510 197 846 511 197 847 509 197 848 512 146 849 513 146 850 511 146 851 514 198 852 515 198 853 513 198 854 516 148 855 517 148 856 515 148 857 518 149 858 519 149 859 517 149 860 520 150 861 521 150 862 519 150 863 522 151 864 523 151 865 521 151 866 524 152 867 525 152 868 523 152 869 526 199 870 527 199 871 525 199 872 528 154 873 529 154 874 527 154 875 530 200 876 531 200 877 529 200 878 532 156 882 533 156 883 531 156 884 534 201 885 471 201 886 533 201 887 529 5 888 531 5 889 509 5 890 536 158 891 537 158 892 535 158 893 538 159 894 539 159 895 537 159 896 540 160 897 541 160 898 539 160 899 542 161 900 543 161 901 541 161 902 544 202 903 545 202 904 543 202 905 546 163 906 547 163 907 545 163 908 548 203 909 549 203 910 547 203 911 550 204 912 551 204 913 549 204 914 552 205 915 553 205 916 551 205 917 554 167 918 555 167 919 553 167 920 556 206 921 557 206 922 555 206 923 558 207 924 559 207 925 557 207 926 560 208 927 561 208 928 559 208 929 562 171 930 563 171 931 561 171 932 564 172 933 565 172 934 563 172 935 566 209 936 567 209 937 565 209 938 568 174 939 569 174 940 567 174 941 570 210 942 571 210 943 569 210 944 572 211 945 573 211 946 571 211 947 574 177 948 575 177 949 573 177 950 576 212 951 577 212 952 575 212 953 578 179 954 579 179 955 577 179 956 580 213 957 581 213 958 579 213 959 582 181 960 583 181 961 581 181 962 584 214 963 585 214 964 583 214 965 586 183 966 587 183 967 585 183 968 588 215 969 589 215 970 587 215 971 590 185 972 591 185 973 589 185 974 592 216 975 593 216 976 591 216 977 594 187 978 595 187 979 593 187 980 544 17 981 542 17 982 560 17 983 596 217 984 597 217 985 595 217 986 598 189 987 535 189 988 597 189 989 593 218 990 595 218 991 573 218 992 600 219 993 601 219 994 599 219 995 602 220 996 603 220 997 601 220 998 604 128 999 605 128 1000 603 128 1001 606 221 1002 607 221 1003 605 221 1004 608 222 1005 609 222 1006 607 222 1007 610 223 1008 611 223 1009 609 223 1010 612 224 1011 613 224 1012 611 224 1013 614 133 1014 615 133 1015 613 133 1016 616 225 1017 617 225 1018 615 225 1019 618 226 1020 619 226 1021 617 226 1022 620 227 1023 621 227 1024 619 227 1025 622 192 1026 623 192 1027 621 192 1028 624 193 1029 625 193 1030 623 193 1031 626 194 1032 627 194 1033 625 194 1034 628 195 1035 629 195 1036 627 195 1037 630 141 1038 631 141 1039 629 141 1040 632 142 1041 633 142 1042 631 142 1043 634 196 1044 635 196 1045 633 196 1046 636 144 1047 637 144 1048 635 144 1049 638 197 1050 639 197 1051 637 197 1052 640 146 1053 641 146 1054 639 146 1055 642 228 1056 643 228 1057 641 228 1058 644 229 1059 645 229 1060 643 229 1061 646 230 1062 647 230 1063 645 230 1064 648 150 1065 649 150 1066 647 150 1067 650 231 1068 651 231 1069 649 231 1070 652 232 1071 653 232 1072 651 232 1073 654 233 1074 655 233 1075 653 233 1076 656 234 1077 657 234 1078 655 234 1079 658 200 1080 659 200 1081 657 200 1082 660 235 1086 661 235 1087 659 235 1088 662 236 1089 599 236 1090 661 236 1091 657 5 1092 659 5 1093 637 5 1094 664 237 1095 665 237 1096 663 237 1097 666 238 1098 667 238 1099 665 238 1100 668 160 1101 669 160 1102 667 160 1103 670 239 1104 671 239 1105 669 239 1106 672 202 1107 673 202 1108 671 202 1109 674 240 1110 675 240 1111 673 240 1112 676 203 1113 677 203 1114 675 203 1115 678 241 1116 679 241 1117 677 241 1118 680 242 1119 681 242 1120 679 242 1121 682 243 1122 683 243 1123 681 243 1124 684 206 1125 685 206 1126 683 206 1127 686 207 1128 687 207 1129 685 207 1130 688 244 1131 689 244 1132 687 244 1133 690 245 1134 691 245 1135 689 245 1136 692 172 1137 693 172 1138 691 172 1139 694 209 1140 695 209 1141 693 209 1142 696 174 1143 697 174 1144 695 174 1145 698 210 1146 699 210 1147 697 210 1148 700 246 1149 701 246 1150 699 246 1151 702 247 1152 703 247 1153 701 247 1154 704 212 1155 705 212 1156 703 212 1157 706 179 1158 707 179 1159 705 179 1160 708 248 1161 709 248 1162 707 248 1163 710 249 1164 711 249 1165 709 249 1166 712 250 1167 713 250 1168 711 250 1169 714 183 1170 715 183 1171 713 183 1172 716 251 1173 717 251 1174 715 251 1175 718 185 1176 719 185 1177 717 185 1178 720 252 1179 721 252 1180 719 252 1181 722 187 1182 723 187 1183 721 187 1184 672 17 1185 670 17 1186 688 17 1187 724 253 1188 725 253 1189 723 253 1190 726 254 1191 663 254 1192 725 254 1193 721 255 1194 723 255 1195 701 255 1196 728 219 1197 729 219 1198 727 219 1199 730 220 1200 731 220 1201 729 220 1202 732 128 1203 733 128 1204 731 128 1205 734 221 1206 735 221 1207 733 221 1208 736 222 1209 737 222 1210 735 222 1211 738 223 1212 739 223 1213 737 223 1214 740 224 1215 741 224 1216 739 224 1217 742 133 1218 743 133 1219 741 133 1220 744 256 1221 745 256 1222 743 256 1223 746 226 1224 747 226 1225 745 226 1226 748 227 1227 749 227 1228 747 227 1229 750 137 1230 751 137 1231 749 137 1232 752 138 1233 753 138 1234 751 138 1235 754 139 1236 755 139 1237 753 139 1238 756 140 1239 757 140 1240 755 140 1241 758 141 1242 759 141 1243 757 141 1244 760 142 1245 761 142 1246 759 142 1247 762 143 1248 763 143 1249 761 143 1250 764 144 1251 765 144 1252 763 144 1253 766 145 1254 767 145 1255 765 145 1256 768 146 1257 769 146 1258 767 146 1259 770 257 1260 771 257 1261 769 257 1262 772 229 1263 773 229 1264 771 229 1265 774 230 1266 775 230 1267 773 230 1268 776 150 1269 777 150 1270 775 150 1271 778 231 1272 779 231 1273 777 231 1274 780 232 1275 781 232 1276 779 232 1277 782 258 1278 783 258 1279 781 258 1280 784 234 1281 785 234 1282 783 234 1283 786 155 1284 787 155 1285 785 155 1286 788 235 1290 789 235 1291 787 235 1292 790 259 1293 727 259 1294 789 259 1295 785 5 1296 787 5 1297 765 5 1298 792 237 1299 793 237 1300 791 237 1301 794 238 1302 795 238 1303 793 238 1304 796 160 1305 797 160 1306 795 160 1307 798 239 1308 799 239 1309 797 239 1310 800 162 1311 801 162 1312 799 162 1313 802 240 1314 803 240 1315 801 240 1316 804 164 1317 805 164 1318 803 164 1319 806 260 1320 807 260 1321 805 260 1322 808 261 1323 809 261 1324 807 261 1325 810 243 1326 811 243 1327 809 243 1328 812 168 1329 813 168 1330 811 168 1331 814 169 1332 815 169 1333 813 169 1334 816 262 1335 817 262 1336 815 262 1337 818 245 1338 819 245 1339 817 245 1340 820 172 1341 821 172 1342 819 172 1343 822 173 1344 823 173 1345 821 173 1346 824 174 1347 825 174 1348 823 174 1349 826 175 1350 827 175 1351 825 175 1352 828 263 1353 829 263 1354 827 263 1355 830 247 1356 831 247 1357 829 247 1358 832 178 1359 833 178 1360 831 178 1361 834 179 1362 835 179 1363 833 179 1364 836 264 1365 837 264 1366 835 264 1367 838 249 1368 839 249 1369 837 249 1370 840 265 1371 841 265 1372 839 265 1373 842 183 1374 843 183 1375 841 183 1376 844 266 1377 845 266 1378 843 266 1379 846 185 1380 847 185 1381 845 185 1382 848 267 1383 849 267 1384 847 267 1385 850 187 1386 851 187 1387 849 187 1388 800 17 1389 798 17 1390 816 17 1391 852 268 1392 853 268 1393 851 268 1394 854 254 1395 791 254 1396 853 254 1397 849 269 1398 851 269 1399 829 269 1400 344 490 3408 346 490 3409 345 490 3410 346 491 3411 348 491 3412 347 491 3413 348 492 3414 350 492 3415 349 492 3416 350 493 3417 352 493 3418 351 493 3419 352 494 3420 354 494 3421 353 494 3422 354 495 3423 356 495 3424 355 495 3425 356 496 3426 358 496 3427 357 496 3428 358 497 3429 360 497 3430 359 497 3431 360 498 3432 362 498 3433 361 498 3434 362 499 3435 364 499 3436 363 499 3437 364 500 3438 366 500 3439 365 500 3440 366 501 3441 368 501 3442 367 501 3443 368 502 3444 370 502 3445 369 502 3446 370 503 3447 372 503 3448 371 503 3449 372 504 3450 374 504 3451 373 504 3452 374 505 3453 376 505 3454 375 505 3455 376 506 3456 378 506 3457 377 506 3458 378 507 3459 380 507 3460 379 507 3461 380 508 3462 382 508 3463 381 508 3464 382 509 3465 384 509 3466 383 509 3467 384 510 3468 386 510 3469 385 510 3470 386 257 3471 388 257 3472 387 257 3473 388 511 3474 390 511 3475 389 511 3476 390 512 3477 392 512 3478 391 512 3479 392 513 3480 394 513 3481 393 513 3482 394 514 3483 396 514 3484 395 514 3485 396 232 3486 398 232 3487 397 232 3488 398 515 3489 400 515 3490 399 515 3491 400 516 3492 402 516 3493 401 516 3494 402 517 3495 404 517 3496 403 517 3497 404 522 3585 406 522 3586 405 522 3587 406 523 3588 344 523 3589 343 523 3590 405 524 3591 343 524 3592 375 524 3593 343 5 3594 345 5 3595 373 5 3596 345 525 3597 347 525 3598 373 525 3599 347 5 3600 349 5 3601 371 5 3602 373 5 3603 347 5 3604 371 5 3605 349 526 3606 351 526 3607 367 526 3608 351 5 3609 353 5 3610 365 5 3611 353 5 3612 355 5 3613 365 5 3614 355 527 3615 357 527 3616 363 527 3617 365 5 3618 355 5 3619 363 5 3620 357 5 3621 359 5 3622 361 5 3623 361 5 3624 363 5 3625 357 5 3626 365 5 3627 367 5 3628 351 5 3629 367 5 3630 369 5 3631 349 5 3632 369 5 3633 371 5 3634 349 5 3635 373 528 3636 375 528 3637 343 528 3638 375 5 3639 377 5 3640 405 5 3641 377 529 3642 379 529 3643 405 529 3644 379 5 3645 381 5 3646 403 5 3647 405 5 3648 379 5 3649 403 5 3650 381 530 3651 383 530 3652 399 530 3653 383 5 3654 385 5 3655 397 5 3656 385 5 3657 387 5 3658 397 5 3659 387 531 3660 389 531 3661 395 531 3662 397 5 3663 387 5 3664 395 5 3665 389 5 3666 391 5 3667 393 5 3668 393 5 3669 395 5 3670 389 5 3671 397 5 3672 399 5 3673 383 5 3674 399 5 3675 401 5 3676 381 5 3677 408 532 3678 410 532 3679 409 532 3680 410 533 3681 412 533 3682 411 533 3683 412 534 3684 414 534 3685 413 534 3686 414 161 3687 416 161 3688 415 161 3689 416 535 3690 418 535 3691 417 535 3692 418 163 3693 420 163 3694 419 163 3695 420 536 3696 422 536 3697 421 536 3698 422 165 3699 424 165 3700 423 165 3701 424 166 3702 426 166 3703 425 166 3704 426 537 3705 428 537 3706 427 537 3707 428 168 3708 430 168 3709 429 168 3710 430 538 3711 432 538 3712 431 538 3713 432 170 3714 434 170 3715 433 170 3716 434 539 3717 436 539 3718 435 539 3719 436 540 3720 438 540 3721 437 540 3722 438 209 3723 440 209 3724 439 209 3725 440 541 3726 442 541 3727 441 541 3728 442 542 3729 444 542 3730 443 542 3731 444 543 3732 446 543 3733 445 543 3734 446 544 3735 448 544 3736 447 544 3737 448 545 3738 450 545 3739 449 545 3740 450 179 3741 452 179 3742 451 179 3743 452 546 3744 454 546 3745 453 546 3746 454 181 3747 456 181 3748 455 181 3749 456 182 3750 458 182 3751 457 182 3752 458 547 3753 460 547 3754 459 547 3755 460 184 3756 462 184 3757 461 184 3758 462 548 3759 464 548 3760 463 548 3761 464 549 3762 466 549 3763 465 549 3764 466 550 3765 468 550 3766 467 550 3767 412 17 3768 410 17 3769 438 17 3770 410 17 3771 408 17 3772 440 17 3773 408 17 3774 470 17 3775 442 17 3776 470 551 3777 468 551 3778 444 551 3779 468 17 3780 466 17 3781 444 17 3782 466 17 3783 464 17 3784 446 17 3785 444 17 3786 466 17 3787 446 17 3788 464 17 3789 462 17 3790 448 17 3791 462 17 3792 460 17 3793 450 17 3794 448 17 3795 462 17 3796 450 17 3797 460 17 3798 458 17 3799 452 17 3800 458 17 3801 456 17 3802 454 17 3803 452 552 3804 458 552 3805 454 552 3806 452 17 3807 450 17 3808 460 17 3809 448 17 3810 446 17 3811 464 17 3812 444 17 3813 442 17 3814 470 17 3815 442 17 3816 440 17 3817 408 17 3818 440 17 3819 438 17 3820 410 17 3821 438 553 3822 436 553 3823 412 553 3824 436 17 3825 434 17 3826 412 17 3827 434 17 3828 432 17 3829 414 17 3830 412 17 3831 434 17 3832 414 17 3833 432 554 3834 430 554 3835 416 554 3836 430 17 3837 428 17 3838 418 17 3839 416 555 3840 430 555 3841 418 555 3842 428 556 3843 426 556 3844 422 556 3845 426 17 3846 424 17 3847 422 17 3848 422 17 3849 420 17 3850 428 17 3851 420 17 3852 418 17 3853 428 17 3854 468 557 3855 470 557 3856 469 557 3857 470 558 3858 408 558 3859 407 558 3860 469 5 3861 407 5 3862 439 5 3863 407 5 3864 409 5 3865 437 5 3866 409 559 3867 411 559 3868 437 559 3869 411 5 3870 413 5 3871 435 5 3872 437 5 3873 411 5 3874 435 5 3875 413 5 3876 415 5 3877 431 5 3878 415 5 3879 417 5 3880 429 5 3881 417 560 3882 419 560 3883 429 560 3884 419 5 3885 421 5 3886 427 5 3887 429 561 3888 419 561 3889 427 561 3890 421 5 3891 423 5 3892 425 5 3893 425 5 3894 427 5 3895 421 5 3896 429 5 3897 431 5 3898 415 5 3899 431 562 3900 433 562 3901 413 562 3902 433 563 3903 435 563 3904 413 563 3905 437 5 3906 439 5 3907 407 5 3908 439 5 3909 441 5 3910 469 5 3911 441 564 3912 443 564 3913 469 564 3914 443 5 3915 445 5 3916 467 5 3917 469 5 3918 443 5 3919 467 5 3920 445 5 3921 447 5 3922 463 5 3923 447 5 3924 449 5 3925 461 5 3926 449 565 3927 451 565 3928 461 565 3929 451 5 3930 453 5 3931 459 5 3932 461 566 3933 451 566 3934 459 566 3935 453 5 3936 455 5 3937 457 5 3938 457 5 3939 459 5 3940 453 5 3941 461 5 3942 463 5 3943 447 5 3944 463 567 3945 465 567 3946 445 567 3947 472 490 3948 474 490 3949 473 490 3950 474 568 3951 476 568 3952 475 568 3953 476 569 3954 478 569 3955 477 569 3956 478 570 3957 480 570 3958 479 570 3959 480 571 3960 482 571 3961 481 571 3962 482 495 3963 484 495 3964 483 495 3965 484 496 3966 486 496 3967 485 496 3968 486 572 3969 488 572 3970 487 572 3971 488 498 3972 490 498 3973 489 498 3974 490 499 3975 492 499 3976 491 499 3977 492 500 3978 494 500 3979 493 500 3980 494 501 3981 496 501 3982 495 501 3983 496 502 3984 498 502 3985 497 502 3986 498 503 3987 500 503 3988 499 503 3989 500 504 3990 502 504 3991 501 504 3992 502 505 3993 504 505 3994 503 505 3995 504 573 3996 506 573 3997 505 573 3998 506 507 3999 508 507 4000 507 507 4001 508 574 4002 510 574 4003 509 574 4004 510 509 4005 512 509 4006 511 509 4007 512 575 4008 514 575 4009 513 575 4010 514 257 4011 516 257 4012 515 257 4013 516 511 4014 518 511 4015 517 511 4016 518 512 4017 520 512 4018 519 512 4019 520 513 4020 522 513 4021 521 513 4022 522 514 4023 524 514 4024 523 514 4025 524 576 4026 526 576 4027 525 576 4028 526 515 4029 528 515 4030 527 515 4031 528 577 4032 530 577 4033 529 577 4034 530 517 4035 532 517 4036 531 517 4037 532 579 4125 534 579 4126 533 579 4127 534 523 4128 472 523 4129 471 523 4130 533 580 4131 471 580 4132 503 580 4133 471 5 4134 473 5 4135 501 5 4136 473 581 4137 475 581 4138 501 581 4139 475 5 4140 477 5 4141 499 5 4142 501 5 4143 475 5 4144 499 5 4145 477 526 4146 479 526 4147 495 526 4148 479 5 4149 481 5 4150 493 5 4151 481 5 4152 483 5 4153 493 5 4154 483 527 4155 485 527 4156 491 527 4157 493 5 4158 483 5 4159 491 5 4160 485 5 4161 487 5 4162 489 5 4163 489 5 4164 491 5 4165 485 5 4166 493 5 4167 495 5 4168 479 5 4169 495 5 4170 497 5 4171 477 5 4172 497 5 4173 499 5 4174 477 5 4175 501 528 4176 503 528 4177 471 528 4178 503 5 4179 505 5 4180 533 5 4181 505 582 4182 507 582 4183 533 582 4184 507 5 4185 509 5 4186 531 5 4187 533 5 4188 507 5 4189 531 5 4190 509 530 4191 511 530 4192 527 530 4193 511 5 4194 513 5 4195 525 5 4196 513 5 4197 515 5 4198 525 5 4199 515 583 4200 517 583 4201 523 583 4202 525 5 4203 515 5 4204 523 5 4205 517 5 4206 519 5 4207 521 5 4208 521 5 4209 523 5 4210 517 5 4211 525 5 4212 527 5 4213 511 5 4214 527 5 4215 529 5 4216 509 5 4217 536 584 4218 538 584 4219 537 584 4220 538 533 4221 540 533 4222 539 533 4223 540 534 4224 542 534 4225 541 534 4226 542 585 4227 544 585 4228 543 585 4229 544 586 4230 546 586 4231 545 586 4232 546 587 4233 548 587 4234 547 587 4235 548 536 4236 550 536 4237 549 536 4238 550 204 4239 552 204 4240 551 204 4241 552 205 4242 554 205 4243 553 205 4244 554 588 4245 556 588 4246 555 588 4247 556 168 4248 558 168 4249 557 168 4250 558 589 4251 560 589 4252 559 589 4253 560 170 4254 562 170 4255 561 170 4256 562 539 4257 564 539 4258 563 539 4259 564 540 4260 566 540 4261 565 540 4262 566 209 4263 568 209 4264 567 209 4265 568 541 4266 570 541 4267 569 541 4268 570 590 4269 572 590 4270 571 590 4271 572 543 4272 574 543 4273 573 543 4274 574 591 4275 576 591 4276 575 591 4277 576 545 4278 578 545 4279 577 545 4280 578 592 4281 580 592 4282 579 592 4283 580 546 4284 582 546 4285 581 546 4286 582 593 4287 584 593 4288 583 593 4289 584 182 4290 586 182 4291 585 182 4292 586 594 4293 588 594 4294 587 594 4295 588 184 4296 590 184 4297 589 184 4298 590 595 4299 592 595 4300 591 595 4301 592 549 4302 594 549 4303 593 549 4304 594 596 4305 596 596 4306 595 596 4307 540 17 4308 538 17 4309 566 17 4310 538 17 4311 536 17 4312 568 17 4313 536 17 4314 598 17 4315 570 17 4316 598 597 4317 596 597 4318 572 597 4319 596 17 4320 594 17 4321 572 17 4322 594 17 4323 592 17 4324 574 17 4325 572 17 4326 594 17 4327 574 17 4328 592 17 4329 590 17 4330 576 17 4331 590 17 4332 588 17 4333 578 17 4334 576 17 4335 590 17 4336 578 17 4337 588 17 4338 586 17 4339 580 17 4340 586 17 4341 584 17 4342 582 17 4343 580 552 4344 586 552 4345 582 552 4346 580 17 4347 578 17 4348 588 17 4349 576 17 4350 574 17 4351 592 17 4352 572 17 4353 570 17 4354 598 17 4355 570 17 4356 568 17 4357 536 17 4358 568 17 4359 566 17 4360 538 17 4361 566 553 4362 564 553 4363 540 553 4364 564 17 4365 562 17 4366 540 17 4367 562 17 4368 560 17 4369 542 17 4370 540 17 4371 562 17 4372 542 17 4373 560 598 4374 558 598 4375 544 598 4376 558 17 4377 556 17 4378 546 17 4379 544 599 4380 558 599 4381 546 599 4382 556 556 4383 554 556 4384 550 556 4385 554 17 4386 552 17 4387 550 17 4388 550 17 4389 548 17 4390 556 17 4391 548 17 4392 546 17 4393 556 17 4394 596 600 4395 598 600 4396 597 600 4397 598 558 4398 536 558 4399 535 558 4400 597 5 4401 535 5 4402 567 5 4403 535 5 4404 537 5 4405 565 5 4406 537 559 4407 539 559 4408 565 559 4409 539 5 4410 541 5 4411 563 5 4412 565 5 4413 539 5 4414 563 5 4415 541 5 4416 543 5 4417 559 5 4418 543 5 4419 545 5 4420 557 5 4421 545 560 4422 547 560 4423 557 560 4424 547 5 4425 549 5 4426 555 5 4427 557 561 4428 547 561 4429 555 561 4430 549 5 4431 551 5 4432 553 5 4433 553 5 4434 555 5 4435 549 5 4436 557 5 4437 559 5 4438 543 5 4439 559 562 4440 561 562 4441 541 562 4442 561 563 4443 563 563 4444 541 563 4445 565 5 4446 567 5 4447 535 5 4448 567 5 4449 569 5 4450 597 5 4451 569 601 4452 571 601 4453 597 601 4454 571 5 4455 573 5 4456 595 5 4457 597 5 4458 571 5 4459 595 5 4460 573 5 4461 575 5 4462 591 5 4463 575 5 4464 577 5 4465 589 5 4466 577 565 4467 579 565 4468 589 565 4469 579 5 4470 581 5 4471 587 5 4472 589 566 4473 579 566 4474 587 566 4475 581 5 4476 583 5 4477 585 5 4478 585 5 4479 587 5 4480 581 5 4481 589 5 4482 591 5 4483 575 5 4484 591 602 4485 593 602 4486 573 602 4487 600 219 4488 602 219 4489 601 219 4490 602 603 4491 604 603 4492 603 603 4493 604 569 4494 606 569 4495 605 569 4496 606 604 4497 608 604 4498 607 604 4499 608 605 4500 610 605 4501 609 605 4502 610 606 4503 612 606 4504 611 606 4505 612 607 4506 614 607 4507 613 607 4508 614 572 4509 616 572 4510 615 572 4511 616 608 4512 618 608 4513 617 608 4514 618 609 4515 620 609 4516 619 609 4517 620 610 4518 622 610 4519 621 610 4520 622 501 4521 624 501 4522 623 501 4523 624 502 4524 626 502 4525 625 502 4526 626 503 4527 628 503 4528 627 503 4529 628 504 4530 630 504 4531 629 504 4532 630 505 4533 632 505 4534 631 505 4535 632 573 4536 634 573 4537 633 573 4538 634 507 4539 636 507 4540 635 507 4541 636 574 4542 638 574 4543 637 574 4544 638 509 4545 640 509 4546 639 509 4547 640 575 4548 642 575 4549 641 575 4550 642 611 4551 644 611 4552 643 611 4553 644 612 4554 646 612 4555 645 612 4556 646 613 4557 648 613 4558 647 613 4559 648 513 4560 650 513 4561 649 513 4562 650 614 4563 652 614 4564 651 614 4565 652 615 4566 654 615 4567 653 615 4568 654 616 4569 656 616 4570 655 616 4571 656 234 4572 658 234 4573 657 234 4574 658 517 4575 660 517 4576 659 517 4577 660 619 4665 662 619 4666 661 619 4667 662 620 4668 600 620 4669 599 620 4670 661 5 4671 599 5 4672 631 5 4673 599 5 4674 601 5 4675 629 5 4676 601 5 4677 603 5 4678 629 5 4679 603 5 4680 605 5 4681 627 5 4682 629 5 4683 603 5 4684 627 5 4685 605 621 4686 607 621 4687 623 621 4688 607 622 4689 609 622 4690 621 622 4691 609 5 4692 611 5 4693 621 5 4694 611 5 4695 613 5 4696 619 5 4697 621 623 4698 611 623 4699 619 623 4700 613 5 4701 615 5 4702 617 5 4703 617 5 4704 619 5 4705 613 5 4706 621 5 4707 623 5 4708 607 5 4709 623 5 4710 625 5 4711 605 5 4712 625 5 4713 627 5 4714 605 5 4715 629 528 4716 631 528 4717 599 528 4718 631 624 4719 633 624 4720 661 624 4721 633 5 4722 635 5 4723 661 5 4724 635 5 4725 637 5 4726 659 5 4727 661 5 4728 635 5 4729 659 5 4730 637 5 4731 639 5 4732 655 5 4733 639 625 4734 641 625 4735 653 625 4736 641 5 4737 643 5 4738 653 5 4739 643 5 4740 645 5 4741 651 5 4742 653 626 4743 643 626 4744 651 626 4745 645 5 4746 647 5 4747 649 5 4748 649 5 4749 651 5 4750 645 5 4751 653 5 4752 655 5 4753 639 5 4754 655 627 4755 657 627 4756 637 627 4757 664 237 4758 666 237 4759 665 237 4760 666 628 4761 668 628 4762 667 628 4763 668 534 4764 670 534 4765 669 534 4766 670 629 4767 672 629 4768 671 629 4769 672 586 4770 674 586 4771 673 586 4772 674 630 4773 676 630 4774 675 630 4775 676 536 4776 678 536 4777 677 536 4778 678 241 4779 680 241 4780 679 241 4781 680 242 4782 682 242 4783 681 242 4784 682 631 4785 684 631 4786 683 631 4787 684 168 4788 686 168 4789 685 168 4790 686 589 4791 688 589 4792 687 589 4793 688 262 4794 690 262 4795 689 262 4796 690 632 4797 692 632 4798 691 632 4799 692 540 4800 694 540 4801 693 540 4802 694 209 4803 696 209 4804 695 209 4805 696 541 4806 698 541 4807 697 541 4808 698 590 4809 700 590 4810 699 590 4811 700 633 4812 702 633 4813 701 633 4814 702 634 4815 704 634 4816 703 634 4817 704 545 4818 706 545 4819 705 545 4820 706 592 4821 708 592 4822 707 592 4823 708 180 4824 710 180 4825 709 180 4826 710 635 4827 712 635 4828 711 635 4829 712 265 4830 714 265 4831 713 265 4832 714 594 4833 716 594 4834 715 594 4835 716 266 4836 718 266 4837 717 266 4838 718 595 4839 720 595 4840 719 595 4841 720 636 4842 722 636 4843 721 636 4844 722 596 4845 724 596 4846 723 596 4847 668 17 4848 666 17 4849 694 17 4850 666 17 4851 664 17 4852 696 17 4853 664 17 4854 726 17 4855 698 17 4856 726 637 4857 724 637 4858 700 637 4859 724 17 4860 722 17 4861 700 17 4862 722 17 4863 720 17 4864 702 17 4865 700 17 4866 722 17 4867 702 17 4868 720 554 4869 718 554 4870 704 554 4871 718 17 4872 716 17 4873 706 17 4874 704 638 4875 718 638 4876 706 638 4877 716 17 4878 714 17 4879 708 17 4880 714 17 4881 712 17 4882 710 17 4883 708 639 4884 714 639 4885 710 639 4886 708 17 4887 706 17 4888 716 17 4889 704 17 4890 702 17 4891 720 17 4892 700 17 4893 698 17 4894 726 17 4895 698 17 4896 696 17 4897 664 17 4898 696 17 4899 694 17 4900 666 17 4901 694 553 4902 692 553 4903 668 553 4904 692 640 4905 690 640 4906 668 640 4907 690 17 4908 688 17 4909 670 17 4910 668 641 4911 690 641 4912 670 641 4913 688 17 4914 686 17 4915 672 17 4916 686 642 4917 684 642 4918 674 642 4919 672 17 4920 686 17 4921 674 17 4922 684 643 4923 682 643 4924 678 643 4925 682 17 4926 680 17 4927 678 17 4928 678 17 4929 676 17 4930 684 17 4931 676 17 4932 674 17 4933 684 17 4934 724 644 4935 726 644 4936 725 644 4937 726 645 4938 664 645 4939 663 645 4940 725 5 4941 663 5 4942 695 5 4943 663 5 4944 665 5 4945 693 5 4946 665 646 4947 667 646 4948 693 646 4949 667 5 4950 669 5 4951 691 5 4952 693 5 4953 667 5 4954 691 5 4955 669 5 4956 671 5 4957 687 5 4958 671 5 4959 673 5 4960 685 5 4961 673 647 4962 675 647 4963 685 647 4964 675 5 4965 677 5 4966 683 5 4967 685 648 4968 675 648 4969 683 648 4970 677 5 4971 679 5 4972 681 5 4973 681 5 4974 683 5 4975 677 5 4976 685 5 4977 687 5 4978 671 5 4979 687 649 4980 689 649 4981 669 649 4982 689 563 4983 691 563 4984 669 563 4985 693 5 4986 695 5 4987 663 5 4988 695 5 4989 697 5 4990 725 5 4991 697 650 4992 699 650 4993 725 650 4994 699 5 4995 701 5 4996 723 5 4997 725 5 4998 699 5 4999 723 5 5000 701 5 5001 703 5 5002 719 5 5003 703 5 5004 705 5 5005 717 5 5006 705 651 5007 707 651 5008 717 651 5009 707 5 5010 709 5 5011 715 5 5012 717 652 5013 707 652 5014 715 652 5015 709 5 5016 711 5 5017 713 5 5018 713 5 5019 715 5 5020 709 5 5021 717 5 5022 719 5 5023 703 5 5024 719 602 5025 721 602 5026 701 602 5027 728 219 5028 730 219 5029 729 219 5030 730 653 5031 732 653 5032 731 653 5033 732 492 5034 734 492 5035 733 492 5036 734 221 5037 736 221 5038 735 221 5039 736 654 5040 738 654 5041 737 654 5042 738 606 5043 740 606 5044 739 606 5045 740 607 5046 742 607 5047 741 607 5048 742 497 5049 744 497 5050 743 497 5051 744 608 5052 746 608 5053 745 608 5054 746 609 5055 748 609 5056 747 609 5057 748 610 5058 750 610 5059 749 610 5060 750 501 5061 752 501 5062 751 501 5063 752 502 5064 754 502 5065 753 502 5066 754 503 5067 756 503 5068 755 503 5069 756 504 5070 758 504 5071 757 504 5072 758 505 5073 760 505 5074 759 505 5075 760 506 5076 762 506 5077 761 506 5078 762 507 5079 764 507 5080 763 507 5081 764 508 5082 766 508 5083 765 508 5084 766 509 5085 768 509 5086 767 509 5087 768 510 5088 770 510 5089 769 510 5090 770 611 5091 772 611 5092 771 611 5093 772 612 5094 774 612 5095 773 612 5096 774 613 5097 776 613 5098 775 613 5099 776 513 5100 778 513 5101 777 513 5102 778 614 5103 780 614 5104 779 614 5105 780 655 5106 782 655 5107 781 655 5108 782 616 5109 784 616 5110 783 616 5111 784 656 5112 786 656 5113 785 656 5114 786 517 5115 788 517 5116 787 517 5117 788 657 5205 790 657 5206 789 657 5207 790 620 5208 728 620 5209 727 620 5210 789 5 5211 727 5 5212 759 5 5213 727 5 5214 729 5 5215 757 5 5216 729 5 5217 731 5 5218 757 5 5219 731 5 5220 733 5 5221 755 5 5222 757 5 5223 731 5 5224 755 5 5225 733 621 5226 735 621 5227 751 621 5228 735 658 5229 737 658 5230 749 658 5231 737 5 5232 739 5 5233 749 5 5234 739 5 5235 741 5 5236 747 5 5237 749 623 5238 739 623 5239 747 623 5240 741 5 5241 743 5 5242 745 5 5243 745 5 5244 747 5 5245 741 5 5246 749 5 5247 751 5 5248 735 5 5249 751 5 5250 753 5 5251 733 5 5252 753 5 5253 755 5 5254 733 5 5255 757 528 5256 759 528 5257 727 528 5258 759 659 5259 761 659 5260 789 659 5261 761 5 5262 763 5 5263 789 5 5264 763 5 5265 765 5 5266 787 5 5267 789 5 5268 763 5 5269 787 5 5270 765 5 5271 767 5 5272 783 5 5273 767 625 5274 769 625 5275 781 625 5276 769 5 5277 771 5 5278 781 5 5279 771 5 5280 773 5 5281 779 5 5282 781 660 5283 771 660 5284 779 660 5285 773 5 5286 775 5 5287 777 5 5288 777 5 5289 779 5 5290 773 5 5291 781 5 5292 783 5 5293 767 5 5294 783 627 5295 785 627 5296 765 627 5297 792 661 5298 794 661 5299 793 661 5300 794 628 5301 796 628 5302 795 628 5303 796 534 5304 798 534 5305 797 534 5306 798 239 5307 800 239 5308 799 239 5309 800 535 5310 802 535 5311 801 535 5312 802 240 5313 804 240 5314 803 240 5315 804 536 5316 806 536 5317 805 536 5318 806 260 5319 808 260 5320 807 260 5321 808 261 5322 810 261 5323 809 261 5324 810 167 5325 812 167 5326 811 167 5327 812 168 5328 814 168 5329 813 168 5330 814 538 5331 816 538 5332 815 538 5333 816 262 5334 818 262 5335 817 262 5336 818 632 5337 820 632 5338 819 632 5339 820 540 5340 822 540 5341 821 540 5342 822 209 5343 824 209 5344 823 209 5345 824 541 5346 826 541 5347 825 541 5348 826 542 5349 828 542 5350 827 542 5351 828 633 5352 830 633 5353 829 633 5354 830 662 5355 832 662 5356 831 662 5357 832 545 5358 834 545 5359 833 545 5360 834 179 5361 836 179 5362 835 179 5363 836 180 5364 838 180 5365 837 180 5366 838 249 5367 840 249 5368 839 249 5369 840 265 5370 842 265 5371 841 265 5372 842 547 5373 844 547 5374 843 547 5375 844 266 5376 846 266 5377 845 266 5378 846 548 5379 848 548 5380 847 548 5381 848 636 5382 850 636 5383 849 636 5384 850 550 5385 852 550 5386 851 550 5387 796 17 5388 794 17 5389 822 17 5390 794 17 5391 792 17 5392 824 17 5393 792 17 5394 854 17 5395 826 17 5396 854 663 5397 852 663 5398 828 663 5399 852 17 5400 850 17 5401 828 17 5402 850 17 5403 848 17 5404 830 17 5405 828 17 5406 850 17 5407 830 17 5408 848 554 5409 846 554 5410 832 554 5411 846 17 5412 844 17 5413 834 17 5414 832 638 5415 846 638 5416 834 638 5417 844 17 5418 842 17 5419 836 17 5420 842 17 5421 840 17 5422 838 17 5423 836 639 5424 842 639 5425 838 639 5426 836 17 5427 834 17 5428 844 17 5429 832 17 5430 830 17 5431 848 17 5432 828 17 5433 826 17 5434 854 17 5435 826 17 5436 824 17 5437 792 17 5438 824 17 5439 822 17 5440 794 17 5441 822 553 5442 820 553 5443 796 553 5444 820 640 5445 818 640 5446 796 640 5447 818 17 5448 816 17 5449 798 17 5450 796 641 5451 818 641 5452 798 641 5453 816 17 5454 814 17 5455 800 17 5456 814 642 5457 812 642 5458 802 642 5459 800 17 5460 814 17 5461 802 17 5462 812 643 5463 810 643 5464 806 643 5465 810 17 5466 808 17 5467 806 17 5468 806 17 5469 804 17 5470 812 17 5471 804 17 5472 802 17 5473 812 17 5474 852 664 5475 854 664 5476 853 664 5477 854 645 5478 792 645 5479 791 645 5480 853 5 5481 791 5 5482 823 5 5483 791 5 5484 793 5 5485 821 5 5486 793 646 5487 795 646 5488 821 646 5489 795 5 5490 797 5 5491 819 5 5492 821 5 5493 795 5 5494 819 5 5495 797 5 5496 799 5 5497 815 5 5498 799 5 5499 801 5 5500 813 5 5501 801 647 5502 803 647 5503 813 647 5504 803 5 5505 805 5 5506 811 5 5507 813 648 5508 803 648 5509 811 648 5510 805 5 5511 807 5 5512 809 5 5513 809 5 5514 811 5 5515 805 5 5516 813 5 5517 815 5 5518 799 5 5519 815 649 5520 817 649 5521 797 649 5522 817 563 5523 819 563 5524 797 563 5525 821 5 5526 823 5 5527 791 5 5528 823 5 5529 825 5 5530 853 5 5531 825 564 5532 827 564 5533 853 564 5534 827 5 5535 829 5 5536 851 5 5537 853 5 5538 827 5 5539 851 5 5540 829 5 5541 831 5 5542 847 5 5543 831 5 5544 833 5 5545 845 5 5546 833 651 5547 835 651 5548 845 651 5549 835 5 5550 837 5 5551 843 5 5552 845 652 5553 835 652 5554 843 652 5555 837 5 5556 839 5 5557 841 5 5558 841 5 5559 843 5 5560 837 5 5561 845 5 5562 847 5 5563 831 5 5564 847 567 5565 849 567 5566 829 567 5567

-
- - - - -

1 0 0 2 0 1 0 0 2 3 1 3 6 1 4 2 1 5 7 2 6 4 2 7 6 2 8 5 3 9 0 3 10 4 3 11 9 4 12 14 4 13 10 4 14 37 5 15 162 5 16 159 5 17 29 6 18 22 6 19 31 6 20 6 7 21 77 7 22 78 7 23 85 8 24 66 8 25 67 8 26 69 9 27 86 9 28 87 9 29 55 6 30 44 6 31 56 6 32 113 10 33 99 10 34 104 10 35 119 11 36 101 11 37 106 11 38 149 12 39 138 12 40 150 12 41 152 13 42 139 13 43 140 13 44 157 9 45 167 9 46 163 9 47 172 5 48 171 5 49 170 5 50 180 14 51 193 14 52 186 14 53 182 15 54 198 15 55 188 15 56 201 16 57 213 16 58 212 16 59 328 17 60 305 17 61 334 17 62 315 17 63 320 17 64 313 17 65 231 18 66 222 18 67 225 18 68 269 19 69 274 19 70 273 19 71 281 20 72 292 20 73 293 20 74 282 17 75 296 17 76 283 17 77 3 17 78 184 17 79 215 17 80 103 21 81 254 21 82 185 21 83 96 22 84 254 22 85 97 22 86 95 23 87 256 23 88 96 23 89 89 24 90 253 24 91 95 24 92 89 2 93 174 2 94 173 2 95 90 25 96 185 25 97 174 25 98 126 26 99 262 26 100 259 26 101 142 22 102 262 22 103 137 22 104 134 27 105 263 27 106 142 27 107 133 28 108 261 28 109 134 28 110 133 2 111 260 2 112 257 2 113 109 29 114 259 29 115 260 29 116 149 30 117 280 30 118 274 30 119 155 22 120 280 22 121 156 22 122 153 31 123 278 31 124 155 31 125 143 32 126 289 32 127 153 32 128 143 2 129 268 2 130 267 2 131 136 33 132 274 33 133 268 33 134 167 34 135 302 34 136 292 34 137 164 22 138 302 22 139 165 22 140 172 35 141 304 35 142 164 35 143 154 28 144 334 28 145 172 28 146 154 2 147 279 2 148 286 2 149 163 36 150 292 36 151 279 36 152 82 37 153 326 37 154 329 37 155 79 22 156 326 22 157 80 22 158 170 38 159 325 38 160 79 38 161 171 39 162 328 39 163 170 39 164 171 2 165 306 2 166 305 2 167 168 40 168 329 40 169 306 40 170 112 37 171 205 37 172 192 37 173 121 22 174 205 22 175 129 22 176 110 35 177 258 35 178 121 35 179 98 41 180 255 41 181 110 41 182 98 2 183 180 2 184 179 2 185 99 42 186 192 42 187 180 42 188 139 43 189 272 43 190 270 43 191 150 44 192 272 44 193 151 44 194 138 35 195 273 35 196 150 35 197 127 45 198 269 45 199 138 45 200 127 2 201 265 2 202 264 2 203 128 46 204 270 46 205 265 46 206 158 47 207 294 47 208 282 47 209 160 48 210 294 48 211 161 48 212 157 49 213 293 49 214 160 49 215 148 32 216 281 32 217 157 32 218 148 50 219 276 50 220 275 50 221 147 36 222 282 36 223 276 36 224 61 51 225 318 51 226 309 51 227 70 22 228 318 22 229 71 22 230 169 52 231 317 52 232 70 52 233 166 53 234 307 53 235 169 53 236 166 54 237 295 54 238 290 54 239 46 46 240 309 46 241 295 46 242 105 55 243 194 55 244 187 55 245 113 56 246 194 56 247 115 56 248 104 57 249 193 57 250 113 57 251 91 58 252 186 58 253 104 58 254 91 59 255 176 59 256 175 59 257 92 60 258 187 60 259 176 60 260 131 61 261 217 61 262 208 61 263 141 44 264 217 44 265 144 44 266 130 62 267 271 62 268 141 62 269 111 63 270 206 63 271 130 63 272 111 64 273 195 64 274 190 64 275 114 65 276 208 65 277 195 65 278 34 66 279 287 66 280 230 66 281 159 44 282 287 44 283 37 44 284 152 67 285 284 67 286 159 67 287 140 68 288 277 68 289 152 68 290 140 69 291 216 69 292 266 69 293 146 70 294 230 70 295 216 70 296 49 21 297 303 21 298 297 21 299 59 22 300 303 22 301 64 22 302 47 71 303 308 71 304 59 71 305 162 72 306 296 72 307 47 72 308 162 50 309 285 50 310 283 50 311 38 25 312 297 25 313 285 25 314 84 73 315 322 73 316 331 73 317 81 22 318 322 22 319 76 22 320 83 74 321 327 74 322 81 74 323 62 75 324 330 75 325 83 75 326 62 2 327 311 2 328 310 2 329 63 60 330 331 60 331 311 60 332 118 76 333 202 76 334 197 76 335 122 77 336 202 77 337 124 77 338 116 78 339 207 78 340 122 78 341 100 79 342 196 79 343 116 79 344 100 80 345 182 80 346 181 80 347 101 81 348 197 81 349 182 81 350 18 82 351 227 82 352 219 82 353 24 83 354 227 83 355 28 83 356 145 84 357 223 84 358 24 84 359 132 85 360 218 85 361 145 85 362 132 86 363 210 86 364 209 86 365 135 87 366 18 87 367 219 87 368 41 88 369 299 88 370 239 88 371 50 22 372 299 22 373 52 22 374 36 89 375 298 89 376 50 89 377 33 90 378 288 90 379 36 90 380 33 91 381 228 91 382 226 91 383 26 92 384 239 92 385 228 92 386 66 93 387 316 93 388 314 93 389 72 22 390 316 22 391 73 22 392 65 31 393 319 31 394 72 31 395 48 94 396 312 94 397 65 94 398 48 2 399 300 2 400 291 2 401 51 95 402 314 95 403 300 95 404 107 21 405 199 21 406 189 21 407 119 22 408 199 22 409 120 22 410 106 96 411 198 96 412 119 96 413 93 24 414 188 24 415 106 24 416 93 2 417 178 2 418 177 2 419 94 25 420 189 25 421 178 25 422 14 97 423 221 97 424 213 97 425 19 98 426 221 98 427 21 98 428 15 99 429 211 99 430 220 99 431 117 72 432 211 72 433 123 72 434 117 2 435 200 2 436 191 2 437 10 100 438 14 100 439 213 100 440 29 30 441 240 30 442 231 30 443 42 44 444 240 44 445 43 44 446 27 101 447 235 101 448 42 101 449 20 102 450 229 102 451 27 102 452 20 103 453 225 103 454 224 103 455 23 25 456 231 25 457 225 25 458 55 34 459 249 34 460 244 34 461 60 104 462 249 104 463 68 104 464 53 105 465 313 105 466 60 105 467 39 106 468 301 106 469 53 106 470 39 50 471 241 50 472 238 50 473 40 36 474 244 36 475 241 36 476 86 37 477 324 37 478 333 37 479 77 107 480 324 107 481 78 107 482 85 35 483 323 35 484 77 35 485 67 53 486 332 53 487 85 53 488 67 108 489 320 108 490 315 108 491 87 40 492 333 40 493 320 40 494 11 109 495 204 109 496 215 109 497 12 110 498 204 110 499 17 110 500 9 111 501 212 111 502 12 111 503 102 112 504 201 112 505 9 112 506 102 2 507 184 2 508 183 2 509 8 113 510 215 113 511 184 113 512 25 114 513 233 114 514 234 114 515 31 115 516 233 115 517 35 115 518 22 111 519 232 111 520 31 111 521 13 102 522 222 102 523 22 102 524 13 116 525 203 116 526 214 116 527 16 117 528 234 117 529 203 117 530 45 114 531 246 114 532 252 114 533 56 22 534 246 22 535 58 22 536 44 118 537 247 118 538 56 118 539 30 119 540 242 119 541 44 119 542 30 120 543 237 120 544 236 120 545 32 40 546 252 40 547 237 40 548 88 21 549 250 21 550 251 21 551 74 22 552 250 22 553 75 22 554 69 121 555 321 121 556 74 121 557 54 122 558 248 122 559 69 122 560 54 2 561 245 2 562 243 2 563 57 123 564 251 123 565 245 123 566 889 2 1455 888 2 1456 887 2 1457 893 125 1458 890 125 1459 889 125 1460 891 22 1461 894 22 1462 893 22 1463 887 124 1464 892 124 1465 891 124 1466 887 17 1467 893 17 1468 889 17 1469 892 5 1470 890 5 1471 894 5 1472 1 0 1635 3 0 1636 2 0 1637 3 1 1638 7 1 1639 6 1 1640 7 2 1641 5 2 1642 4 2 1643 5 3 1644 1 3 1645 0 3 1646 9 292 1647 12 292 1648 14 292 1649 18 293 1650 20 293 1651 27 293 1652 27 5 1653 26 5 1654 28 5 1655 26 5 1656 33 5 1657 28 5 1658 28 294 1659 18 294 1660 27 294 1661 24 5 1662 28 5 1663 33 5 1664 145 295 1665 24 295 1666 34 295 1667 24 5 1668 33 5 1669 34 5 1670 15 5 1671 135 5 1672 125 5 1673 124 5 1674 123 5 1675 125 5 1676 123 5 1677 15 5 1678 125 5 1679 131 5 1680 122 5 1681 132 5 1682 122 5 1683 124 5 1684 132 5 1685 139 5 1686 141 5 1687 140 5 1688 141 5 1689 144 5 1690 140 5 1691 124 5 1692 125 5 1693 132 5 1694 146 5 1695 140 5 1696 144 5 1697 131 5 1698 132 5 1699 144 5 1700 132 296 1701 145 296 1702 144 296 1703 146 5 1704 144 5 1705 145 5 1706 52 297 1707 41 297 1708 53 297 1709 41 298 1710 39 298 1711 53 298 1712 53 5 1713 51 5 1714 52 5 1715 48 299 1716 65 299 1717 64 299 1718 65 300 1719 63 300 1720 64 300 1721 50 5 1722 52 5 1723 48 5 1724 52 5 1725 51 5 1726 48 5 1727 36 301 1728 50 301 1729 49 301 1730 50 5 1731 48 5 1732 49 5 1733 63 302 1734 62 302 1735 59 302 1736 62 5 1737 61 5 1738 59 5 1739 61 5 1740 46 5 1741 59 5 1742 46 303 1743 47 303 1744 59 303 1745 146 5 1746 145 5 1747 34 5 1748 34 5 1749 33 5 1750 37 5 1751 33 296 1752 36 296 1753 37 296 1754 63 5 1755 59 5 1756 64 5 1757 37 5 1758 36 5 1759 38 5 1760 38 304 1761 36 304 1762 49 304 1763 147 305 1764 152 305 1765 159 305 1766 48 5 1767 64 5 1768 49 5 1769 158 5 1770 147 5 1771 159 5 1772 38 5 1773 162 5 1774 37 5 1775 162 5 1776 158 5 1777 159 5 1778 29 306 1779 23 306 1780 22 306 1781 51 307 1782 53 307 1783 60 307 1784 68 308 1785 55 308 1786 54 308 1787 55 5 1788 56 5 1789 54 5 1790 66 5 1791 51 5 1792 60 5 1793 66 5 1794 60 5 1795 67 5 1796 60 5 1797 68 5 1798 67 5 1799 87 5 1800 67 5 1801 68 5 1802 54 309 1803 69 309 1804 68 309 1805 69 5 1806 87 5 1807 68 5 1808 30 310 1809 44 310 1810 43 310 1811 44 5 1812 40 5 1813 43 5 1814 40 5 1815 39 5 1816 42 5 1817 39 5 1818 41 5 1819 42 5 1820 41 5 1821 26 5 1822 42 5 1823 26 307 1824 27 307 1825 42 307 1826 54 5 1827 56 5 1828 58 5 1829 57 5 1830 54 5 1831 58 5 1832 57 5 1833 58 5 1834 88 5 1835 58 5 1836 45 5 1837 88 5 1838 86 5 1839 74 5 1840 78 5 1841 74 5 1842 75 5 1843 78 5 1844 73 311 1845 85 311 1846 77 311 1847 63 5 1848 65 5 1849 84 5 1850 65 312 1851 72 312 1852 84 312 1853 72 5 1854 73 5 1855 77 5 1856 76 313 1857 84 313 1858 72 313 1859 76 5 1860 72 5 1861 77 5 1862 43 314 1863 29 314 1864 30 314 1865 29 5 1866 31 5 1867 30 5 1868 40 5 1869 42 5 1870 43 5 1871 13 315 1872 22 315 1873 21 315 1874 22 5 1875 23 5 1876 21 5 1877 23 5 1878 20 5 1879 19 5 1880 20 5 1881 18 5 1882 19 5 1883 18 316 1884 135 316 1885 19 316 1886 135 317 1887 15 317 1888 19 317 1889 32 5 1890 30 5 1891 31 5 1892 32 5 1893 31 5 1894 35 5 1895 45 5 1896 32 5 1897 35 5 1898 45 5 1899 35 5 1900 25 5 1901 21 318 1902 14 318 1903 13 318 1904 14 5 1905 12 5 1906 13 5 1907 23 5 1908 19 5 1909 21 5 1910 102 319 1911 9 319 1912 120 319 1913 9 320 1914 10 320 1915 108 320 1916 9 5 1917 108 5 1918 120 5 1919 117 321 1920 123 321 1921 118 321 1922 123 294 1923 124 294 1924 118 294 1925 118 5 1926 119 5 1927 117 5 1928 16 5 1929 13 5 1930 12 5 1931 16 5 1932 12 5 1933 17 5 1934 25 5 1935 16 5 1936 17 5 1937 25 5 1938 17 5 1939 11 5 1940 108 5 1941 117 5 1942 119 5 1943 108 5 1944 119 5 1945 120 5 1946 102 322 1947 120 322 1948 107 322 1949 8 323 1950 102 323 1951 107 323 1952 8 324 1953 107 324 1954 94 324 1955 93 5 1956 106 5 1957 105 5 1958 106 325 1959 101 325 1960 100 325 1961 106 326 1962 100 326 1963 105 326 1964 116 327 1965 122 327 1966 131 327 1967 114 5 1968 111 5 1969 113 5 1970 111 5 1971 112 5 1972 113 5 1973 116 328 1974 131 328 1975 114 328 1976 100 5 1977 116 5 1978 115 5 1979 116 5 1980 114 5 1981 115 5 1982 114 5 1983 113 5 1984 115 5 1985 100 5 1986 115 5 1987 105 5 1988 93 329 1989 105 329 1990 92 329 1991 91 5 1992 104 5 1993 103 5 1994 104 330 1995 99 330 1996 98 330 1997 104 331 1998 98 331 1999 103 331 2000 110 332 2001 121 332 2002 126 332 2003 126 333 2004 109 333 2005 110 333 2006 109 5 2007 97 5 2008 110 5 2009 98 334 2010 110 334 2011 97 334 2012 98 335 2013 97 335 2014 103 335 2015 90 5 2016 89 5 2017 0 5 2018 91 336 2019 103 336 2020 90 336 2021 92 5 2022 91 5 2023 0 5 2024 91 337 2025 90 337 2026 0 337 2027 0 5 2028 2 5 2029 92 5 2030 6 338 2031 4 338 2032 76 338 2033 4 5 2034 79 5 2035 80 5 2036 4 339 2037 80 339 2038 81 339 2039 76 340 2040 4 340 2041 81 340 2042 93 5 2043 92 5 2044 2 5 2045 82 341 2046 168 341 2047 169 341 2048 82 6 2049 169 6 2050 70 6 2051 94 5 2052 93 5 2053 2 5 2054 8 5 2055 94 5 2056 2 5 2057 80 342 2058 82 342 2059 70 342 2060 71 343 2061 61 343 2062 83 343 2063 61 298 2064 62 298 2065 83 298 2066 80 344 2067 70 344 2068 81 344 2069 70 5 2070 71 5 2071 81 5 2072 11 5 2073 8 5 2074 2 5 2075 25 5 2076 11 5 2077 2 5 2078 71 345 2079 83 345 2080 81 345 2081 25 5 2082 2 5 2083 45 5 2084 2 5 2085 6 5 2086 45 5 2087 88 5 2088 45 5 2089 6 5 2090 75 5 2091 88 5 2092 6 5 2093 6 346 2094 76 346 2095 77 346 2096 78 347 2097 75 347 2098 6 347 2099 85 297 2100 73 297 2101 66 297 2102 69 348 2103 74 348 2104 86 348 2105 55 306 2106 40 306 2107 44 306 2108 113 349 2109 112 349 2110 99 349 2111 119 350 2112 118 350 2113 101 350 2114 149 351 2115 136 351 2116 138 351 2117 152 352 2118 151 352 2119 139 352 2120 157 353 2121 160 353 2122 167 353 2123 130 5 2124 141 5 2125 128 5 2126 141 354 2127 139 354 2128 128 354 2129 112 355 2130 111 355 2131 130 355 2132 126 5 2133 121 5 2134 127 5 2135 121 5 2136 129 5 2137 127 5 2138 129 356 2139 112 356 2140 130 356 2141 130 5 2142 128 5 2143 129 5 2144 128 5 2145 127 5 2146 129 5 2147 127 319 2148 138 319 2149 137 319 2150 138 5 2151 136 5 2152 137 5 2153 97 5 2154 109 5 2155 133 5 2156 96 5 2157 97 5 2158 133 5 2159 96 5 2160 133 5 2161 95 5 2162 133 5 2163 134 5 2164 95 5 2165 0 357 2166 89 357 2167 95 357 2168 0 5 2169 95 5 2170 134 5 2171 170 5 2172 79 5 2173 4 5 2174 169 5 2175 168 5 2176 165 5 2177 168 5 2178 171 5 2179 164 5 2180 170 5 2181 4 5 2182 172 5 2183 4 5 2184 0 5 2185 153 5 2186 172 5 2187 4 5 2188 153 5 2189 156 308 2190 149 308 2191 148 308 2192 149 5 2193 150 5 2194 148 5 2195 150 5 2196 151 5 2197 148 5 2198 151 5 2199 152 5 2200 147 5 2201 148 5 2202 151 5 2203 147 5 2204 148 319 2205 157 319 2206 156 319 2207 157 5 2208 163 5 2209 156 5 2210 165 358 2211 167 358 2212 166 358 2213 167 5 2214 160 5 2215 166 5 2216 161 356 2217 158 356 2218 47 356 2219 158 355 2220 162 355 2221 47 355 2222 155 5 2223 156 5 2224 163 5 2225 155 5 2226 163 5 2227 154 5 2228 153 5 2229 155 5 2230 154 5 2231 153 5 2232 154 5 2233 172 5 2234 47 5 2235 46 5 2236 161 5 2237 46 5 2238 166 5 2239 161 5 2240 137 359 2241 126 359 2242 127 359 2243 160 5 2244 161 5 2245 166 5 2246 137 5 2247 136 5 2248 143 5 2249 142 5 2250 137 5 2251 143 5 2252 142 5 2253 143 5 2254 134 5 2255 143 360 2256 153 360 2257 134 360 2258 134 5 2259 153 5 2260 0 5 2261 165 361 2262 166 361 2263 169 361 2264 164 5 2265 165 5 2266 168 5 2267 172 5 2268 164 5 2269 171 5 2270 180 362 2271 192 362 2272 193 362 2273 182 363 2274 197 363 2275 198 363 2276 201 17 2277 200 17 2278 213 17 2279 206 364 2280 190 364 2281 192 364 2282 205 17 2283 258 17 2284 265 17 2285 258 17 2286 259 17 2287 264 17 2288 265 17 2289 258 17 2290 264 17 2291 206 17 2292 192 17 2293 205 17 2294 270 365 2295 271 365 2296 265 365 2297 271 366 2298 206 366 2299 265 366 2300 206 17 2301 205 17 2302 265 17 2303 268 17 2304 269 17 2305 262 17 2306 269 17 2307 264 17 2308 262 17 2309 264 17 2310 259 17 2311 262 17 2312 273 17 2313 274 17 2314 275 17 2315 274 17 2316 280 17 2317 275 17 2318 277 17 2319 272 17 2320 276 17 2321 272 17 2322 273 17 2323 276 17 2324 282 367 2325 284 367 2326 276 367 2327 284 368 2328 277 368 2329 276 368 2330 268 17 2331 262 17 2332 263 17 2333 267 17 2334 268 17 2335 263 17 2336 261 17 2337 257 17 2338 253 17 2339 257 17 2340 256 17 2341 253 17 2342 267 17 2343 263 17 2344 261 17 2345 289 17 2346 267 17 2347 261 17 2348 253 17 2349 173 17 2350 1 17 2351 5 17 2352 325 17 2353 328 17 2354 305 17 2355 306 17 2356 304 17 2357 306 17 2358 307 17 2359 302 17 2360 304 17 2361 306 17 2362 302 17 2363 1 17 2364 5 17 2365 289 17 2366 5 369 2367 328 369 2368 334 369 2369 261 17 2370 253 17 2371 1 17 2372 289 17 2373 261 17 2374 1 17 2375 290 17 2376 295 17 2377 294 17 2378 295 17 2379 296 17 2380 294 17 2381 294 17 2382 293 17 2383 290 17 2384 293 17 2385 292 17 2386 290 17 2387 292 17 2388 302 17 2389 290 17 2390 279 17 2391 281 17 2392 280 17 2393 281 17 2394 275 17 2395 280 17 2396 275 17 2397 276 17 2398 273 17 2399 286 17 2400 279 17 2401 280 17 2402 286 17 2403 280 17 2404 278 17 2405 334 17 2406 286 17 2407 289 17 2408 286 17 2409 278 17 2410 289 17 2411 334 17 2412 289 17 2413 5 17 2414 307 17 2415 290 17 2416 302 17 2417 305 17 2418 304 17 2419 334 17 2420 202 17 2421 207 17 2422 210 17 2423 207 17 2424 208 17 2425 209 17 2426 210 17 2427 207 17 2428 209 17 2429 217 17 2430 271 17 2431 266 17 2432 271 17 2433 270 17 2434 266 17 2435 191 17 2436 197 17 2437 211 17 2438 197 370 2439 202 370 2440 211 370 2441 210 17 2442 211 17 2443 202 17 2444 270 371 2445 272 371 2446 277 371 2447 270 17 2448 277 17 2449 266 17 2450 217 17 2451 266 17 2452 216 17 2453 208 17 2454 217 17 2455 209 17 2456 217 17 2457 216 17 2458 218 17 2459 209 372 2460 217 372 2461 218 372 2462 218 17 2463 216 17 2464 230 17 2465 223 17 2466 218 17 2467 230 17 2468 287 17 2469 284 17 2470 283 17 2471 284 17 2472 282 17 2473 283 17 2474 223 17 2475 230 17 2476 226 17 2477 230 17 2478 287 17 2479 226 17 2480 224 17 2481 219 17 2482 229 17 2483 219 373 2484 227 373 2485 229 373 2486 287 17 2487 283 17 2488 285 17 2489 226 17 2490 228 17 2491 227 17 2492 228 17 2493 229 17 2494 227 17 2495 287 17 2496 285 17 2497 288 17 2498 226 17 2499 227 17 2500 223 17 2501 288 17 2502 226 17 2503 287 17 2504 308 374 2505 296 374 2506 295 374 2507 295 375 2508 309 375 2509 308 375 2510 309 376 2511 310 376 2512 308 376 2513 310 377 2514 311 377 2515 303 377 2516 311 17 2517 312 17 2518 303 17 2519 303 378 2520 308 378 2521 310 378 2522 314 379 2523 316 379 2524 332 379 2525 314 17 2526 332 17 2527 315 17 2528 300 380 2529 314 380 2530 313 380 2531 314 17 2532 315 17 2533 313 17 2534 320 381 2535 333 381 2536 248 381 2537 333 17 2538 321 17 2539 248 17 2540 297 382 2541 303 382 2542 291 382 2543 303 383 2544 312 383 2545 291 383 2546 301 17 2547 299 17 2548 300 17 2549 299 17 2550 298 17 2551 300 17 2552 298 384 2553 288 384 2554 297 384 2555 288 17 2556 285 17 2557 297 17 2558 297 385 2559 291 385 2560 298 385 2561 242 17 2562 241 17 2563 244 17 2564 243 17 2565 247 17 2566 244 17 2567 247 386 2568 242 386 2569 244 386 2570 243 17 2571 244 17 2572 249 17 2573 320 17 2574 248 17 2575 249 17 2576 248 17 2577 243 17 2578 249 17 2579 298 17 2580 291 17 2581 300 17 2582 320 17 2583 249 17 2584 313 17 2585 313 387 2586 301 387 2587 300 387 2588 231 17 2589 232 17 2590 222 17 2591 269 17 2592 268 17 2593 274 17 2594 281 17 2595 279 17 2596 292 17 2597 282 388 2598 294 388 2599 296 388 2600 238 17 2601 241 17 2602 240 17 2603 241 17 2604 242 17 2605 240 17 2606 299 17 2607 301 17 2608 239 17 2609 301 389 2610 238 389 2611 239 389 2612 229 390 2613 228 390 2614 235 390 2615 228 391 2616 239 391 2617 235 391 2618 246 17 2619 247 17 2620 243 17 2621 246 17 2622 243 17 2623 245 17 2624 252 17 2625 246 17 2626 245 17 2627 252 17 2628 245 17 2629 251 17 2630 250 392 2631 321 392 2632 324 392 2633 321 17 2634 333 17 2635 324 17 2636 323 393 2637 332 393 2638 316 393 2639 319 17 2640 312 17 2641 331 17 2642 312 17 2643 311 17 2644 331 17 2645 323 394 2646 316 394 2647 319 394 2648 319 17 2649 331 17 2650 322 17 2651 323 395 2652 319 395 2653 322 395 2654 239 17 2655 238 17 2656 235 17 2657 232 17 2658 231 17 2659 236 17 2660 231 17 2661 240 17 2662 236 17 2663 240 17 2664 235 17 2665 238 17 2666 330 396 2667 310 396 2668 309 396 2669 330 17 2670 309 17 2671 318 17 2672 327 397 2673 330 397 2674 318 397 2675 317 386 2676 307 386 2677 329 386 2678 307 17 2679 306 17 2680 329 17 2681 327 392 2682 318 392 2683 317 392 2684 326 398 2685 325 398 2686 5 398 2687 317 17 2688 329 17 2689 326 17 2690 327 399 2691 317 399 2692 326 399 2693 326 17 2694 5 17 2695 327 17 2696 5 17 2697 7 17 2698 322 17 2699 327 17 2700 5 17 2701 322 17 2702 3 17 2703 1 17 2704 176 17 2705 1 400 2706 173 400 2707 174 400 2708 1 401 2709 174 401 2710 175 401 2711 176 17 2712 1 17 2713 175 17 2714 254 17 2715 256 17 2716 257 17 2717 260 402 2718 259 402 2719 255 402 2720 259 17 2721 258 17 2722 255 17 2723 254 17 2724 257 17 2725 260 17 2726 185 17 2727 254 17 2728 179 17 2729 254 17 2730 260 17 2731 255 17 2732 179 403 2733 254 403 2734 255 403 2735 179 404 2736 180 404 2737 186 404 2738 179 17 2739 186 17 2740 185 17 2741 186 17 2742 175 17 2743 185 17 2744 323 405 2745 322 405 2746 7 405 2747 324 406 2748 323 406 2749 7 406 2750 174 17 2751 185 17 2752 175 17 2753 250 407 2754 324 407 2755 7 407 2756 251 17 2757 250 17 2758 7 17 2759 251 17 2760 7 17 2761 252 17 2762 7 17 2763 3 17 2764 252 17 2765 194 17 2766 193 17 2767 190 17 2768 193 17 2769 192 17 2770 190 17 2771 190 17 2772 195 17 2773 194 17 2774 195 408 2775 208 408 2776 196 408 2777 208 17 2778 207 17 2779 196 17 2780 187 17 2781 194 17 2782 181 17 2783 194 17 2784 195 17 2785 196 17 2786 181 17 2787 194 17 2788 196 17 2789 181 409 2790 182 409 2791 188 409 2792 181 17 2793 188 17 2794 187 17 2795 188 17 2796 177 17 2797 187 17 2798 225 17 2799 222 17 2800 221 17 2801 222 17 2802 214 17 2803 221 17 2804 219 17 2805 224 17 2806 220 17 2807 224 17 2808 225 17 2809 220 17 2810 211 410 2811 210 410 2812 220 410 2813 210 411 2814 219 411 2815 220 411 2816 240 17 2817 242 17 2818 236 17 2819 233 17 2820 232 17 2821 236 17 2822 233 17 2823 236 17 2824 237 17 2825 234 17 2826 233 17 2827 252 17 2828 233 17 2829 237 17 2830 252 17 2831 176 17 2832 187 17 2833 177 17 2834 234 17 2835 252 17 2836 3 17 2837 3 412 2838 176 412 2839 177 412 2840 3 413 2841 177 413 2842 178 413 2843 212 17 2844 213 17 2845 214 17 2846 213 17 2847 221 17 2848 214 17 2849 221 17 2850 220 17 2851 225 17 2852 200 17 2853 201 17 2854 199 17 2855 201 17 2856 183 17 2857 199 17 2858 197 17 2859 191 17 2860 198 17 2861 191 17 2862 200 17 2863 199 17 2864 199 17 2865 198 17 2866 191 17 2867 3 17 2868 178 17 2869 184 17 2870 178 414 2871 189 414 2872 184 414 2873 204 17 2874 212 17 2875 214 17 2876 204 17 2877 214 17 2878 203 17 2879 215 17 2880 204 17 2881 203 17 2882 189 17 2883 199 17 2884 183 17 2885 215 17 2886 203 17 2887 234 17 2888 189 17 2889 183 17 2890 184 17 2891 215 17 2892 234 17 2893 3 17 2894 103 415 2895 97 415 2896 254 415 2897 96 22 2898 256 22 2899 254 22 2900 95 416 2901 253 416 2902 256 416 2903 89 417 2904 173 417 2905 253 417 2906 89 2 2907 90 2 2908 174 2 2909 90 33 2910 103 33 2911 185 33 2912 126 418 2913 137 418 2914 262 418 2915 142 22 2916 263 22 2917 262 22 2918 134 419 2919 261 419 2920 263 419 2921 133 90 2922 257 90 2923 261 90 2924 133 2 2925 109 2 2926 260 2 2927 109 33 2928 126 33 2929 259 33 2930 149 30 2931 156 30 2932 280 30 2933 155 22 2934 278 22 2935 280 22 2936 153 35 2937 289 35 2938 278 35 2939 143 420 2940 267 420 2941 289 420 2942 143 2 2943 136 2 2944 268 2 2945 136 33 2946 149 33 2947 274 33 2948 167 415 2949 165 415 2950 302 415 2951 164 22 2952 304 22 2953 302 22 2954 172 421 2955 334 421 2956 304 421 2957 154 32 2958 286 32 2959 334 32 2960 154 2 2961 163 2 2962 279 2 2963 163 33 2964 167 33 2965 292 33 2966 82 415 2967 80 415 2968 326 415 2969 79 22 2970 325 22 2971 326 22 2972 170 416 2973 328 416 2974 325 416 2975 171 422 2976 305 422 2977 328 422 2978 171 2 2979 168 2 2980 306 2 2981 168 42 2982 82 42 2983 329 42 2984 112 93 2985 129 93 2986 205 93 2987 121 22 2988 258 22 2989 205 22 2990 110 416 2991 255 416 2992 258 416 2993 98 423 2994 179 423 2995 255 423 2996 98 2 2997 99 2 2998 180 2 2999 99 424 3000 112 424 3001 192 424 3002 139 43 3003 151 43 3004 272 43 3005 150 425 3006 273 425 3007 272 425 3008 138 35 3009 269 35 3010 273 35 3011 127 417 3012 264 417 3013 269 417 3014 127 2 3015 128 2 3016 265 2 3017 128 426 3018 139 426 3019 270 426 3020 158 427 3021 161 427 3022 294 427 3023 160 428 3024 293 428 3025 294 428 3026 157 429 3027 281 429 3028 293 429 3029 148 90 3030 275 90 3031 281 90 3032 148 69 3033 147 69 3034 276 69 3035 147 25 3036 158 25 3037 282 25 3038 61 430 3039 71 430 3040 318 430 3041 70 22 3042 317 22 3043 318 22 3044 169 431 3045 307 431 3046 317 431 3047 166 90 3048 290 90 3049 307 90 3050 166 432 3051 46 432 3052 295 432 3053 46 433 3054 61 433 3055 309 433 3056 105 61 3057 115 61 3058 194 61 3059 113 434 3060 193 434 3061 194 434 3062 104 435 3063 186 435 3064 193 435 3065 91 436 3066 175 436 3067 186 436 3068 91 437 3069 92 437 3070 176 437 3071 92 438 3072 105 438 3073 187 438 3074 131 55 3075 144 55 3076 217 55 3077 141 425 3078 271 425 3079 217 425 3080 130 421 3081 206 421 3082 271 421 3083 111 423 3084 190 423 3085 206 423 3086 111 59 3087 114 59 3088 195 59 3089 114 438 3090 131 438 3091 208 438 3092 34 439 3093 37 439 3094 287 439 3095 159 425 3096 284 425 3097 287 425 3098 152 440 3099 277 440 3100 284 440 3101 140 441 3102 266 441 3103 277 441 3104 140 91 3105 146 91 3106 216 91 3107 146 438 3108 34 438 3109 230 438 3110 49 61 3111 64 61 3112 303 61 3113 59 22 3114 308 22 3115 303 22 3116 47 84 3117 296 84 3118 308 84 3119 162 442 3120 283 442 3121 296 442 3122 162 69 3123 38 69 3124 285 69 3125 38 438 3126 49 438 3127 297 438 3128 84 443 3129 76 443 3130 322 443 3131 81 22 3132 327 22 3133 322 22 3134 83 444 3135 330 444 3136 327 444 3137 62 24 3138 310 24 3139 330 24 3140 62 2 3141 63 2 3142 311 2 3143 63 445 3144 84 445 3145 331 445 3146 118 446 3147 124 446 3148 202 446 3149 122 447 3150 207 447 3151 202 447 3152 116 448 3153 196 448 3154 207 448 3155 100 449 3156 181 449 3157 196 449 3158 100 450 3159 101 450 3160 182 450 3161 101 451 3162 118 451 3163 197 451 3164 18 418 3165 28 418 3166 227 418 3167 24 452 3168 223 452 3169 227 452 3170 145 31 3171 218 31 3172 223 31 3173 132 453 3174 209 453 3175 218 453 3176 132 454 3177 125 454 3178 210 454 3179 219 455 3180 210 455 3181 135 455 3182 210 456 3183 125 456 3184 135 456 3185 41 446 3186 52 446 3187 299 446 3188 50 22 3189 298 22 3190 299 22 3191 36 457 3192 288 457 3193 298 457 3194 33 458 3195 226 458 3196 288 458 3197 33 459 3198 26 459 3199 228 459 3200 26 445 3201 41 445 3202 239 445 3203 66 460 3204 73 460 3205 316 460 3206 72 22 3207 319 22 3208 316 22 3209 65 38 3210 312 38 3211 319 38 3212 48 53 3213 291 53 3214 312 53 3215 48 2 3216 51 2 3217 300 2 3218 51 451 3219 66 451 3220 314 451 3221 107 415 3222 120 415 3223 199 415 3224 119 22 3225 198 22 3226 199 22 3227 106 461 3228 188 461 3229 198 461 3230 93 417 3231 177 417 3232 188 417 3233 93 2 3234 94 2 3235 178 2 3236 94 33 3237 107 33 3238 189 33 3239 14 418 3240 21 418 3241 221 418 3242 19 462 3243 220 462 3244 221 462 3245 220 463 3246 19 463 3247 15 463 3248 15 464 3249 123 464 3250 211 464 3251 117 465 3252 191 465 3253 211 465 3254 117 2 3255 108 2 3256 200 2 3257 213 466 3258 200 466 3259 10 466 3260 200 467 3261 108 467 3262 10 467 3263 29 468 3264 43 468 3265 240 468 3266 42 425 3267 235 425 3268 240 425 3269 27 461 3270 229 461 3271 235 461 3272 20 32 3273 224 32 3274 229 32 3275 20 469 3276 23 469 3277 225 469 3278 23 33 3279 29 33 3280 231 33 3281 55 415 3282 68 415 3283 249 415 3284 60 470 3285 313 470 3286 249 470 3287 53 416 3288 301 416 3289 313 416 3290 39 442 3291 238 442 3292 301 442 3293 39 69 3294 40 69 3295 241 69 3296 40 471 3297 55 471 3298 244 471 3299 86 415 3300 78 415 3301 324 415 3302 77 472 3303 323 472 3304 324 472 3305 85 440 3306 332 440 3307 323 440 3308 67 417 3309 315 417 3310 332 417 3311 67 473 3312 87 473 3313 320 473 3314 87 42 3315 86 42 3316 333 42 3317 11 474 3318 17 474 3319 204 474 3320 12 475 3321 212 475 3322 204 475 3323 9 476 3324 201 476 3325 212 476 3326 102 477 3327 183 477 3328 201 477 3329 102 2 3330 8 2 3331 184 2 3332 8 478 3333 11 478 3334 215 478 3335 25 479 3336 35 479 3337 233 479 3338 31 480 3339 232 480 3340 233 480 3341 22 419 3342 222 419 3343 232 419 3344 13 417 3345 214 417 3346 222 417 3347 13 481 3348 16 481 3349 203 481 3350 16 482 3351 25 482 3352 234 482 3353 45 483 3354 58 483 3355 246 483 3356 56 22 3357 247 22 3358 246 22 3359 44 484 3360 242 484 3361 247 484 3362 30 485 3363 236 485 3364 242 485 3365 30 486 3366 32 486 3367 237 486 3368 32 487 3369 45 487 3370 252 487 3371 88 93 3372 75 93 3373 250 93 3374 74 22 3375 321 22 3376 250 22 3377 69 488 3378 248 488 3379 321 488 3380 54 489 3381 243 489 3382 248 489 3383 54 2 3384 57 2 3385 245 2 3386 57 487 3387 88 487 3388 251 487 3389 889 2 5694 890 2 5695 888 2 5696 893 125 5697 894 125 5698 890 125 5699 891 22 5700 892 22 5701 894 22 5702 887 124 5703 888 124 5704 892 124 5705 887 17 5706 891 17 5707 893 17 5708 892 5 5709 888 5 5710 890 5 5711

-
-
-
-
- - - - 0.364727 0 0 -0.003200948 0 0.3838361 0 0.002424642 0 0 -0.01140138 0.5492982 0 0 0 1 - - - - - - - - - - - - - - - -
\ No newline at end of file diff --git a/src/picknik_ur_mock_hw_config/meshes/table.png b/src/picknik_ur_mock_hw_config/meshes/table.png deleted file mode 100644 index 3610870b..00000000 Binary files a/src/picknik_ur_mock_hw_config/meshes/table.png and /dev/null differ diff --git a/src/picknik_ur_mock_hw_config/objectives/3_waypoint_pick_and_place.xml b/src/picknik_ur_mock_hw_config/objectives/3_waypoint_pick_and_place.xml deleted file mode 100644 index bfb73650..00000000 --- a/src/picknik_ur_mock_hw_config/objectives/3_waypoint_pick_and_place.xml +++ /dev/null @@ -1,114 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_mock_hw_config/objectives/constrained_pick_place.xml b/src/picknik_ur_mock_hw_config/objectives/constrained_pick_place.xml deleted file mode 100644 index 1fdc14b1..00000000 --- a/src/picknik_ur_mock_hw_config/objectives/constrained_pick_place.xml +++ /dev/null @@ -1,50 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_mock_hw_config/objectives/cycle_between_waypoints.xml b/src/picknik_ur_mock_hw_config/objectives/cycle_between_waypoints.xml deleted file mode 100644 index b5bbf2b2..00000000 --- a/src/picknik_ur_mock_hw_config/objectives/cycle_between_waypoints.xml +++ /dev/null @@ -1,27 +0,0 @@ - - - - - - - - - - - diff --git a/src/picknik_ur_mock_hw_config/objectives/joint_diagnostic.xml b/src/picknik_ur_mock_hw_config/objectives/joint_diagnostic.xml deleted file mode 100644 index c785d370..00000000 --- a/src/picknik_ur_mock_hw_config/objectives/joint_diagnostic.xml +++ /dev/null @@ -1,39 +0,0 @@ - - - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_mock_hw_config/objectives/move_along_path.xml b/src/picknik_ur_mock_hw_config/objectives/move_along_path.xml deleted file mode 100644 index 2f6b3592..00000000 --- a/src/picknik_ur_mock_hw_config/objectives/move_along_path.xml +++ /dev/null @@ -1,122 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_mock_hw_config/objectives/my_constraints.yaml b/src/picknik_ur_mock_hw_config/objectives/my_constraints.yaml deleted file mode 100644 index 0183b3b3..00000000 --- a/src/picknik_ur_mock_hw_config/objectives/my_constraints.yaml +++ /dev/null @@ -1,11 +0,0 @@ -AppendOrientationConstraint: - constraint_frame: "world" - link_frame: "grasp_link" - orientation: # radians - x: -3.14 - y: 0.0 - z: -1.57 - tolerance: # radians - x: 0.1 - y: 0.1 - z: 10.0 diff --git a/src/picknik_ur_mock_hw_config/objectives/rrt_connect_test.xml b/src/picknik_ur_mock_hw_config/objectives/rrt_connect_test.xml deleted file mode 100644 index 172c5482..00000000 --- a/src/picknik_ur_mock_hw_config/objectives/rrt_connect_test.xml +++ /dev/null @@ -1,37 +0,0 @@ - - - - - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_mock_hw_config/package.xml b/src/picknik_ur_mock_hw_config/package.xml deleted file mode 100644 index 32c8dd9f..00000000 --- a/src/picknik_ur_mock_hw_config/package.xml +++ /dev/null @@ -1,21 +0,0 @@ - - - picknik_ur_mock_hw_config - 6.0.0 - - - Configuration package for a UR arm that can be simulated with mock hardware - - - MoveIt Pro Maintainer - - BSD-3-Clause - - ament_cmake - - picknik_ur_base_config - - - ament_cmake - - diff --git a/src/picknik_ur_mock_hw_config/waypoints/machine_tending_waypoints.yaml b/src/picknik_ur_mock_hw_config/waypoints/machine_tending_waypoints.yaml deleted file mode 100644 index ca062118..00000000 --- a/src/picknik_ur_mock_hw_config/waypoints/machine_tending_waypoints.yaml +++ /dev/null @@ -1,297 +0,0 @@ -- description: '' - favorite: true - joint_group_names: - - manipulator - joint_state: - effort: [] - header: - frame_id: world - stamp: - nanosec: 0 - sec: 0 - name: - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - position: - - -1.483921129263475 - - -2.46201364140547 - - -1.4155434352593872 - - -0.8311314387025445 - - 1.5924748792504824 - - 0.1385336124548016 - velocity: [] - name: Grasp Right -- description: '' - favorite: false - joint_group_names: - - manipulator - joint_state: - effort: [] - header: - frame_id: world - stamp: - nanosec: 0 - sec: 0 - name: - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - position: - - 0.06985069152408796 - - -1.4672882628347366 - - -1.7175797731890454 - - -1.5205531132576242 - - 1.5615168254863208 - - -1.3999864602892913 - velocity: [] - name: Gripper Down -- description: '' - favorite: true - joint_group_names: - - manipulator - joint_state: - effort: [] - header: - frame_id: world - stamp: - nanosec: 0 - sec: 0 - name: - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - position: - - 0 - - -1.41 - - -0.7 - - -2.12 - - 1.67 - - 0 - velocity: [] - name: Forward Down -- description: '' - favorite: true - joint_group_names: - - manipulator - joint_state: - effort: [] - header: - frame_id: world - stamp: - nanosec: 0 - sec: 0 - name: - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - position: - - 1.8388098170804708 - - -2.443292149016804 - - -1.4333817078874915 - - -0.8454175837578257 - - 1.5642496598380444 - - 0.37040650512506323 - velocity: [] - name: Grasp Left -- description: '' - favorite: false - joint_group_names: - - manipulator - joint_state: - effort: [] - header: - frame_id: world - stamp: - nanosec: 0 - sec: 0 - name: - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - position: - - -2.2335834056138996e-05 - - -0.7800858658974525 - - -0.5100288585397881 - - -2.399985082258936 - - -3.141592653589793 - - 2.282092208042741e-05 - velocity: [] - name: Wrist 2 Min -- description: '' - favorite: true - joint_group_names: - - manipulator - joint_state: - effort: [] - header: - frame_id: world - stamp: - nanosec: 0 - sec: 0 - name: - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - position: - - -1.5707963267948966 - - -2.0943951023931953 - - -0.7 - - -1.71359599286716 - - 1.5707963267948966 - - 0 - velocity: [] - name: Look at Right Table -- description: '' - favorite: true - joint_group_names: - - manipulator - joint_state: - effort: [] - header: - frame_id: world - stamp: - nanosec: 0 - sec: 0 - name: - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - position: - - 0 - - -0.78 - - -0.51 - - -2.4 - - 1.65 - - 0 - velocity: [] - name: Home -- description: '' - favorite: true - joint_group_names: - - manipulator - joint_state: - effort: [] - header: - frame_id: world - stamp: - nanosec: 0 - sec: 0 - name: - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - position: - - 1.6966397903773711 - - -2.0432638182120124 - - -0.845901355537658 - - -1.6204157592324464 - - 1.5452251290161947 - - 0.12328727782236398 - velocity: [] - name: Look at Left Table -- description: '' - favorite: true - joint_group_names: - - manipulator - joint_state: - effort: [] - header: - frame_id: world - stamp: - nanosec: 0 - sec: 0 - name: - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - position: - - 0.5509848570442806 - - -0.9919020912742678 - - -1.5210004994776822 - - -1.1362474187224354 - - 1.1424099505908154 - - 0.2545176268195681 - velocity: [] - name: Look at Machine -- description: '' - favorite: false - joint_group_names: - - manipulator - joint_state: - effort: [] - header: - frame_id: world - stamp: - nanosec: 0 - sec: 0 - name: - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - position: - - -2.2335834056138996e-05 - - -0.7800858658974525 - - -0.5100288585397881 - - -2.399985082258936 - - 3.141592653589793 - - 2.282092208042741e-05 - velocity: [] - name: Wrist 2 Max -- description: '' - favorite: true - joint_group_names: - - manipulator - joint_state: - effort: [] - header: - frame_id: world - stamp: - nanosec: 0 - sec: 0 - name: - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - position: - - 0.11111391121840652 - - -2.5862044847356653 - - -0.5012274095862923 - - -0.7858302699684137 - - 1.454618253084769 - - 0.06085157834607742 - velocity: [] - name: Grasp Machine diff --git a/src/picknik_ur_site_config/CMakeLists.txt b/src/picknik_ur_site_config/CMakeLists.txt deleted file mode 100644 index db083761..00000000 --- a/src/picknik_ur_site_config/CMakeLists.txt +++ /dev/null @@ -1,34 +0,0 @@ -cmake_minimum_required(VERSION 3.22) -project(picknik_ur_site_config) - -find_package(ament_cmake REQUIRED) -find_package(moveit_studio_common REQUIRED) -moveit_studio_package() - -# add custom behaviors -add_subdirectory(behaviors) - -install( - DIRECTORY - config - # Uncomment the following lines if you make use of these directories in you site_config package - # description - launch - objectives - # waypoints - DESTINATION - share/${PROJECT_NAME} -) - -if(BUILD_TESTING) - find_package(ament_lint_auto REQUIRED) - ament_lint_auto_find_test_dependencies() -endif() - -# Export the behavior plugins defined in this package so they are available to -# plugin loaders that load the behavior base class library from the -# moveit_studio_behavior package. -pluginlib_export_plugin_description_file( - moveit_studio_behavior_interface behaviors/trigger_pstop_reset_service_plugin_description.xml) - -ament_package() diff --git a/src/picknik_ur_site_config/LICENSE b/src/picknik_ur_site_config/LICENSE deleted file mode 100644 index 574ef079..00000000 --- a/src/picknik_ur_site_config/LICENSE +++ /dev/null @@ -1,25 +0,0 @@ -Redistribution and use in source and binary forms, with or without -modification, are permitted provided that the following conditions are met: - - * Redistributions of source code must retain the above copyright - notice, this list of conditions and the following disclaimer. - - * Redistributions in binary form must reproduce the above copyright - notice, this list of conditions and the following disclaimer in the - documentation and/or other materials provided with the distribution. - - * Neither the name of the copyright holder nor the names of its - contributors may be used to endorse or promote products derived from - this software without specific prior written permission. - -THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -POSSIBILITY OF SUCH DAMAGE. diff --git a/src/picknik_ur_site_config/README.md b/src/picknik_ur_site_config/README.md deleted file mode 100644 index 23d0ef9c..00000000 --- a/src/picknik_ur_site_config/README.md +++ /dev/null @@ -1,5 +0,0 @@ -# picknik_ur_site_config - -A MoveIt Pro site configuration for a UR arm based on the `picknik_ur_base_config` package. - -For further documentation see: [MoveIt Pro Documentation](https://docs.picknik.ai/) diff --git a/src/picknik_ur_site_config/behaviors/CMakeLists.txt b/src/picknik_ur_site_config/behaviors/CMakeLists.txt deleted file mode 100644 index 95f5a4a4..00000000 --- a/src/picknik_ur_site_config/behaviors/CMakeLists.txt +++ /dev/null @@ -1,37 +0,0 @@ -set(THIS_PACKAGE_INCLUDE_DEPENDS - moveit_studio_behavior_interface - pluginlib - std_srvs - ) -foreach(package IN ITEMS ${THIS_PACKAGE_INCLUDE_DEPENDS}) - find_package(${package} REQUIRED) -endforeach() - -add_library( - trigger_pstop_reset_service - SHARED - src/trigger_pstop_reset_service.cpp - src/register_behaviors.cpp) -target_include_directories( - trigger_pstop_reset_service - PUBLIC $ - $) -ament_target_dependencies(trigger_pstop_reset_service - ${THIS_PACKAGE_INCLUDE_DEPENDS}) - -if(BUILD_TESTING) - moveit_pro_behavior_test(trigger_pstop_reset_service) -endif() - -# Install Libraries -install( - TARGETS trigger_pstop_reset_service - EXPORT trigger_pstop_reset_serviceTargets - ARCHIVE DESTINATION lib - LIBRARY DESTINATION lib - RUNTIME DESTINATION bin - INCLUDES - DESTINATION include) - -ament_export_targets(trigger_pstop_reset_serviceTargets HAS_LIBRARY_TARGET) -ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS}) diff --git a/src/picknik_ur_site_config/behaviors/include/trigger_pstop_reset_service/trigger_pstop_reset_service.hpp b/src/picknik_ur_site_config/behaviors/include/trigger_pstop_reset_service/trigger_pstop_reset_service.hpp deleted file mode 100644 index 03a26ebe..00000000 --- a/src/picknik_ur_site_config/behaviors/include/trigger_pstop_reset_service/trigger_pstop_reset_service.hpp +++ /dev/null @@ -1,78 +0,0 @@ -#pragma once - -#include -#include - -namespace trigger_pstop_reset_service -{ -/** - * @brief Resets the UR P-stop status by calling the reset service named /recover_from_protective_stop. - */ -using PStopService = std_srvs::srv::Trigger; -class TriggerPStopResetService : public moveit_studio::behaviors::ServiceClientBehaviorBase -{ -public: -/** - * @brief Constructor for the trigger_pstop_reset_service behavior. - * @param name The name of a particular instance of this Behavior. This will be set by the behavior tree factory when this Behavior is created within a new behavior tree. - * @param config This contains runtime configuration info for this Behavior, such as the mapping between the Behavior's data ports on the behavior tree's blackboard. This will be set by the behavior tree factory when this Behavior is created within a new behavior tree. - * @details An important limitation is that the members of the base Behavior class are not instantiated until after the initialize() function is called, so these classes should not be used within the constructor. - */ - TriggerPStopResetService(const std::string& name, const BT::NodeConfiguration& config, - const std::shared_ptr& shared_resources); - - /** - * @brief Implementation of the required providedPorts() function for the trigger_pstop_reset_service Behavior. - * @details The BehaviorTree.CPP library requires that Behaviors must implement a static function named providedPorts() which defines their input and output ports. If the Behavior does not use any ports, this function must return an empty BT::PortsList. - * This function returns a list of ports with their names and port info, which is used internally by the behavior tree. - * @return trigger_pstop_reset_service does not use expose any ports, so this function returns an empty list. - */ - static BT::PortsList providedPorts(); - - /** - * @brief Implementation of the metadata() function for displaying metadata, such as Behavior description and - * subcategory, in the MoveIt Studio Developer Tool. - * @return A BT::KeyValueVector containing the Behavior metadata. - */ - static BT::KeyValueVector metadata(); - -private: - /** - * @brief Specify the name of the service that will be called by the behaviors - * @return Returns the name of the service. If not successful, returns an error message. - */ - tl::expected getServiceName() override; - /** - * @brief Sets the timeout for the service response. - * @details If the timeout expires before a response is received, the behavior will fail. A negative duration indicates no timeout. - * @return Returns the service response timeout duration. - */ - tl::expected, std::string> getResponseTimeout() override; - /** - * @brief Create a service request. - * @return Returns a service request message. If not successful, returns an error message. - */ - tl::expected createRequest() override; - /** - * @brief Determines if the service request succeeded or failed based on the response message. - * @param response Response message received from the service server. - * @return Returns true if the response indicates success. If not successful, returns an error message. - */ - tl::expected processResponse(const std_srvs::srv::Trigger::Response&) override; - - /** @brief Classes derived from AsyncBehaviorBase must implement getFuture() so that it returns a shared_future class member */ - std::shared_future>& getFuture() override; - - /** - * @brief Holds a copy of the service name specified by the input port. - */ - std::string service_name_; - - /** - * @brief Holds the result of calling the service asynchronously. - */ - std::shared_future> future_; - - -}; -} // namespace trigger_pstop_reset_service diff --git a/src/picknik_ur_site_config/behaviors/src/register_behaviors.cpp b/src/picknik_ur_site_config/behaviors/src/register_behaviors.cpp deleted file mode 100644 index e5ecd0e9..00000000 --- a/src/picknik_ur_site_config/behaviors/src/register_behaviors.cpp +++ /dev/null @@ -1,24 +0,0 @@ -#include -#include -#include - -#include - -#include - -namespace trigger_pstop_reset_service -{ -class TriggerPStopResetServiceBehaviorsLoader : public moveit_studio::behaviors::SharedResourcesNodeLoaderBase -{ -public: - void registerBehaviors(BT::BehaviorTreeFactory& factory, - [[maybe_unused]] const std::shared_ptr& shared_resources) override - { - moveit_studio::behaviors::registerBehavior(factory, "TriggerPStopResetService", shared_resources); - - } -}; -} // namespace trigger_pstop_reset_service - -PLUGINLIB_EXPORT_CLASS(trigger_pstop_reset_service::TriggerPStopResetServiceBehaviorsLoader, - moveit_studio::behaviors::SharedResourcesNodeLoaderBase); diff --git a/src/picknik_ur_site_config/behaviors/src/trigger_pstop_reset_service.cpp b/src/picknik_ur_site_config/behaviors/src/trigger_pstop_reset_service.cpp deleted file mode 100644 index 624f7491..00000000 --- a/src/picknik_ur_site_config/behaviors/src/trigger_pstop_reset_service.cpp +++ /dev/null @@ -1,80 +0,0 @@ -#include -#include - -namespace -{ - constexpr auto kDefaultPStopServiceName = "/recover_from_protective_stop"; - constexpr auto kPortServiceName = "service_name"; -}// namespace - -namespace trigger_pstop_reset_service -{ - TriggerPStopResetService::TriggerPStopResetService(const std::string& name, const BT::NodeConfiguration& config, - const std::shared_ptr& - shared_resources) - : ServiceClientBehaviorBase(name, config, shared_resources) - { - } - - tl::expected TriggerPStopResetService::getServiceName() - { - // Get service name from the input port. - const auto service_name = getInput(kPortServiceName); - // Check that the port has a value on it, if not, return an error. - if (const auto error = moveit_studio::behaviors::maybe_error(service_name)) - { - return tl::make_unexpected("Failed to get required value from input data port: " + error.value()); - } - - service_name_ = service_name.value(); - return service_name_; - } - - tl::expected, std::string> TriggerPStopResetService::getResponseTimeout() - { - // Create timeout for service call. - return std::chrono::duration{2.0}; - } - - tl::expected TriggerPStopResetService::createRequest() - { - // Create request message. - return PStopService::Request{}; - } - - tl::expected TriggerPStopResetService::processResponse( - const std_srvs::srv::Trigger::Response& trigger_response) - { - // If the service response could not be processed, returns an error message, otherwise, return true to indicate success. - return trigger_response.success - ? tl::expected(true) - : tl::make_unexpected( - "Failed to call P-Stop service `" + service_name_ + "`: " + trigger_response.message); - } - - std::shared_future>& TriggerPStopResetService::getFuture() - { - return future_; - } - - - BT::PortsList TriggerPStopResetService::providedPorts() - { - return { - BT::InputPort(kPortServiceName, kDefaultPStopServiceName, - "Name of the service to send a request to.") - }; - } - - BT::KeyValueVector TriggerPStopResetService::metadata() - { - return { - { - "description", - std::string( - "Resets the UR P-stop status by calling the reset service named service name specified by the input port named `") - .append(kPortServiceName).append("`.") - } - }; - } -} // namespace trigger_pstop_reset_service diff --git a/src/picknik_ur_site_config/behaviors/test/CMakeLists.txt b/src/picknik_ur_site_config/behaviors/test/CMakeLists.txt deleted file mode 100644 index 2780a607..00000000 --- a/src/picknik_ur_site_config/behaviors/test/CMakeLists.txt +++ /dev/null @@ -1,6 +0,0 @@ -find_package(ament_cmake_auto REQUIRED) -find_package(ament_cmake_gmock REQUIRED) -find_package(ament_cmake_gtest REQUIRED) - -ament_auto_add_gtest(test_behavior_plugins test_behavior_plugins.cpp) -ament_target_dependencies(test_behavior_plugins ${THIS_PACKAGE_INCLUDE_DEPENDS}) diff --git a/src/picknik_ur_site_config/behaviors/test/test_behavior_plugins.cpp b/src/picknik_ur_site_config/behaviors/test/test_behavior_plugins.cpp deleted file mode 100644 index 0d688f2b..00000000 --- a/src/picknik_ur_site_config/behaviors/test/test_behavior_plugins.cpp +++ /dev/null @@ -1,37 +0,0 @@ -#include - -#include -#include -#include -#include - -/** - * @brief This test makes sure that the Behaviors provided in this package can be successfully registered and - * instantiated by the behavior tree factory. - */ -TEST(BehaviorTests, test_load_behavior_plugins) -{ - pluginlib::ClassLoader class_loader( - "moveit_studio_behavior_interface", "moveit_studio::behaviors::SharedResourcesNodeLoaderBase"); - - auto node = std::make_shared("test_node"); - auto shared_resources = std::make_shared(node); - - BT::BehaviorTreeFactory factory; - { - auto plugin_instance = class_loader.createUniqueInstance("trigger_pstop_reset_service::TriggerPStopResetServiceBehaviorsLoader"); - ASSERT_NO_THROW(plugin_instance->registerBehaviors(factory, shared_resources)); - } - - // Test that ClassLoader is able to find and instantiate each behavior using the package's plugin description info. - EXPECT_NO_THROW( - (void)factory.instantiateTreeNode("test_behavior_name", "TriggerPStopResetService", BT::NodeConfiguration())); -} - -int main(int argc, char** argv) -{ - rclcpp::init(argc, argv); - - testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); -} diff --git a/src/picknik_ur_site_config/behaviors/trigger_pstop_reset_service_plugin_description.xml b/src/picknik_ur_site_config/behaviors/trigger_pstop_reset_service_plugin_description.xml deleted file mode 100644 index 5574332f..00000000 --- a/src/picknik_ur_site_config/behaviors/trigger_pstop_reset_service_plugin_description.xml +++ /dev/null @@ -1,7 +0,0 @@ - - - - diff --git a/src/picknik_ur_site_config/config/config.yaml b/src/picknik_ur_site_config/config/config.yaml deleted file mode 100644 index b722faeb..00000000 --- a/src/picknik_ur_site_config/config/config.yaml +++ /dev/null @@ -1,42 +0,0 @@ -based_on_package: "picknik_ur_base_config" - -objectives: - behavior_loader_plugins: - trigger_pstop_reset_service: - - "trigger_pstop_reset_service::TriggerPStopResetServiceBehaviorsLoader" - objective_library_paths: - # You must use a unique key for each package. - # The picknik_ur_base_config uses "core" - custom_objectives: - package_name: "picknik_ur_site_config" - relative_path: "objectives" - -# Configuration for launching ros2_control processes. -# [Required, if using ros2_control] -ros2_control: - config: - package: "picknik_ur_site_config" - path: "config/control/picknik_ur.ros2_control.yaml" - # MoveIt Pro will load and activate these controllers at start up to ensure they are available. - # If not specified, it is up to the user to ensure the appropriate controllers are active and available - # for running the application. - # [Optional, default=[]] - controllers_active_at_startup: - - "force_torque_sensor_broadcaster" - - "robotiq_gripper_controller" - - "joint_state_broadcaster" - - "servo_controller" - - "io_and_status_controller" - - "robotiq_activation_controller" - # Load but do not start these controllers so they can be activated later if needed. - # [Optional, default=[]] - controllers_inactive_at_startup: - - "joint_trajectory_controller" - - "joint_trajectory_admittance_controller" - - "velocity_force_controller" - # Any controllers here will not be spawned by MoveIt Pro. - # [Optional, default=[]] - controllers_not_managed: [] - # Optionally configure remapping rules to let multiple controllers receive commands on the same topic. - # [Optional, default=[]] - controller_shared_topics: [] diff --git a/src/picknik_ur_site_config/config/control/picknik_ur.ros2_control.yaml b/src/picknik_ur_site_config/config/control/picknik_ur.ros2_control.yaml deleted file mode 100644 index 17851768..00000000 --- a/src/picknik_ur_site_config/config/control/picknik_ur.ros2_control.yaml +++ /dev/null @@ -1,194 +0,0 @@ -controller_manager: - ros__parameters: - update_rate: 600 # Hz - joint_state_broadcaster: - type: joint_state_broadcaster/JointStateBroadcaster - io_and_status_controller: - type: ur_controllers/GPIOController - force_torque_sensor_broadcaster: - type: force_torque_sensor_broadcaster/ForceTorqueSensorBroadcaster - joint_trajectory_controller: - type: joint_trajectory_controller/JointTrajectoryController - robotiq_gripper_controller: - type: position_controllers/GripperActionController - robotiq_activation_controller: - type: robotiq_controllers/RobotiqActivationController - servo_controller: - type: joint_trajectory_controller/JointTrajectoryController - joint_trajectory_admittance_controller: - type: joint_trajectory_admittance_controller/JointTrajectoryAdmittanceController - velocity_force_controller: - type: velocity_force_controller/VelocityForceController - -io_and_status_controller: - ros__parameters: - tf_prefix: "" - -force_torque_sensor_broadcaster: - ros__parameters: - sensor_name: tcp_fts_sensor - state_interface_names: - - force.x - - force.y - - force.z - - torque.x - - torque.y - - torque.z - frame_id: tool0 - topic_name: ft_data - -joint_trajectory_controller: - ros__parameters: - joints: - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - command_interfaces: - - position - state_interfaces: - - position - - velocity - command_joints: - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - state_publish_rate: 100.0 - action_monitor_rate: 20.0 - allow_partial_joints_goal: false - constraints: - stopped_velocity_tolerance: 0.0 - goal_time: 0.0 - shoulder_pan_joint: - goal: 0.05 - shoulder_lift_joint: - goal: 0.05 - elbow_joint: - goal: 0.05 - wrist_1_joint: - goal: 0.05 - wrist_2_joint: - goal: 0.05 - wrist_3_joint: - goal: 0.05 - -servo_controller: - ros__parameters: - joints: - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - command_interfaces: - - position - state_interfaces: - - position - - velocity - command_joints: - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - state_publish_rate: 100.0 - action_monitor_rate: 20.0 - allow_partial_joints_goal: false - constraints: - stopped_velocity_tolerance: 0.0 - goal_time: 0.0 - shoulder_pan_joint: - goal: 0.05 - shoulder_lift_joint: - goal: 0.05 - elbow_joint: - goal: 0.05 - wrist_1_joint: - goal: 0.05 - wrist_2_joint: - goal: 0.05 - wrist_3_joint: - goal: 0.05 - -robotiq_gripper_controller: - ros__parameters: - default: true - joint: robotiq_85_left_knuckle_joint - allow_stalling: true - -robotiq_activation_controller: - ros__parameters: - default: true - -joint_trajectory_admittance_controller: - ros__parameters: - joints: - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - base_frame: base_link - sensor_frame: tool0 - ee_frame: grasp_link - ft_sensor_name: tcp_fts_sensor - # Joint accelerations chosen to match MoveIt configs. - stop_accelerations: - - 30.0 - - 30.0 - - 30.0 - - 30.0 - - 30.0 - - 30.0 - -velocity_force_controller: - ros__parameters: - joints: - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - base_frame: base_link - sensor_frame: tool0 - ee_frame: grasp_link - ft_sensor_name: tcp_fts_sensor - ft_force_deadband: 2.0 - ft_torque_deadband: 1.0 - max_joint_velocity: - - 0.524 - - 0.524 - - 0.524 - - 1.047 - - 1.047 - - 1.047 - max_joint_acceleration: - - 52.4 - - 52.4 - - 52.4 - - 52.4 - - 52.4 - - 52.4 - max_cartesian_velocity: - - 0.25 - - 0.25 - - 0.25 - - 1.5707 - - 1.5707 - - 1.5707 - max_cartesian_acceleration: - - 20.0 - - 20.0 - - 20.0 - - 40.0 - - 40.0 - - 40.0 diff --git a/src/picknik_ur_site_config/launch/agent_bridge.launch.xml b/src/picknik_ur_site_config/launch/agent_bridge.launch.xml deleted file mode 100644 index b2aa7543..00000000 --- a/src/picknik_ur_site_config/launch/agent_bridge.launch.xml +++ /dev/null @@ -1,6 +0,0 @@ - - - - diff --git a/src/picknik_ur_site_config/objectives/51mm_apriltag_detection_config.yaml b/src/picknik_ur_site_config/objectives/51mm_apriltag_detection_config.yaml deleted file mode 100644 index 6a2926c4..00000000 --- a/src/picknik_ur_site_config/objectives/51mm_apriltag_detection_config.yaml +++ /dev/null @@ -1,9 +0,0 @@ -DetectAprilTags: - apriltag_family_name: 36h11 - apriltag_size: 0.051 - max_hamming: 0 - n_threads: 1 - quad_decimate: 1 - quad_sigma: 0.1 - refine_edges: false - z_up: true diff --git a/src/picknik_ur_site_config/objectives/apriltag1_grasp_offset.yaml b/src/picknik_ur_site_config/objectives/apriltag1_grasp_offset.yaml deleted file mode 100644 index 49b6035e..00000000 --- a/src/picknik_ur_site_config/objectives/apriltag1_grasp_offset.yaml +++ /dev/null @@ -1,10 +0,0 @@ -GraspOffset: - position: - x: -0.1 - y: 0.0 - z: 0.05 - orientation: - x: 0.707 - y: -0.707 - z: 0.0 - w: 0.0 diff --git a/src/picknik_ur_site_config/objectives/close_cabinet_door.xml b/src/picknik_ur_site_config/objectives/close_cabinet_door.xml deleted file mode 100644 index fcca6052..00000000 --- a/src/picknik_ur_site_config/objectives/close_cabinet_door.xml +++ /dev/null @@ -1,125 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_site_config/objectives/detect_door_graspable_object.xml b/src/picknik_ur_site_config/objectives/detect_door_graspable_object.xml deleted file mode 100644 index df7751cf..00000000 --- a/src/picknik_ur_site_config/objectives/detect_door_graspable_object.xml +++ /dev/null @@ -1,95 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_site_config/objectives/detect_fixed_handle_graspable_object.xml b/src/picknik_ur_site_config/objectives/detect_fixed_handle_graspable_object.xml deleted file mode 100644 index f6ced3a6..00000000 --- a/src/picknik_ur_site_config/objectives/detect_fixed_handle_graspable_object.xml +++ /dev/null @@ -1,108 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_site_config/objectives/detect_hinge_line_segment.xml b/src/picknik_ur_site_config/objectives/detect_hinge_line_segment.xml deleted file mode 100644 index e7ef9475..00000000 --- a/src/picknik_ur_site_config/objectives/detect_hinge_line_segment.xml +++ /dev/null @@ -1,71 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_site_config/objectives/detect_lever_handle_line_segment.xml b/src/picknik_ur_site_config/objectives/detect_lever_handle_line_segment.xml deleted file mode 100644 index 94da04e0..00000000 --- a/src/picknik_ur_site_config/objectives/detect_lever_handle_line_segment.xml +++ /dev/null @@ -1,83 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_site_config/objectives/find_cuboids.xml b/src/picknik_ur_site_config/objectives/find_cuboids.xml deleted file mode 100644 index ef49033e..00000000 --- a/src/picknik_ur_site_config/objectives/find_cuboids.xml +++ /dev/null @@ -1,25 +0,0 @@ - - - - - - - - - - diff --git a/src/picknik_ur_site_config/objectives/find_cuboids_config.yaml b/src/picknik_ur_site_config/objectives/find_cuboids_config.yaml deleted file mode 100644 index 1265d62e..00000000 --- a/src/picknik_ur_site_config/objectives/find_cuboids_config.yaml +++ /dev/null @@ -1,23 +0,0 @@ -FindSingularCuboids: - base_frame: "world" - - # Distance threshold used when fitting a plane to the supporting surface. - # Increasing this value lets us fit to an uneven or noisy surface at the cost of preventing segmentation of short objects. - # Reducing this value allows detecting small objects on a very flat surface, but this will produce bad results for uneven or noisy surfaces. - plane_model_threshold: 0.01 - - # Distance threshold used when identifying clusters of points corresponding to distinct objects. - # Increasing this value makes the algorithm combine nearby discontinuous points into the same object, which lets the algorithm tolerate noisy data without introducing false positives at the cost of reduced accuracy. - # Reducing this value allows recognizing objects that are close to each other as distinct objects, but could increase the false positive rate. - cluster_distance_threshold: 0.01 - - # These define a rectangular region of interest relative to base_frame. - # The settings here define a 2m x 2m x 1m box just below the XY plane of the world frame. - # Origin of the region: - crop_box_origin_x: -1.0 - crop_box_origin_y: -1.0 - crop_box_origin_z: -0.03 - # Extent of the region: - crop_box_size_x: 2.0 - crop_box_size_y: 2.0 - crop_box_size_z: 1.0 diff --git a/src/picknik_ur_site_config/objectives/force_exceeds_threshold.xml b/src/picknik_ur_site_config/objectives/force_exceeds_threshold.xml deleted file mode 100644 index c121b4e9..00000000 --- a/src/picknik_ur_site_config/objectives/force_exceeds_threshold.xml +++ /dev/null @@ -1,19 +0,0 @@ - - - - - - - - diff --git a/src/picknik_ur_site_config/objectives/inspect_surface.xml b/src/picknik_ur_site_config/objectives/inspect_surface.xml deleted file mode 100644 index b83cb44c..00000000 --- a/src/picknik_ur_site_config/objectives/inspect_surface.xml +++ /dev/null @@ -1,71 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_site_config/objectives/loop_detect_apriltag.xml b/src/picknik_ur_site_config/objectives/loop_detect_apriltag.xml deleted file mode 100644 index fed3e120..00000000 --- a/src/picknik_ur_site_config/objectives/loop_detect_apriltag.xml +++ /dev/null @@ -1,39 +0,0 @@ - - - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_site_config/objectives/looping_pick_and_place_object.xml b/src/picknik_ur_site_config/objectives/looping_pick_and_place_object.xml deleted file mode 100644 index ebd6aa5c..00000000 --- a/src/picknik_ur_site_config/objectives/looping_pick_and_place_object.xml +++ /dev/null @@ -1,207 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_site_config/objectives/looping_pick_and_place_object_config.yaml b/src/picknik_ur_site_config/objectives/looping_pick_and_place_object_config.yaml deleted file mode 100644 index 233ad54c..00000000 --- a/src/picknik_ur_site_config/objectives/looping_pick_and_place_object_config.yaml +++ /dev/null @@ -1,95 +0,0 @@ -FindSingularCuboids: - base_frame: "world" - - # Distance threshold used when fitting a plane to the supporting surface. - # Increasing this value lets us fit to an uneven or noisy surface at the cost of preventing segmentation of short objects. - # Reducing this value allows detecting small objects on a very flat surface, but this will produce bad results for uneven or noisy surfaces. - plane_model_threshold: 0.01 - - # Distance threshold used when identifying clusters of points corresponding to distinct objects. - # Increasing this value makes the algorithm combine nearby discontinuous points into the same object, which lets the algorithm tolerate noisy data without introducing false positives at the cost of reduced accuracy. - # Reducing this value allows recognizing objects that are close to each other as distinct objects, but could increase the false positive rate. - cluster_distance_threshold: 0.01 - - # These define a rectangular region of interest relative to base_frame. - # The settings here define a box that encloses the shelf in the space station booth just below the XY plane of the world frame. - # Origin of the region: - crop_box_origin_x: -0.8 - crop_box_origin_y: 0.0 - crop_box_origin_z: -0.03 - # Extent of the region: - crop_box_size_x: 0.5 - crop_box_size_y: 0.75 - crop_box_size_z: 0.5 - -SetupMTCApproachGrasp: - # The lift vector points to the direction of the positive z-axis of the frame marked as the world frame. - world_frame_name: "world" - arm_group_name: "manipulator" - end_effector_group_name: "gripper" - end_effector_name: "moveit_ee" - hand_frame_name: "grasp_link" - - approach_distance: 0.15 - - # Set to true to make the robot keep the object within view of its camera while reaching to grasp it - enforce_visibility_constraint: true - camera_optical_frame_id: "wrist_mounted_camera_color_optical_frame" - camera_field_of_view_angle: 1.0472 # radians: approx. 60 degrees, which is narrower than the 70 degree diagonal FOV of the D415 camera - sensor_z_offset: 0.02 - target_diameter: 0.0 # Set to 0 to disable the visibility cone constraint -- it's not useful with a single-arm camera-in-hand configuration. - - -SetupMTCGenerateCuboidGrasps: - end_effector_group_name: "gripper" - end_effector_name: "moveit_ee" - hand_frame_name: "grasp_link" - end_effector_closed_pose_name: "close" - ui_grasp_link: "grasp_link" - - # Grasp candidate configs - grasp_candidate_config: - generate_x_axis_grasps: true - generate_y_axis_grasps: true - generate_z_axis_grasps: true - - # Number of samples to generate for each quadrant of the cuboid. - samples_per_quadrant: 3 - - # Grasp data configs - grasp_data: - # See https://ros-planning.github.io/moveit_tutorials/_images/finger_gripper_explanation.jpg for description of the following parameters - # Note: these parameters are copied from Robotiq gripper without tweaking - # min/max values of the grasp depth range in meter. - # This should fit to the distance from finger tip to inner palm or the suction cup stroke - grasp_min_depth: 0.01 # minimum amount fingers must overlap object - grasp_max_depth: 0.035 # Maximum distance from tip of end effector inwards that an object can be for a grasp - - # Maximum allowed finger width for a grasp. - # This value should be considerably smaller than max_finger_width - # to allow padded collision checks - max_grasp_width: 0.1 - - # The transform from the arm IK link to the grasp point to align it with the following convention. - # - # z-axis pointing toward object to grasp - # x-axis perpendicular to movement of grippers - # y-axis parallel to movement of grippers - eef_mount_to_tcp_transform: - x: 0.0 - y: 0.0 - z: -0.02 - roll: 0.0 - pitch: 0.0 - yaw: 1.57 - -SetupMTCRetractFromGrasp: - world_frame_name: "world" - arm_group_name: "manipulator" - end_effector_group_name: "gripper" - hand_frame_name: "grasp_link" - end_effector_closed_pose_name: "close" - - # The lift vector points to the direction of the positive z-axis of the frame marked as the world frame. - approach_distance: 0.15 - lift_distance: 0.1 diff --git a/src/picknik_ur_site_config/objectives/open_cabinet_door.xml b/src/picknik_ur_site_config/objectives/open_cabinet_door.xml deleted file mode 100644 index 55b2b4b7..00000000 --- a/src/picknik_ur_site_config/objectives/open_cabinet_door.xml +++ /dev/null @@ -1,185 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_site_config/objectives/open_door_admittance_controller_config.yaml b/src/picknik_ur_site_config/objectives/open_door_admittance_controller_config.yaml deleted file mode 100644 index 8f1bc6ee..00000000 --- a/src/picknik_ur_site_config/objectives/open_door_admittance_controller_config.yaml +++ /dev/null @@ -1,53 +0,0 @@ -UpdateAdmittanceController: - controller_name: "admittance_controller_open_door" - base_frame: "base_link" - end_effector_frame: "grasp_link" - control_frame: "grasp_link" - admittance: - selected_axes: - x: True - y: True - z: True - rx: True - ry: True - rz: True - mass_position: # kg - x: 10.0 - y: 10.0 - z: 10.0 - min: 0.001 - max: 100.0 - mass_rotation: # kg*m^2 - x: 5.0 - y: 5.0 - z: 5.0 - min: 0.001 - max: 100.0 - stiffness_position: # N/m - x: 500.0 - y: 500.0 - z: 500.0 - min: 0.0 - max: 1000.0 - stiffness_rotation: # N*m/rad - x: 100.0 - y: 100.0 - z: 100.0 - min: 0.0 - max: 1000.0 - damping_ratio_position: # unitless - x: 5.0 - y: 5.0 - z: 5.0 - min: 0.0 - max: 100.0 - damping_ratio_rotation: # unitless - x: 5.0 - y: 5.0 - z: 5.0 - min: 0.0 - max: 100.0 - joint_damping: # 1/s - value: 5.0 - min: 0.0 - max: 100.0 diff --git a/src/picknik_ur_site_config/objectives/open_door_fixed_handle_MTC_config.yaml b/src/picknik_ur_site_config/objectives/open_door_fixed_handle_MTC_config.yaml deleted file mode 100644 index a62d052e..00000000 --- a/src/picknik_ur_site_config/objectives/open_door_fixed_handle_MTC_config.yaml +++ /dev/null @@ -1,88 +0,0 @@ -SetupMTCGraspThenMoveAlongArcPull: - arm_group_name: "manipulator" - end_effector_group_name: "gripper" - end_effector_name: "moveit_ee" - ik_frame_name: "grasp_link" - end_effector_closed_pose_name: "close" - end_effector_open_pose_name: "open" - - # List of controllers to use during the stages that interact with the door. - move_along_arc_controllers: "/joint_trajectory_controller_chained_open_door /admittance_controller_open_door /robotiq_gripper_controller" - - # Approach parameters used for retract phase for now. - approach_min_distance: 0.10 # meters - approach_max_distance: 1.00 # meters - - translation_distance: 0.0 # meters (0 means only move along arc here, no linear component) - rotation_distance: 55.0 # Degrees - use_circular_arc: true - -SetupMTCApproachGrasp: - world_frame_name: "world" - arm_group_name: "manipulator" - end_effector_group_name: "gripper" - end_effector_name: "moveit_ee" - hand_frame_name: "grasp_link" - end_effector_closed_pose_name: "close" - ui_grasp_link: "grasp_link" - - approach_distance: 0.15 - - # Set to true to make the robot keep the object within view of its camera while reaching to grasp it - enforce_visibility_constraint: true - camera_optical_frame_id: "wrist_mounted_camera_color_optical_frame" - camera_field_of_view_angle: 1.0472 # radians: approx. 60 degrees, which is narrower than the 70 degree diagonal FOV of the D415 camera - sensor_z_offset: 0.02 - target_diameter: 0.0 # Set to 0 to disable the visibility cone constraint -- it's not useful with a single-arm camera-in-hand configuration. - - # Grasp candidate configs - grasp_candidate_config: - generate_x_axis_grasps: true - generate_y_axis_grasps: true - generate_z_axis_grasps: true - - # Number of samples to generate for each quadrant of the cuboid. - samples_per_quadrant: 3 - -SetupMTCGenerateCuboidGrasps: - end_effector_group_name: "gripper" - end_effector_name: "moveit_ee" - hand_frame_name: "grasp_link" - end_effector_closed_pose_name: "close" - ui_grasp_link: "grasp_link" - - # Grasp candidate configs - grasp_candidate_config: - generate_x_axis_grasps: true - generate_y_axis_grasps: true - generate_z_axis_grasps: true - - # Number of samples to generate for each quadrant of the cuboid. - samples_per_quadrant: 3 - - # Grasp data configs - grasp_data: - # See https://ros-planning.github.io/moveit_tutorials/_images/finger_gripper_explanation.jpg for description of the following parameters - # Note: these parameters are copied from Robotiq gripper without tweaking - # min/max values of the grasp depth range in meter. - # This should fit to the distance from finger tip to inner palm or the suction cup stroke - grasp_min_depth: 0.01 # minimum amount fingers must overlap object - grasp_max_depth: 0.035 # Maximum distance from tip of end effector inwards that an object can be for a grasp - - # Maximum allowed finger width for a grasp. - # This value should be considerably smaller than max_finger_width - # to allow padded collision checks - max_grasp_width: 0.1 - - # The transform from the arm IK link to the grasp point to align it with the following convention. - # - # z-axis pointing toward object to grasp - # x-axis perpendicular to movement of grippers - # y-axis parallel to movement of grippers - eef_mount_to_tcp_transform: - x: 0.0 - y: 0.0 - z: -0.02 - roll: 0.0 - pitch: 0.0 - yaw: 1.57 diff --git a/src/picknik_ur_site_config/objectives/open_door_fixed_handle_ml.xml b/src/picknik_ur_site_config/objectives/open_door_fixed_handle_ml.xml deleted file mode 100644 index e3f2f308..00000000 --- a/src/picknik_ur_site_config/objectives/open_door_fixed_handle_ml.xml +++ /dev/null @@ -1,173 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_site_config/objectives/open_door_lever_handle_MTC_config.yaml b/src/picknik_ur_site_config/objectives/open_door_lever_handle_MTC_config.yaml deleted file mode 100644 index f3549175..00000000 --- a/src/picknik_ur_site_config/objectives/open_door_lever_handle_MTC_config.yaml +++ /dev/null @@ -1,23 +0,0 @@ -SetupMTCGraspAndTwistThenMoveAlongArcPush: - arm_group_name: "manipulator" - end_effector_group_name: "gripper" - ik_frame_name: "grasp_link" - - # List of controllers to use during the stages that interact with the door. - move_along_arc_controllers: "/joint_trajectory_controller_chained_open_door /admittance_controller_open_door /robotiq_gripper_controller" - - # The hand should be placed 75% of the way down the handle length when - # manipulating the handle. Valid value range [0, 1.0]. - handle_grasp_offset_percent: 0.75 - # The distance above the handle the robot should approach with before - # manipulating it. - above_handle_approach_distance: 0.03 # meters - # The distance the hand should move past the end of the handle to release it. - release_handle_distance: 0.03 # meters - # How many degrees to rotate the lever handle (use positive value for - # counter-clockwise rotation and negative value for clockwise rotation). - handle_twist_angle: 45.0 # degrees - approach_max_distance: 0.05 # meters - approach_min_distance: 0.01 # meters - push_open_distance: 0.05 # meters - use_circular_arc: true diff --git a/src/picknik_ur_site_config/objectives/open_door_lever_handle_ml.xml b/src/picknik_ur_site_config/objectives/open_door_lever_handle_ml.xml deleted file mode 100644 index 450556ef..00000000 --- a/src/picknik_ur_site_config/objectives/open_door_lever_handle_ml.xml +++ /dev/null @@ -1,108 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_site_config/objectives/open_lever_handle_door.xml b/src/picknik_ur_site_config/objectives/open_lever_handle_door.xml deleted file mode 100644 index 6c09dc1e..00000000 --- a/src/picknik_ur_site_config/objectives/open_lever_handle_door.xml +++ /dev/null @@ -1,143 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_site_config/objectives/pick_apriltag_labeled_object.xml b/src/picknik_ur_site_config/objectives/pick_apriltag_labeled_object.xml deleted file mode 100644 index 5b3f8ef6..00000000 --- a/src/picknik_ur_site_config/objectives/pick_apriltag_labeled_object.xml +++ /dev/null @@ -1,52 +0,0 @@ - - - - - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_site_config/objectives/pick_object.xml b/src/picknik_ur_site_config/objectives/pick_object.xml deleted file mode 100644 index 2bb981ba..00000000 --- a/src/picknik_ur_site_config/objectives/pick_object.xml +++ /dev/null @@ -1,76 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_site_config/objectives/pick_object_config.yaml b/src/picknik_ur_site_config/objectives/pick_object_config.yaml deleted file mode 100644 index 09ca7d6e..00000000 --- a/src/picknik_ur_site_config/objectives/pick_object_config.yaml +++ /dev/null @@ -1,11 +0,0 @@ -SetupMTCPickObject: - # The lift vector points to the direction of the positive z-axis of the frame marked as the world frame. - world_frame_name: "world" - arm_group_name: "manipulator" - end_effector_group_name: "gripper" - end_effector_name: "moveit_ee" - hand_frame_name: "grasp_link" - end_effector_closed_pose_name: "close" - - approach_distance: 0.1 - lift_distance: 0.1 diff --git a/src/picknik_ur_site_config/objectives/pick_place_object.xml b/src/picknik_ur_site_config/objectives/pick_place_object.xml deleted file mode 100644 index 573b2dee..00000000 --- a/src/picknik_ur_site_config/objectives/pick_place_object.xml +++ /dev/null @@ -1,294 +0,0 @@ - - - - - -