diff --git a/libraries/SITL/SIM_Webots_Python.cpp b/libraries/SITL/SIM_Webots_Python.cpp new file mode 100644 index 0000000000..e5676d73ab --- /dev/null +++ b/libraries/SITL/SIM_Webots_Python.cpp @@ -0,0 +1,172 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ +/* + simulator connection for Webots 2023a +*/ + +#include "SIM_Webots_Python.h" + +#if HAL_SIM_WEBOTSPYTHON_ENABLED + +#include +#include + +namespace SITL { + +WebotsPython::WebotsPython(const char *frame_str) : + Aircraft(frame_str), + last_timestamp(0), + socket_sitl{true}{ + + // disable time sync and sensor smoothing to allow for faster than realtime simulation + use_time_sync = false; + use_smoothing = false; + + printf("Starting SITL Webots\n"); +} + +/* + Create and set in/out socket +*/ +void WebotsPython::set_interface_ports(const char* address, const int port_in, const int port_out) +{ + // try to bind to a specific port so that if we restart ArduPilot + // Webots keeps sending us packets. Not strictly necessary but + // useful for debugging + if (!socket_sitl.bind("0.0.0.0", port_in)) { + fprintf(stderr, "SITL: socket in bind failed on sim in : %d - %s\n", port_in, strerror(errno)); + fprintf(stderr, "Aborting launch...\n"); + exit(1); + } + printf("Bind %s:%d for SITL in\n", "127.0.0.1", port_in); + socket_sitl.reuseaddress(); + socket_sitl.set_blocking(false); + + _webots_address = address; + _webots_port = port_out; + printf("Setting Webots interface to %s:%d \n", _webots_address, _webots_port); +} + +/* + Decode and send SITL outputs to FDM aka Webots (scaled to be 0-1 instead of 1000-2000) +*/ +void WebotsPython::send_servos(const struct sitl_input &input) +{ + servo_packet pkt; + for (unsigned i = 0; i < 16; ++i){ + pkt.motor_speed[i] = (input.servos[i]-1000) / 1000.0f; + } + socket_sitl.sendto(&pkt, sizeof(pkt), _webots_address, _webots_port); +} + +/* + Receive sensor data from Webots (the Flight Dynamics Model) +*/ +void WebotsPython::recv_fdm(const struct sitl_input &input) +{ + fdm_packet pkt; + + /* + we re-send the servo packet every 0.1 seconds until we get a + reply. This allows us to cope with some packet loss to the FDM + */ + while (socket_sitl.recv(&pkt, sizeof(pkt), 100) != sizeof(pkt)) { + send_servos(input); + // Reset the timestamp after a long disconnection, also catch webots reset + if (get_wall_time_us() > last_wall_time_us + WEBOTS_TIMEOUT_US) { + last_timestamp = 0; + } + } + + const double deltat = pkt.timestamp - last_timestamp; // in seconds + if (deltat < 0) { // don't use old packet + time_now_us += 1; + return; + } + // get imu stuff + accel_body = Vector3f(static_cast(pkt.imu_linear_acceleration_xyz[0]), + static_cast(pkt.imu_linear_acceleration_xyz[1]), + static_cast(pkt.imu_linear_acceleration_xyz[2])); + + gyro = Vector3f(static_cast(pkt.imu_angular_velocity_rpy[0]), + static_cast(pkt.imu_angular_velocity_rpy[1]), + static_cast(pkt.imu_angular_velocity_rpy[2])); + + // compute dcm from imu orientation + dcm.from_euler(static_cast(pkt.imu_orientation_rpy[0]), + static_cast(pkt.imu_orientation_rpy[1]), + static_cast(pkt.imu_orientation_rpy[2])); + + velocity_ef = Vector3f(static_cast(pkt.velocity_xyz[0]), + static_cast(pkt.velocity_xyz[1]), + static_cast(pkt.velocity_xyz[2])); + + position = Vector3d(pkt.position_xyz[0], + pkt.position_xyz[1], + pkt.position_xyz[2]); + position.xy() += origin.get_distance_NE_double(home); + + // auto-adjust to simulation frame rate + time_now_us += static_cast(deltat * 1.0e6); + + if (deltat < 0.01 && deltat > 0) { + adjust_frame_time(static_cast(1.0/deltat)); + } + last_timestamp = pkt.timestamp; + +} + +/* + Drain remaining data on the socket to prevent phase lag + */ +void WebotsPython::drain_sockets() +{ + const uint16_t buflen = 1024; + char buf[buflen]; + ssize_t received; + errno = 0; + do { + received = socket_sitl.recv(buf, buflen, 0); + if (received < 0) { + if (errno != EAGAIN && errno != EWOULDBLOCK && errno != 0) { + fprintf(stderr, "error recv on socket in: %s \n", + strerror(errno)); + } + } else { + // fprintf(stderr, "received from control socket: %s\n", buf); + } + } while (received > 0); + +} + +/* + Update the Webots simulation by one time step + */ +void WebotsPython::update(const struct sitl_input &input) +{ + send_servos(input); + recv_fdm(input); + update_position(); + + time_advance(); + // update magnetic field + update_mag_field_bf(); + drain_sockets(); +} + +} // namespace SITL + + +#endif // HAL_SIM_WEBOTSPYTHON_ENABLED diff --git a/libraries/SITL/SIM_Webots_Python.h b/libraries/SITL/SIM_Webots_Python.h new file mode 100644 index 0000000000..194d8cd648 --- /dev/null +++ b/libraries/SITL/SIM_Webots_Python.h @@ -0,0 +1,90 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ +/* + simulator connection for Webots 2023a +*/ + +#pragma once + +#include + +#ifndef HAL_SIM_WEBOTSPYTHON_ENABLED +#define HAL_SIM_WEBOTSPYTHON_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL) +#endif + +#if HAL_SIM_WEBOTSPYTHON_ENABLED + +#include "SIM_Aircraft.h" +#include + +namespace SITL { + +/* + WebotsPython simulator + */ +class WebotsPython : public Aircraft { +public: + WebotsPython(const char *frame_str); + + /* update model by one time step */ + void update(const struct sitl_input &input) override; + + /* static object creator */ + static Aircraft *create(const char *frame_str) { + return new WebotsPython(frame_str); + } + + /* Create and set in/out socket for Webots simulator */ + void set_interface_ports(const char* address, const int port_in, const int port_out) override; + +private: + /// @brief packet to send to Webots + /// python struct code 'f'*16 + struct servo_packet { + float motor_speed[16]; + }; + + /// @brief packet from Webots (the Flight Dynamics Model) + /// python struct code 'd'*(1+3+3+3+3+3) + struct fdm_packet { + double timestamp; // in seconds + double imu_angular_velocity_rpy[3]; + double imu_linear_acceleration_xyz[3]; + double imu_orientation_rpy[3]; + double velocity_xyz[3]; + double position_xyz[3]; + }; + + /// @brief receive sensor packet from Webots + void recv_fdm(const struct sitl_input &input); + + /// @brief send servo packet to Webots + void send_servos(const struct sitl_input &input); + + /// @brief drain all pending packets from Webots + void drain_sockets(); + + double last_timestamp; + + SocketAPM socket_sitl; + const char* _webots_address = "127.0.0.1"; + int _webots_port = 9002; + static const uint64_t WEBOTS_TIMEOUT_US = 5000000; +}; + +} // namespace SITL + + +#endif // HAL_SIM_WEBOTSPYTHON_ENABLED diff --git a/libraries/SITL/examples/Webots_Python/.gitignore b/libraries/SITL/examples/Webots_Python/.gitignore new file mode 100644 index 0000000000..f09cdcb4c9 --- /dev/null +++ b/libraries/SITL/examples/Webots_Python/.gitignore @@ -0,0 +1,3 @@ +*.wbproj +__pycache__ +worlds/.* diff --git a/libraries/SITL/examples/Webots_Python/controllers/ardupilot_vehicle_controller/ardupilot_vehicle_controller.py b/libraries/SITL/examples/Webots_Python/controllers/ardupilot_vehicle_controller/ardupilot_vehicle_controller.py new file mode 100755 index 0000000000..1903966166 --- /dev/null +++ b/libraries/SITL/examples/Webots_Python/controllers/ardupilot_vehicle_controller/ardupilot_vehicle_controller.py @@ -0,0 +1,127 @@ +#!/usr/bin/env python3 +''' +General ardupilot vehicle controller for Webots 2023a + +AP_FLAKE8_CLEAN +''' + + +import time +import argparse +from webots_vehicle import WebotsArduVehicle + + +def get_args(): + parser = argparse.ArgumentParser() + + parser.add_argument("--motors", "-m", + type=str, + default="m1_motor, m2_motor, m3_motor, m4_motor", + help="Comma spaced list of motor names in ardupilot numerical order (ex --motors \"m1,m2,m3, m4\")") + parser.add_argument("--reversed-motors", "-r", + type=str, + default=None, + help="Comma spaced list of motors to reverse (starting from 1, in ardupilot order)") + parser.add_argument("--bidirectional-motors", + type=bool, + default=False, + help="If the motors are bidirectional (as is the case for Rovers usually)") + parser.add_argument("--uses-propellers", + type=bool, + default=True, + help="Whether the vehicle uses propellers. This is important as we need to linearize thrust if so") + parser.add_argument("--motor-cap", + type=float, + default=float('inf'), + help="Motor velocity cap. This is useful for the crazyflie which default has way too much power") + + parser.add_argument("--accel", + type=str, + default="accelerometer", + help="Webots accelerometer name") + parser.add_argument("--imu", + type=str, + default="inertial unit", + help="Webots IMU name") + parser.add_argument("--gyro", + type=str, + default="gyro", + help="Webots gyro name") + parser.add_argument("--gps", + type=str, + default="gps", + help="Webots GPS name") + + parser.add_argument("--camera", + type=str, + default=None, + help="Webots Camera name (optional)") + parser.add_argument("--camera-fps", + type=int, + default=10, + help="Camera FPS. Note lower FPS is faster") + parser.add_argument("--camera-port", + type=int, + default=None, + help="Port to stream grayscale camera images to. " + "If no port is supplied the camera will not be streamed.") + + parser.add_argument("--rangefinder", + type=str, + default=None, + help="Webots RangeFinder name (optional)") + parser.add_argument("--rangefinder-fps", + type=int, + default=10, + help="rangefinder FPS. Note lower FPS is faster") + parser.add_argument("--rangefinder-port", + type=int, + default=None, + help="Port to stream grayscale rangefinder images to. " + "If no port is supplied the rangefinder will not be streamed.") + + parser.add_argument("--instance", "-i", + type=int, + default=0, + help="Drone instance to match the SITL. This allows multiple vehicles") + parser.add_argument("--sitl-address", + type=str, + default="127.0.0.1", + help="IP address of the SITL (useful with WSL2 eg \"172.24.220.98\")") + + return parser.parse_args() + + +if __name__ == "__main__": + args = get_args() + + # parse string arguments into lists + motors = [x.strip() for x in args.motors.split(',')] + if args.reversed_motors: + reversed_motors = [int(x) for x in args.reversed_motors.split(",")] + else: + reversed_motors = [] + + vehicle = WebotsArduVehicle(motor_names=motors, + reversed_motors=reversed_motors, + accel_name=args.accel, + imu_name=args.imu, + gyro_name=args.gyro, + gps_name=args.gps, + camera_name=args.camera, + camera_fps=args.camera_fps, + camera_stream_port=args.camera_port, + rangefinder_name=args.rangefinder, + rangefinder_fps=args.rangefinder_fps, + rangefinder_stream_port=args.rangefinder_port, + instance=args.instance, + motor_velocity_cap=args.motor_cap, + bidirectional_motors=args.bidirectional_motors, + uses_propellers=args.uses_propellers, + sitl_address=args.sitl_address) + + # User code (ex: connect via drone kit and take off) + # ... + + while vehicle.webots_connected(): + time.sleep(1) diff --git a/libraries/SITL/examples/Webots_Python/controllers/ardupilot_vehicle_controller/webots_vehicle.py b/libraries/SITL/examples/Webots_Python/controllers/ardupilot_vehicle_controller/webots_vehicle.py new file mode 100644 index 0000000000..3de1197bcb --- /dev/null +++ b/libraries/SITL/examples/Webots_Python/controllers/ardupilot_vehicle_controller/webots_vehicle.py @@ -0,0 +1,392 @@ +#!/usr/bin/env python3 +''' +This file implements a class that acts as a bridge between ArduPilot SITL and Webots + +AP_FLAKE8_CLEAN +''' + +# Imports +import os +import sys +import time +import socket +import select +import struct +import numpy as np +from threading import Thread +from typing import List, Union + +# Here we set up environment variables so we can run this script +# as an external controller outside of Webots (useful for debugging) +# https://cyberbotics.com/doc/guide/running-extern-robot-controllers +if sys.platform.startswith("win"): + WEBOTS_HOME = "C:\\Program Files\\Webots" +elif sys.platform.startswith("darwin"): + WEBOTS_HOME = "/Applications/Webots.app" +elif sys.platform.startswith("linux"): + WEBOTS_HOME = "/usr/local/webots" +else: + raise Exception("Unsupported OS") + +if os.environ.get("WEBOTS_HOME") is None: + os.environ["WEBOTS_HOME"] = WEBOTS_HOME +else: + WEBOTS_HOME = os.environ.get("WEBOTS_HOME") + +os.environ["PYTHONIOENCODING"] = "UTF-8" +sys.path.append(f"{WEBOTS_HOME}/lib/controller/python") + +from controller import Robot, Camera, RangeFinder # noqa: E401, E402 + + +class WebotsArduVehicle(): + """Class representing an ArduPilot controlled Webots Vehicle""" + + controls_struct_format = 'f'*16 + controls_struct_size = struct.calcsize(controls_struct_format) + fdm_struct_format = 'd'*(1+3+3+3+3+3) + fdm_struct_size = struct.calcsize(fdm_struct_format) + + def __init__(self, + motor_names: List[str], + accel_name: str = "accelerometer", + imu_name: str = "inertial unit", + gyro_name: str = "gyro", + gps_name: str = "gps", + camera_name: str = None, + camera_fps: int = 10, + camera_stream_port: int = None, + rangefinder_name: str = None, + rangefinder_fps: int = 10, + rangefinder_stream_port: int = None, + instance: int = 0, + motor_velocity_cap: float = float('inf'), + reversed_motors: List[int] = None, + bidirectional_motors: bool = False, + uses_propellers: bool = True, + sitl_address: str = "127.0.0.1"): + """WebotsArduVehicle constructor + + Args: + motor_names (List[str]): Motor names in ArduPilot numerical order (first motor is SERVO1 etc). + accel_name (str, optional): Webots accelerometer name. Defaults to "accelerometer". + imu_name (str, optional): Webots imu name. Defaults to "inertial unit". + gyro_name (str, optional): Webots gyro name. Defaults to "gyro". + gps_name (str, optional): Webots GPS name. Defaults to "gps". + camera_name (str, optional): Webots camera name. Defaults to None. + camera_fps (int, optional): Camera FPS. Lower FPS runs better in sim. Defaults to 10. + camera_stream_port (int, optional): Port to stream grayscale camera images to. + If no port is supplied the camera will not be streamed. Defaults to None. + rangefinder_name (str, optional): Webots RangeFinder name. Defaults to None. + rangefinder_fps (int, optional): RangeFinder FPS. Lower FPS runs better in sim. Defaults to 10. + rangefinder_stream_port (int, optional): Port to stream rangefinder images to. + If no port is supplied the camera will not be streamed. Defaults to None. + instance (int, optional): Vehicle instance number to match the SITL. This allows multiple vehicles. Defaults to 0. + motor_velocity_cap (float, optional): Motor velocity cap. This is useful for the crazyflie + which default has way too much power. Defaults to float('inf'). + reversed_motors (list[int], optional): Reverse the motors (indexed from 1). Defaults to None. + bidirectional_motors (bool, optional): Enable bidirectional motors. Defaults to False. + uses_propellers (bool, optional): Whether the vehicle uses propellers. + This is important as we need to linearize thrust if so. Defaults to True. + sitl_address (str, optional): IP address of the SITL (useful with WSL2 eg \"172.24.220.98\"). + Defaults to "127.0.0.1". + """ + # init class variables + self.motor_velocity_cap = motor_velocity_cap + self._instance = instance + self._reversed_motors = reversed_motors + self._bidirectional_motors = bidirectional_motors + self._uses_propellers = uses_propellers + self._webots_connected = True + + # setup Webots robot instance + self.robot = Robot() + + # set robot time step relative to sim time step + self._timestep = int(self.robot.getBasicTimeStep()) + + # init sensors + self.accel = self.robot.getDevice(accel_name) + self.imu = self.robot.getDevice(imu_name) + self.gyro = self.robot.getDevice(gyro_name) + self.gps = self.robot.getDevice(gps_name) + + self.accel.enable(self._timestep) + self.imu.enable(self._timestep) + self.gyro.enable(self._timestep) + self.gps.enable(self._timestep) + + # init camera + if camera_name is not None: + self.camera = self.robot.getDevice(camera_name) + self.camera.enable(1000//camera_fps) # takes frame period in ms + + # start camera streaming thread if requested + if camera_stream_port is not None: + self._camera_thread = Thread(daemon=True, + target=self._handle_image_stream, + args=[self.camera, camera_stream_port]) + self._camera_thread.start() + + # init rangefinder + if rangefinder_name is not None: + self.rangefinder = self.robot.getDevice(rangefinder_name) + self.rangefinder.enable(1000//rangefinder_fps) # takes frame period in ms + + # start rangefinder streaming thread if requested + if rangefinder_stream_port is not None: + self._rangefinder_thread = Thread(daemon=True, + target=self._handle_image_stream, + args=[self.rangefinder, rangefinder_stream_port]) + self._rangefinder_thread.start() + + # init motors (and setup velocity control) + self._motors = [self.robot.getDevice(n) for n in motor_names] + for m in self._motors: + m.setPosition(float('inf')) + m.setVelocity(0) + + # start ArduPilot SITL communication thread + self._sitl_thread = Thread(daemon=True, target=self._handle_sitl, args=[sitl_address, 9002+10*instance]) + self._sitl_thread.start() + + def _handle_sitl(self, sitl_address: str = "127.0.0.1", port: int = 9002): + """Handles all communications with the ArduPilot SITL + + Args: + port (int, optional): Port to listen for SITL on. Defaults to 9002. + """ + + # create a local UDP socket server to listen for SITL + s = socket.socket(socket.AF_INET, socket.SOCK_DGRAM) # SOCK_STREAM + s.setsockopt(socket.SOL_SOCKET, socket.SO_REUSEADDR, 1) + s.bind(('0.0.0.0', port)) + + # wait for SITL to connect + print(f"Listening for ardupilot SITL (I{self._instance}) at 127.0.0.1:{port}") + self.robot.step(self._timestep) # flush print in webots console + + while not select.select([s], [], [], 0)[0]: # wait for socket to be readable + # if webots is closed, close the socket and exit + if self.robot.step(self._timestep) == -1: + s.close() + self._webots_connected = False + return + + print(f"Connected to ardupilot SITL (I{self._instance})") + + # main loop handling communications + while True: + # check if the socket is ready to send/receive + readable, writable, _ = select.select([s], [s], [], 0) + + # send data to SITL port (one lower than its output port as seen in SITL_cmdline.cpp) + if writable: + fdm_struct = self._get_fdm_struct() + s.sendto(fdm_struct, (sitl_address, port+1)) + + # receive data from SITL port + if readable: + data = s.recv(512) + if not data or len(data) < self.controls_struct_size: + continue + + # parse a single struct + command = struct.unpack(self.controls_struct_format, data[:self.controls_struct_size]) + self._handle_controls(command) + + # wait until the next Webots time step as no new sensor data will be available until then + step_success = self.robot.step(self._timestep) + if step_success == -1: # webots closed + break + + # if we leave the main loop then Webots must have closed + s.close() + self._webots_connected = False + print(f"Lost connection to Webots (I{self._instance})") + + def _get_fdm_struct(self) -> bytes: + """Form the Flight Dynamics Model struct (aka sensor data) to send to the SITL + + Returns: + bytes: bytes representing the struct to send to SITL + """ + # get data from Webots + i = self.imu.getRollPitchYaw() + g = self.gyro.getValues() + a = self.accel.getValues() + gps_pos = self.gps.getValues() + gps_vel = self.gps.getSpeedVector() + + # pack the struct, converting ENU to NED (ish) + # https://discuss.ardupilot.org/t/copter-x-y-z-which-is-which/6823/3 + # struct fdm_packet { + # double timestamp; + # double imu_angular_velocity_rpy[3]; + # double imu_linear_acceleration_xyz[3]; + # double imu_orientation_rpy[3]; + # double velocity_xyz[3]; + # double position_xyz[3]; + # }; + return struct.pack(self.fdm_struct_format, + self.robot.getTime(), + g[0], -g[1], -g[2], + a[0], -a[1], -a[2], + i[0], -i[1], -i[2], + gps_vel[0], -gps_vel[1], -gps_vel[2], + gps_pos[0], -gps_pos[1], -gps_pos[2]) + + def _handle_controls(self, command: tuple): + """Set the motor speeds based on the SITL command + + Args: + command (tuple): tuple of motor speeds 0.0-1.0 where -1.0 is unused + """ + + # get only the number of motors we have + command_motors = command[:len(self._motors)] + if -1 in command_motors: + print(f"Warning: SITL provided {command.index(-1)} motors " + f"but model specifies {len(self._motors)} (I{self._instance})") + + # scale commands to -1.0-1.0 if the motors are bidirectional (ex rover wheels) + if self._bidirectional_motors: + command_motors = [v*2-1 for v in command_motors] + + # linearize propeller thrust for `MOT_THST_EXPO=0` + if self._uses_propellers: + # `Thrust = thrust_constant * |omega| * omega` (ref https://cyberbotics.com/doc/reference/propeller) + # if we set `omega = sqrt(input_thottle)` then `Thrust = thrust_constant * input_thottle` + linearized_motor_commands = [np.sqrt(np.abs(v))*np.sign(v) for v in command_motors] + + # reverse motors if desired + if self._reversed_motors: + for m in self._reversed_motors: + linearized_motor_commands[m-1] *= -1 + + # set velocities of the motors in Webots + for i, m in enumerate(self._motors): + m.setVelocity(linearized_motor_commands[i] * min(m.getMaxVelocity(), self.motor_velocity_cap)) + + def _handle_image_stream(self, camera: Union[Camera, RangeFinder], port: int): + """Stream grayscale images over TCP + + Args: + camera (Camera or RangeFinder): the camera to get images from + port (int): port to send images over + """ + + # get camera info + # https://cyberbotics.com/doc/reference/camera + if isinstance(camera, Camera): + cam_sample_period = self.camera.getSamplingPeriod() + cam_width = self.camera.getWidth() + cam_height = self.camera.getHeight() + print(f"Camera stream started at 127.0.0.1:{port} (I{self._instance}) " + f"({cam_width}x{cam_height} @ {1000/cam_sample_period:0.2f}fps)") + elif isinstance(camera, RangeFinder): + cam_sample_period = self.rangefinder.getSamplingPeriod() + cam_width = self.rangefinder.getWidth() + cam_height = self.rangefinder.getHeight() + print(f"RangeFinder stream started at 127.0.0.1:{port} (I{self._instance}) " + f"({cam_width}x{cam_height} @ {1000/cam_sample_period:0.2f}fps)") + else: + print(sys.stderr, f"Error: camera passed to _handle_image_stream is of invalid type " + f"'{type(camera)}' (I{self._instance})") + return + + # create a local TCP socket server + server = socket.socket(socket.AF_INET, socket.SOCK_STREAM) + server.setsockopt(socket.SOL_SOCKET, socket.SO_REUSEADDR, 1) + server.bind(('127.0.0.1', port)) + server.listen(1) + + # continuously send images + while self._webots_connected: + # wait for incoming connection + conn, _ = server.accept() + print(f"Connected to camera client (I{self._instance})") + + # send images to client + try: + while self._webots_connected: + # delay at sample rate + start_time = self.robot.getTime() + + # get image + if isinstance(camera, Camera): + img = self.get_camera_gray_image() + elif isinstance(camera, RangeFinder): + img = self.get_rangefinder_image() + + if img is None: + print(f"No image received (I{self._instance})") + time.sleep(cam_sample_period/1000) + continue + + # create a header struct with image size + header = struct.pack("=HH", cam_width, cam_height) + + # pack header and image and send + data = header + img.tobytes() + conn.sendall(data) + + # delay at sample rate + while self.robot.getTime() - start_time < cam_sample_period/1000: + time.sleep(0.001) + + except ConnectionResetError: + pass + except BrokenPipeError: + pass + finally: + conn.close() + print(f"Camera client disconnected (I{self._instance})") + + def get_camera_gray_image(self) -> np.ndarray: + """Get the grayscale image from the camera as a numpy array of bytes""" + img = self.get_camera_image() + img_gray = np.average(img, axis=2).astype(np.uint8) + return img_gray + + def get_camera_image(self) -> np.ndarray: + """Get the RGB image from the camera as a numpy array of bytes""" + img = self.camera.getImage() + img = np.frombuffer(img, np.uint8).reshape((self.camera.getHeight(), self.camera.getWidth(), 4)) + return img[:, :, :3] # RGB only, no Alpha + + def get_rangefinder_image(self, use_int16: bool = False) -> np.ndarray: + """Get the rangefinder depth image as a numpy array of int8 or int16"""\ + + # get range image size + height = self.rangefinder.getHeight() + width = self.rangefinder.getWidth() + + # get image, and convert raw ctypes array to numpy array + # https://cyberbotics.com/doc/reference/rangefinder + image_c_ptr = self.rangefinder.getRangeImage(data_type="buffer") + img_arr = np.ctypeslib.as_array(image_c_ptr, (width*height,)) + img_floats = img_arr.reshape((height, width)) + + # normalize and set unknown values to max range + range_range = self.rangefinder.getMaxRange() - self.rangefinder.getMinRange() + img_normalized = (img_floats - self.rangefinder.getMinRange()) / range_range + img_normalized[img_normalized == float('inf')] = 1 + + # convert to int8 or int16, allowing for the option of higher precision if desired + if use_int16: + img = (img_normalized * 65535).astype(np.uint16) + else: + img = (img_normalized * 255).astype(np.uint8) + + return img + + def stop_motors(self): + """Set all motors to zero velocity""" + for m in self._motors: + m.setPosition(float('inf')) + m.setVelocity(0) + + def webots_connected(self) -> bool: + """Check if Webots client is connected""" + return self._webots_connected diff --git a/libraries/SITL/examples/Webots_Python/params/crazyflie.parm b/libraries/SITL/examples/Webots_Python/params/crazyflie.parm new file mode 100644 index 0000000000..e2431c1c9e --- /dev/null +++ b/libraries/SITL/examples/Webots_Python/params/crazyflie.parm @@ -0,0 +1,23 @@ +FRAME_CLASS 1 # Multirotor +FRAME_TYPE 3 # H class + +ATC_ANG_PIT_P 0.5 +ATC_ANG_RLL_P 0.5 +ATC_ANG_YAW_P 0.50000 + +ATC_RAT_PIT_P 0.05 +ATC_RAT_RLL_P 0.05 +ATC_RAT_YAW_P 0.02 + +ATC_RAT_PIT_I 0 +ATC_RAT_RLL_I 0 + +ATC_RAT_PIT_D 0.0003 +ATC_RAT_RLL_D 0.0003 +ATC_RAT_YAW_D 0.000001 + +AHRS_EKF_TYPE 10 # Use sim AHRS +ARMING_CHECK 1045534 # No RC requirements +MOT_THST_EXPO 0 # No motor exponential +SCHED_LOOP_RATE 300 +INS_GYR_CAL 0 \ No newline at end of file diff --git a/libraries/SITL/examples/Webots_Python/params/iris.parm b/libraries/SITL/examples/Webots_Python/params/iris.parm new file mode 100644 index 0000000000..f6abd7ff15 --- /dev/null +++ b/libraries/SITL/examples/Webots_Python/params/iris.parm @@ -0,0 +1,23 @@ +FRAME_CLASS 1 # Multirotor +FRAME_TYPE 1 # X class + +ATC_ANG_PIT_P 0.5 +ATC_ANG_RLL_P 0.5 +ATC_ANG_YAW_P 0.5 + +ATC_RAT_PIT_P 0.05 +ATC_RAT_RLL_P 0.05 +ATC_RAT_YAW_P 0.02 + +ATC_RAT_PIT_I 0 +ATC_RAT_RLL_I 0 + +ATC_RAT_PIT_D 0.0003 +ATC_RAT_RLL_D 0.0003 +ATC_RAT_YAW_D 0.000001 + +AHRS_EKF_TYPE 10 # Use sim AHRS +ARMING_CHECK 1045534 # No RC requirements +MOT_THST_EXPO 0 # No motor exponential +SCHED_LOOP_RATE 300 +INS_GYR_CAL 0 \ No newline at end of file diff --git a/libraries/SITL/examples/Webots_Python/params/pioneer3at.parm b/libraries/SITL/examples/Webots_Python/params/pioneer3at.parm new file mode 100644 index 0000000000..558722f945 --- /dev/null +++ b/libraries/SITL/examples/Webots_Python/params/pioneer3at.parm @@ -0,0 +1,12 @@ +FRAME_CLASS 1 # Rover + +SERVO1_FUNCTION 73 # (Throttle Left) +SERVO2_FUNCTION 73 +SERVO3_FUNCTION 74 # (Throttle Right) +SERVO4_FUNCTION 74 + +AHRS_EKF_TYPE 10 # Use sim AHRS +ARMING_CHECK 1045534 # No RC requirements +MOT_THST_EXPO 0 # No motor exponential +SCHED_LOOP_RATE 300 +INS_GYR_CAL 0 \ No newline at end of file diff --git a/libraries/SITL/examples/Webots_Python/protos/ArucoMarker.proto b/libraries/SITL/examples/Webots_Python/protos/ArucoMarker.proto new file mode 100644 index 0000000000..edd90ab2b4 --- /dev/null +++ b/libraries/SITL/examples/Webots_Python/protos/ArucoMarker.proto @@ -0,0 +1,57 @@ +# VRML_SIM R2022b utf8 +# template language: javascript + +PROTO ArucoMarker [ + field SFVec3f translation 0 0 0 + field SFRotation rotation 0 0 1 0 + field SFString name "aruco" # Defines the name of the aruco board. + field SFFloat size 0.1 # Defines size of the markers. + field SFString{"0", "1", "2", "3", "4", "5", "6", "7", "8"} + markerId "0" # Defines the marker id. +] +{ +Solid { + translation IS translation + rotation IS rotation + name IS name + children [ + # marker slightly in front of the border + Transform { + translation 0 0 1e-3 + children [ + Shape { + appearance PBRAppearance { + baseColor 1 1 1 + metalness 0 + roughness 0.6 + + %< let markerTexture = "textures/aruco_" + fields.markerId.value + ".png"; >% + baseColorMap ImageTexture { + url "%<= markerTexture >%" + } + + } + + geometry Plane { + size %<= fields.size.value >% %<= fields.size.value >% + } + } + ] + } + + + # while boarder + Shape { + appearance PBRAppearance { + baseColor 1 1 1 + metalness 0 + roughness 0.6 + } + geometry Plane { + size %<= fields.size.value * 8/6 >% %<= fields.size.value * 8/6 >% + } + } + + ] +} +} \ No newline at end of file diff --git a/libraries/SITL/examples/Webots_Python/protos/Iris.proto b/libraries/SITL/examples/Webots_Python/protos/Iris.proto new file mode 100644 index 0000000000..229946dd79 --- /dev/null +++ b/libraries/SITL/examples/Webots_Python/protos/Iris.proto @@ -0,0 +1,161 @@ +# VRML_SIM R2022b utf8 +# Iris drone model. Note that the model is not 1-to-1 with the +# real drone as motor/propeller constants were empirically determined. + +PROTO Iris [ + field SFVec3f translation 0 0 0 + field SFRotation rotation 0 0 1 0 + field SFString name "Iris" # Is `Robot.name`. + field SFString controller "void" # Is `Robot.controller`. + field MFString controllerArgs [] # Is `Robot.controllerArgs`. + field SFString customData "" # Is `Robot.customData`. + field SFBool supervisor FALSE # Is `Robot.supervisor`. + field SFBool synchronization TRUE # Is `Robot.synchronization`. + field MFNode extensionSlot [] # Extends the robot with new nodes in the extension slot. +] +{ + Robot { + translation IS translation + rotation IS rotation + controller IS controller + controllerArgs IS controllerArgs + customData IS customData + supervisor IS supervisor + synchronization IS synchronization + name IS name + children [ + Group { + children IS extensionSlot + } + DEF IRIS_MESH Shape { + appearance PBRAppearance { + baseColor 0.05 0.05 0.05 + roughness 1.000000 + metalness 0.2 + } + geometry Mesh { + url "meshes/iris.dae" + } + castShadows FALSE + } + Propeller { + shaftAxis 0 0 1 + centerOfThrust 0.130000 -0.220000 0.023000 + thrustConstants 0.0012 0 + torqueConstants 5.0e-04 0 + device RotationalMotor { + name "m1_motor" + maxVelocity 100 + maxTorque 30 + multiplier 1 + } + slowHelix Solid { + translation 0.130000 -0.220000 0.023000 + children [ + Shape { + appearance DEF PROP_BLUE PBRAppearance { + baseColor 0 0 0.75 + metalness 0.3 + } + geometry DEF CCW_PROP Mesh { + url [ + "meshes/iris_prop_ccw.dae" + ] + } + } + ] + } + } + Propeller { + shaftAxis 0 0 1 + centerOfThrust -0.130000 0.200000 0.023000 + thrustConstants 0.0012 0 + torqueConstants 5.0e-04 0 + device RotationalMotor { + name "m2_motor" + maxVelocity 100 + maxTorque 30 + multiplier 1 + } + slowHelix Solid { + translation -0.130000 0.200000 0.023000 + children [ + Shape { + appearance DEF PROP_BLACK PBRAppearance { + baseColor 0 0 0 + metalness 0.3 + } + geometry USE CCW_PROP + } + ] + } + } + Propeller { + shaftAxis 0 0 1 + centerOfThrust 00.130000 0.220000 0.023000 + thrustConstants -0.0012 0 + torqueConstants 5.0e-04 0 + device RotationalMotor { + name "m3_motor" + maxVelocity 100 + maxTorque 30 + multiplier -1 + } + slowHelix Solid { + translation 0.130000 0.220000 0.023000 + children [ + Shape { + appearance USE PROP_BLUE + geometry DEF CW_PROP Mesh { + url [ + "meshes/iris_prop_cw.dae" + ] + } + } + ] + } + } + Propeller { + shaftAxis 0 0 1 + centerOfThrust -0.130000 -0.200000 0.023000 + thrustConstants -0.0012 0 + torqueConstants 5.0e-04 0 + device RotationalMotor { + name "m4_motor" + maxVelocity 100 + maxTorque 30 + multiplier -1 + } + slowHelix Solid { + translation -0.130000 -0.200000 0.023000 + children [ + Shape { + appearance USE PROP_BLACK + geometry USE CW_PROP + } + ] + } + } + Accelerometer { + } + GPS { + } + Gyro { + } + InertialUnit { + } + ] + boundingObject Box { + size 0.470000 0.470000 0.110000 + } + physics Physics { + density -1 + mass 1.500000 + centerOfMass [ 0.000000 0.000000 0.000000 ] + inertiaMatrix [ + 2.912500e-02 2.912500e-02 5.522500e-02 + 0.000000e+00 0.000000e+00 0.000000e+00 + ] + } + } +} diff --git a/libraries/SITL/examples/Webots_Python/protos/meshes/iris.dae b/libraries/SITL/examples/Webots_Python/protos/meshes/iris.dae new file mode 100644 index 0000000000..6a9d9cd339 --- /dev/null +++ b/libraries/SITL/examples/Webots_Python/protos/meshes/iris.dae @@ -0,0 +1,59 @@ + + + + + Blender User + Blender 3.3.1 commit date:2022-10-04, commit time:18:35, hash:b292cfe5a936 + + 2023-01-12T14:06:40 + 2023-01-12T14:06:40 + + Z_UP + + + + + + + -0.1369961 0.208801 0.03249406 -0.1369961 0.208801 0.02049422 -0.1382977 0.2090982 0.03249406 -0.1359522 0.2079687 0.02049422 -0.1359522 0.2079687 0.03249406 -0.1369961 0.2033953 0.03249406 -0.1382977 0.2030982 0.03249406 -0.1382977 0.2030982 0.02049422 -0.1395994 0.2033953 0.02049422 -0.1395994 0.2033953 0.03249406 -0.1395994 0.208801 0.03249406 -0.1406432 0.2042278 0.02049422 -0.1406432 0.2042278 0.03249406 -0.1412225 0.2054307 0.02049422 -0.1412225 0.2054307 0.03249406 -0.1406432 0.2079687 0.03249406 -0.1395994 0.208801 0.02049422 -0.1412225 0.2067658 0.03249406 -0.1406432 0.2079687 0.02049422 -0.1412225 0.2067658 0.02049422 -0.14586 0.2141917 0.02049428 -0.1490407 0.2087329 0.02049428 -0.1492447 0.2069519 0.01949417 -0.1487627 0.2094694 0.01949423 -0.1493369 0.2068791 0.01546901 -0.1488348 0.2024176 0.01949435 -0.1466979 0.2133622 0.01949411 -0.1485819 0.2024221 0.02049422 -0.1459164 0.1981816 0.02049428 -0.1464609 0.1987314 0.01949423 -0.1403388 0.1950821 0.02049428 -0.1444542 0.1969874 0.01949423 -0.1465107 0.198687 0.01547569 -0.1430689 0.2014338 0.01949423 -0.1444542 0.1969874 0.01549428 -0.1457663 0.1992498 0.01368296 -0.1472466 0.1981645 0.009795129 -0.1487305 0.1971421 0.01119434 -0.1472826 0.1956837 0.01121592 -0.1487305 0.1971421 0.009794354 -0.1457114 0.1945183 0.009794354 -0.1457114 0.1945183 0.01119434 -0.1485158 0.1968978 -0.005005359 -0.1463797 0.1949744 -0.005005359 -0.1438902 0.1935372 -0.005005359 -0.144186 0.2004011 -0.005005359 -0.1447464 0.2126208 -0.005005359 -0.131849 0.1995757 -0.005005359 -0.1324094 0.2117953 -0.005005359 -0.1519722 0.2075355 -0.005005359 -0.1519722 0.204661 -0.005005359 -0.1513745 0.2018494 -0.005005359 -0.1411564 0.1926488 -0.005005359 -0.1502053 0.1992233 -0.005005359 -0.1382977 0.1923484 -0.005005359 -0.1357579 0.1925851 0.009794354 -0.1409193 0.1926007 0.009794354 -0.1383394 0.1923485 0.009794354 -0.1354389 0.1926488 -0.005005359 -0.1327052 0.1935372 -0.005005359 -0.1337705 0.19311 0.01121592 -0.1357579 0.1925851 0.01119434 -0.1319761 0.1938878 0.009794354 -0.1334543 0.1961476 0.01546901 -0.1319761 0.1938878 0.01119434 -0.1359995 0.1953452 0.01549428 -0.1365972 0.1994426 0.01949405 -0.1359995 0.1953452 0.01949423 -0.136101 0.1962059 0.0136829 -0.1358842 0.194199 0.00979495 -0.1330836 0.1955645 0.009794354 -0.133073 0.1955488 0.01119661 -0.1395605 0.2039393 0.009794354 -0.1372383 0.2038326 0.009794354 -0.1269525 0.2023153 0.009795069 -0.1279193 0.197079 0.009794354 -0.1358312 0.2056832 0.009794354 -0.139357 0.2038326 0.01368254 -0.137035 0.2039393 0.01368254 -0.1397619 0.2029781 0.01368153 -0.1357389 0.2065806 0.01368254 -0.1372387 0.2015273 0.01368427 -0.1365201 0.2034182 0.01368242 -0.134009 0.197031 0.01369231 -0.1362578 0.2015618 0.01949423 -0.1344946 0.2048752 0.01949423 -0.1326847 0.2044534 0.01368331 -0.1349157 0.2064236 0.01368093 -0.1348215 0.2093428 0.01368427 -0.1319055 0.2054659 0.01368266 -0.1352285 0.2063493 0.01949417 -0.1273639 0.2052452 0.01949423 -0.1278037 0.2097367 0.01949417 -0.1335265 0.2107627 0.01949423 -0.1301345 0.2134651 0.01549428 -0.1301345 0.2134651 0.01949423 -0.130829 0.2129467 0.01368296 -0.1295036 0.2139247 0.01119667 -0.1323455 0.2148079 0.01318186 -0.1346216 0.2111861 0.01368296 -0.133948 0.2121194 0.01949417 -0.1376451 0.2088906 0.01949423 -0.1376891 0.208662 0.01368427 -0.1402267 0.2079175 0.01368772 -0.136555 0.2078922 0.009794354 -0.1387841 0.2085516 0.009794354 -0.1386637 0.209808 0.01368176 -0.1405147 0.2106376 0.01368343 -0.1399834 0.2127076 0.01949411 -0.1405315 0.2153612 0.01374369 -0.1406095 0.2169165 0.01547563 -0.1426246 0.2152355 0.01368844 -0.14351 0.2166279 0.01123231 -0.1406942 0.2178151 0.009795069 -0.1434755 0.2165697 0.009794354 -0.1408376 0.2196114 0.01119434 -0.1408376 0.2196114 0.009794354 -0.135676 0.2195958 0.009794354 -0.138256 0.219848 0.009794354 -0.1382977 0.219848 -0.005005359 -0.1354389 0.2195476 -0.005005359 -0.1411564 0.2195476 -0.005005359 -0.1428248 0.2190865 0.01121592 -0.1438902 0.2186594 -0.005005359 -0.1463797 0.217222 -0.005005359 -0.1446193 0.2183086 0.009794354 -0.1446193 0.2183086 0.01119434 -0.1467988 0.2169052 0.009794354 -0.1485158 0.2152987 -0.005005359 -0.1486762 0.2151175 0.009794354 -0.149666 0.2098921 0.009795129 -0.1502053 0.2129731 -0.005005359 -0.1501845 0.2130092 0.009794354 -0.1408565 0.2065808 0.009794354 -0.1499552 0.2068498 0.009794354 -0.1408368 0.2054308 0.01368457 -0.1512977 0.2016199 0.009794354 -0.1519073 0.2041395 0.009794354 -0.1502261 0.1992595 0.009794354 -0.152033 0.2067288 0.009794354 -0.152033 0.2067288 0.01119434 -0.1518093 0.2086723 0.01121586 -0.1513745 0.2103471 -0.005005359 -0.1512704 0.2106553 0.01119434 -0.1512704 0.2106553 0.009794354 -0.1487591 0.2094843 0.01549428 -0.1479627 0.2091391 0.01368337 -0.1446899 0.2067306 0.01368266 -0.1500462 0.2068483 0.01119661 -0.1483472 0.2068985 0.01368874 -0.142101 0.2073213 0.01949423 -0.1439108 0.2077431 0.01368331 -0.1403377 0.2106349 0.01949423 -0.1431096 0.2159852 0.01949423 -0.1431096 0.2159852 0.01549428 -0.1413444 0.2166545 0.02049428 -0.1362974 0.2169794 0.02049428 -0.1382977 0.2090982 0.02049422 -0.140596 0.2168512 0.01949423 -0.1362164 0.2170639 0.01949435 -0.1321412 0.215209 0.01949423 -0.1316064 0.2148402 0.02049428 -0.1321018 0.2152681 0.01546901 -0.1277369 0.2098387 0.02049428 -0.1273837 0.2047587 0.02049422 -0.1353729 0.2067658 0.02049422 -0.1353729 0.2054307 0.02049422 -0.1353729 0.2067658 0.03249406 -0.1285663 0.2011405 0.02049422 -0.1353729 0.2054307 0.03249406 -0.1359522 0.2042278 0.02049422 -0.1328274 0.1963855 0.02049428 -0.1359522 0.2042278 0.03249406 -0.1369961 0.2033953 0.02049422 -0.1334857 0.1962112 0.01949423 -0.1307317 0.1980336 0.01949429 -0.1278125 0.2027109 0.01949363 -0.1286326 0.2030574 0.01368337 -0.1277729 0.2026911 0.01547557 -0.1273294 0.205322 0.01549428 -0.125325 0.2015411 0.01119434 -0.1247859 0.2035253 0.01121586 -0.125325 0.2015411 0.009794354 -0.1245624 0.2054677 0.009794354 -0.1245624 0.2054677 0.01119434 -0.1252208 0.2018494 -0.005005359 -0.1246232 0.204661 -0.005005359 -0.1246232 0.2075355 -0.005005359 -0.124688 0.2080569 0.009794354 -0.1252208 0.2103471 -0.005005359 -0.1252977 0.2105767 0.009794354 -0.12639 0.2129731 -0.005005359 -0.1278648 0.2150544 0.009794354 -0.1263692 0.212937 0.009794354 -0.1280796 0.2152987 -0.005005359 -0.1302158 0.217222 -0.005005359 -0.1293135 0.2165133 0.01121592 -0.130884 0.2176781 0.009794354 -0.130884 0.2176781 0.01119434 -0.1278648 0.2150544 0.01119434 -0.1317822 0.2158806 0.009794354 -0.1295764 0.21387 0.009794354 -0.1331893 0.2188639 0.009794354 -0.1327052 0.2186594 -0.005005359 -0.1259178 0.2053762 0.009797155 -0.1282482 0.205298 0.01368874 -0.12639 0.1992233 -0.005005359 -0.1280796 0.1968978 -0.005005359 -0.126411 0.1991873 0.009794354 -0.1302158 0.1949744 -0.005005359 -0.1297966 0.1952913 0.009794354 -0.1413668 0.2058471 0.01949417 -0.1417739 0.2028536 0.01368433 -0.1419737 0.2010105 0.01368296 -0.1426473 0.2000772 0.01949417 -0.1389503 0.2033059 0.01949423 -0.144014 0.197786 0.01368254 -0.1448105 0.1963195 0.01123237 -0.1447773 0.1963784 0.009794354 -0.1434061 0.1933327 0.009794354 -0.1403931 0.1951909 0.01949411 -0.1102201 0.1671164 -0.007641792 -0.1079671 0.1632139 -0.007641792 -0.110399 0.1671643 -0.004644811 -0.108015 0.1630352 -0.004644811 -0.1185293 0.1624702 -0.004644811 -0.1161454 0.158341 -0.004644811 -0.1185773 0.1622915 -0.007641792 -0.1163241 0.1583889 -0.007641792 -0.1189317 0.1568834 -0.007641792 -0.1211848 0.160786 -0.007641792 -0.1212688 0.1553946 -0.004873335 -0.1076126 0.1686219 -0.007641792 -0.1052755 0.1701108 -0.004873335 -0.1004784 0.1613451 -0.004644811 -0.1060001 0.1581571 -0.004644811 -0.1030943 0.165876 -0.004644811 -0.1080943 0.1745362 -0.004644811 -0.113616 0.1713482 -0.004644811 -0.1077243 0.1810215 0.001158118 -0.1097616 0.1849229 6.40063e-4 -0.1090009 0.1785622 5.45947e-4 -0.1128512 0.1852162 5.55451e-4 -0.1133068 0.1844288 0.001082122 -0.1099194 0.1784232 0.001093864 -0.1098041 0.1851338 0.004762351 -0.1131603 0.1855106 0.007264554 -0.1075963 0.1810296 0.004440963 -0.1318691 0.1671656 5.39532e-4 -0.1328864 0.1735788 5.66137e-4 -0.1342819 0.1708678 0.001127719 -0.128981 0.1669017 5.99425e-4 -0.1285832 0.1676622 0.001092851 -0.1319636 0.1736617 0.001098752 -0.131823 0.1738334 0.007020592 -0.1281014 0.167378 0.007025659 -0.1287945 0.1665878 0.007242202 -0.1319469 0.1669563 0.004922986 -0.1077439 0.174822 -0.001492559 -0.110097 0.1850494 -0.001481771 -0.1057382 0.1769888 -0.001443803 -0.1329664 0.1742085 0.007295012 -0.1344451 0.1708463 0.004824399 -0.103154 0.1740038 -8.69784e-4 -0.1077678 0.1848673 -3.38568e-4 -0.09956473 0.1692075 -3.37208e-4 -0.05995529 0.09934544 -8.67763e-4 -0.06426107 0.1079519 -3.37208e-4 -0.05482226 0.0930038 -3.37208e-4 -0.05064111 0.08491206 -8.54144e-4 -0.04513871 0.07820171 -3.37208e-4 -0.04150795 0.07101655 -9.07954e-4 -0.03521054 0.06354564 -3.37208e-4 -0.03397828 0.05912727 -0.001200139 -0.03266429 0.05689156 -0.001306772 -0.09110689 0.153674 -3.37208e-4 -0.1007072 0.1674819 -0.001397848 -0.09812974 0.1626899 -0.001433491 -0.1028103 0.1714351 -0.001386404 -0.1031457 0.1703946 -0.001494884 -0.09116417 0.15004 -0.001391768 -0.08240354 0.138287 -3.37208e-4 -0.08822262 0.1448025 -0.001409292 -0.09337806 0.1540193 -0.001387178 -0.09367018 0.1529983 -0.001492738 -0.083274 0.1361461 -0.001396059 -0.07345485 0.1230463 -3.37208e-4 -0.08118963 0.1325614 -0.001408696 -0.07318264 0.1190584 -0.001387298 -0.0707553 0.1150431 -0.001419663 -0.07347196 0.1180002 -0.001496553 -0.06556469 0.106599 -0.001389503 -0.06238692 0.1015149 -0.001387357 -0.0678271 0.1102578 -0.001425266 -0.055058 0.09000796 -0.001389563 -0.0509743 0.08373177 -0.001395106 -0.05735427 0.09357357 -0.001449346 -0.04843664 0.07987326 -0.00141257 -0.04680883 0.07705193 -0.001491844 -0.03497803 0.05967241 -0.001490235 -0.05984574 0.09747999 -0.001445174 -0.06265157 0.1004068 -0.001494944 -0.07589524 0.1235806 -0.001396775 -0.0781185 0.1273288 -0.001411378 -0.08603471 0.1409553 -0.001414179 -0.09584236 0.158498 -0.001387298 -0.09695994 0.1589056 -0.001496195 -0.115203 0.1817689 -0.001491844 -0.1154274 0.1821576 -0.001598238 -0.1053209 0.1706309 -0.001491844 -0.10295 0.1665191 -0.001491844 -0.1000096 0.1614261 -0.001491844 -0.0976364 0.1573151 -0.001491904 -0.09901118 0.1610355 -0.001493573 -0.1067942 0.1769841 -0.001491546 -0.1027992 0.1675876 -0.001492738 -0.09538358 0.1534136 -0.001491844 -0.0928502 0.1490256 -0.001491844 -0.08990967 0.1439325 -0.001491844 -0.08738017 0.1395512 -0.001491844 -0.08747553 0.140013 -0.001491844 -0.08894747 0.1435296 -0.001492679 -0.08704012 0.140998 -0.00149101 -0.09503138 0.1531002 -0.001491844 -0.09276449 0.1500389 -0.001496136 -0.08528369 0.1359201 -0.001491844 -0.08275032 0.1315321 -0.001491844 -0.07980984 0.126439 -0.001491844 -0.07728028 0.1220578 -0.001491844 -0.07737565 0.1225196 -0.001491844 -0.07884067 0.1260485 -0.00149393 -0.07688969 0.1236074 -0.001491904 -0.08481359 0.1355698 -0.001493752 -0.08262002 0.1325636 -0.001492679 -0.04288595 0.05651205 -0.001491844 -0.07518386 0.1184266 -0.001491844 -0.07265049 0.1140387 -0.001491844 -0.0748316 0.1181132 -0.001491844 -0.07250726 0.1150937 -0.001492798 -0.06970995 0.1089456 -0.001491844 -0.06718045 0.1045643 -0.001491844 -0.06727576 0.1050261 -0.001491844 -0.06870949 0.1085554 -0.001493573 -0.06657463 0.1066195 -0.001491546 -0.06508398 0.1009331 -0.001491844 -0.0625506 0.09654521 -0.001491844 -0.05961006 0.09145212 -0.001491844 -0.05724763 0.08735984 -0.001491904 -0.05859398 0.09104824 -0.00149244 -0.0560618 0.09001624 -0.001491785 -0.06473171 0.1006197 -0.001491844 -0.06245851 0.09762448 -0.001490235 -0.05498409 0.0834397 -0.001491844 -0.05245071 0.07905173 -0.001491844 -0.04934775 0.0736835 -0.001491844 -0.03665721 0.06009626 -0.001491844 -0.04837942 0.07375878 -0.001491844 -0.05463182 0.08312618 -0.001491844 -0.05250638 0.07968324 -0.001491844 -0.05205833 0.08013093 -0.001491844 -0.05154889 0.0828188 -0.001491904 -0.05609285 0.04804348 -0.002104878 -0.1288905 0.1741327 -0.001518845 -0.1293225 0.1748809 -0.002104878 -0.05645811 0.04867619 -0.001491844 -0.1340299 0.1713081 -0.00148791 -0.1333696 0.176354 -0.004873335 -0.1396887 0.1759845 -0.007175445 -0.1351892 0.1690633 -3.37939e-4 -0.1330021 0.1796723 -0.006851255 -0.07088375 0.05974507 0.003989398 -0.0703926 0.05743807 0.003207087 -0.07033538 0.05914938 0.001774549 -0.06619697 0.05871278 0.001746177 -0.06215465 0.05147689 0.001746833 -0.0611608 0.05101597 0.002362668 -0.06578361 0.05925506 0.002734303 -0.06584095 0.04926347 0.001773357 -0.06582778 0.04833775 0.00233221 -0.06641972 0.05944955 0.007615447 -0.06572222 0.05921524 0.007008969 -0.04610556 0.06173431 -8.89382e-4 -0.048653 0.06623291 -8.19306e-4 -0.04684716 0.0620023 -0.001492798 -0.04898422 0.06566059 -0.001395642 -0.04773384 0.05960673 -0.001388609 -0.04748225 0.05911016 -8.18247e-4 -0.0568543 0.05484652 -0.001491844 -0.05688369 0.05384725 -8.90193e-4 -0.05911338 0.0546891 -0.001395642 -0.05944454 0.05411684 -8.19303e-4 -0.0619648 0.05860841 -0.00138992 -0.06036376 0.06074297 -0.001388609 -0.06084346 0.06103265 -8.91236e-4 -0.05124324 0.06550323 -0.001491844 -0.05121439 0.0665 -9.04788e-4 -0.06114739 0.0610935 0.007165908 -0.06230908 0.05853676 0.007015883 -0.05173456 0.06667786 0.007020592 -0.04856455 0.06654655 0.007021546 -0.04580342 0.06184321 0.007015824 -0.0450381 0.07483786 0.002210199 -0.03821432 0.0645948 0.001776516 -0.04432618 0.07438915 0.003817677 -0.04477262 0.07318097 0.001744508 -0.04737585 0.06996446 0.002465963 -0.04654425 0.06994056 0.001745164 -0.04269999 0.06179165 0.002379953 -0.04227268 0.06277614 0.001746118 -0.04744446 0.06984013 0.00700742 -0.04304897 0.06221306 0.007160663 -0.0455352 0.0740714 0.005267798 -0.1177285 0.1985768 -0.004004895 -0.1171315 0.1991576 -0.003341197 -0.1183388 0.1993926 -0.003226757 -0.1198886 0.1960669 -0.003352224 -0.1153695 0.1881653 -0.003407776 -0.1189367 0.1957547 -0.004003167 -0.1147462 0.1890576 -0.004005372 -0.1120183 0.1889581 -0.003323137 -0.1121308 0.1882604 -0.003984749 -0.1126961 0.187875 -0.003040313 -0.1117395 0.1874546 0.006099462 -0.1155277 0.1877894 0.007015407 -0.1181973 0.1923335 0.007020592 -0.1203412 0.1959511 0.008440375 -0.1342906 0.1773461 -0.002793252 -0.1387373 0.1851019 -0.003109395 -0.1344308 0.1767885 -0.003624677 -0.1390696 0.1845355 -0.003659188 -0.1428495 0.1849493 -0.003774523 -0.1429517 0.1843007 -0.002790272 -0.1366226 0.1747044 -0.002790272 -0.1355958 0.1744466 -0.003690004 -0.1422628 0.1854634 -0.002790272 -0.1431089 0.1858621 0.006473243 -0.1389915 0.18559 0.009074628 -0.1383582 0.1852421 0.008307099 -0.1361261 0.1813188 0.007481753 -0.133839 0.1773223 0.007001221 -0.1115749 0.192349 -0.00728625 -0.1139717 0.1899339 -0.006574034 -0.1201046 0.1901567 -0.007695674 -0.1203339 0.1967686 -0.007762789 -0.1188986 0.2003044 -0.007764279 -0.1132602 0.1957126 -0.007755339 -0.1171615 0.2000359 0.005339562 -0.1153861 0.1963358 0.004180192 -0.111381 0.1883956 0.004519462 -0.1335456 0.1821716 -0.007654905 -0.1418222 0.1792224 -0.007755339 -0.1391636 0.1858763 -0.007760286 -0.1432583 0.1864802 -0.007757008 -0.136451 0.1739817 0.004541993 -0.1414328 0.181277 0.004535496 -0.1438654 0.1852204 0.005235731 -0.1354508 0.1738772 0.005758166 -0.1359718 0.1860058 -0.007761478 -0.1327455 0.1854333 -0.007641792 -0.1479339 0.1883728 -0.007756352 -0.1319946 0.186906 -0.007785916 -0.1150181 0.1868376 -0.004850685 -0.1157503 0.1827168 -0.002104878 -0.1357503 0.2146686 -0.01604926 -0.1335737 0.2138118 -0.01850515 -0.135793 0.2149366 -0.01850521 -0.1340252 0.2135847 -0.01648974 -0.1327148 0.2164888 -0.01563447 -0.1324568 0.2174373 -0.01849961 -0.1353536 0.2170418 -0.01632541 -0.1349791 0.2182491 -0.01850217 -0.1280914 0.2157741 -0.01131814 -0.1282182 0.2145959 -0.01797479 -0.1275676 0.2151508 -0.0124967 -0.1318886 0.214316 -0.01663863 -0.1302781 0.2160636 -0.01851493 -0.1293047 0.2168028 -0.01263469 -0.1283006 0.2116515 -0.01612567 -0.1300815 0.2110366 -0.01850515 -0.1269602 0.2119469 -0.0184943 -0.1485462 0.2005921 -0.01581424 -0.1465139 0.2011598 -0.01850515 -0.1496309 0.2002606 -0.01850521 -0.1491279 0.2030919 -0.01644003 -0.1505952 0.2027707 -0.01850992 -0.1474885 0.2045408 -0.01654583 -0.1452521 0.1971591 -0.01632726 -0.1438945 0.1988258 -0.01850473 -0.1469346 0.1956279 -0.01734322 -0.1486026 0.1974897 -0.01325291 -0.148093 0.1960225 -0.0110898 -0.1486354 0.1976051 -0.01769286 -0.141093 0.1956312 -0.01696836 -0.1408023 0.1972589 -0.01850521 -0.1416161 0.1939501 -0.01850521 -0.1436986 0.1961891 -0.01627826 -0.1441637 0.1946902 -0.01840722 -0.1430217 0.1983847 -0.01850515 -0.1425701 0.1986118 -0.01648974 -0.1410068 0.1978006 -0.01572579 -0.1287064 0.1961156 -0.01100564 -0.1286476 0.1961556 -0.01350528 -0.1272808 0.19579 -0.01350528 -0.1274691 0.1958407 -0.010369 -0.1355284 0.1921798 -0.01100414 -0.1345121 0.1927697 -0.01350528 -0.1348317 0.1915901 -0.01050055 -0.1348789 0.1914032 -0.01350528 -0.1345334 0.1915785 -0.004644811 -0.1255441 0.1760084 -0.004644811 -0.1257228 0.1760563 -0.007641792 -0.1342738 0.1903551 -0.01350528 -0.1247775 0.1909411 -0.007628738 -0.1266756 0.1947419 -0.01350528 -0.1186159 0.1800083 -0.004644811 -0.1185681 0.1801871 -0.007641792 -0.1276053 0.1955784 -0.004644811 -0.1344007 0.2083482 -0.01350528 -0.1338661 0.2068797 -0.01350528 -0.1339639 0.2046664 -0.01350528 -0.1359294 0.2021934 -0.01350528 -0.1390354 0.2015894 -0.01350528 -0.1411902 0.202651 -0.01350528 -0.1421948 0.2038483 -0.01350528 -0.03726565 0.04443246 -0.02125471 -0.03937 0.0480768 -0.009096741 -0.03968387 0.04917156 -0.008179664 -0.03931373 0.04995125 -0.007764518 -0.03666245 0.04538714 -0.02125513 -0.03333663 0.04730731 -0.02125519 -0.03485029 0.05253219 -0.007755339 -0.05206865 0.04341822 -0.007640719 -0.04853248 0.03729403 -0.02125513 -0.05144721 0.04207843 -0.008443355 -0.04951435 0.03796523 -0.0212543 -0.05218404 0.04238402 -0.007857441 -0.04903811 0.03547906 -0.02125513 -0.04747104 0.03368991 -0.02125513 -0.05140078 0.03520578 -0.02125513 -0.05419617 0.03493267 -0.02125513 -0.05251801 0.03310608 -0.02125513 -0.05465298 0.03373402 -0.02125513 -0.05456072 0.03241527 -0.02125513 -0.05327159 0.03579783 -0.02125513 -0.0539357 0.03121143 -0.02125513 -0.0517621 0.03135979 -0.02125513 -0.05252712 0.02995574 -0.02125513 -0.05028194 0.03055304 -0.02125513 -0.04911565 0.02931839 -0.02125513 -0.04805332 0.03138381 -0.02125513 -0.04745721 0.02991729 -0.02125513 -0.04680144 0.0302959 -0.02125513 -0.05087864 0.02933174 -0.02125513 -0.04606944 0.03102791 -0.02125513 -0.04580146 0.0320279 -0.02125513 -0.04606944 0.03302788 -0.02125513 -0.04706943 0.03475993 0.002358496 -0.05206936 0.04342007 0.002358496 -0.04606944 0.03302788 -0.004469811 -0.03279322 0.03869205 -0.02125298 -0.03372174 0.03840041 -0.002547264 -0.03364664 0.0388441 -0.003916561 -0.03244155 0.03872281 -0.002807676 -0.03179645 0.03895902 -0.001641392 -0.03601539 0.03883051 -0.001898109 -0.03426688 0.03933542 -0.00463885 -0.0334416 0.0380997 -0.002010345 -0.03767365 0.0371257 -0.002657115 -0.03626054 0.0386911 0.002358496 -0.03530585 0.03979212 0.002358496 -0.0352478 0.03998875 -0.002125859 -0.03552848 0.04142308 0.002358496 -0.03452849 0.03969109 -0.02125513 -0.04052841 0.05008322 0.002358496 -0.0405268 0.05008214 -0.007641375 -0.04433739 0.03402787 0.002358496 -0.04655241 0.05353337 0.002358496 -0.05204653 0.05047827 0.002363502 -0.04596829 0.03380525 0.002358496 -0.04740262 0.05500596 0.002182126 -0.04433739 0.03402787 -0.001641392 -0.04589223 0.03262364 -0.00463885 -0.04576617 0.03373569 -0.002339601 -0.04439038 0.03322643 -0.002589881 -0.0458213 0.03164142 -0.002696573 -0.0461477 0.03088706 -0.002274513 -0.04680144 0.0302959 -0.001641392 -0.04825556 0.02945631 0.005144417 -0.03034234 0.03979855 0.005144417 -0.03114074 0.03933763 -0.02125513 -0.03179645 0.03895902 -0.02125513 -0.0484693 0.05685359 -0.002373933 -0.05361163 0.05307501 -0.001860976 -0.05446219 0.05454826 -0.002641856 -0.04896932 0.05771958 -0.002641856 -0.04802304 0.05608052 -0.001407861 -0.05332791 0.05258369 0.001639306 -0.04789781 0.05586367 0.001135826 -0.04655241 0.05353337 -0.002641856 -0.05204528 0.05036205 -0.002641856 -0.05206936 0.04874652 -0.004644811 -0.05206936 0.0484848 -0.007641792 -0.04514122 0.05274647 -0.004644811 -0.0449146 0.05261558 -0.007641792 -0.06622886 0.04810875 0.00351274 -0.06136357 0.05063951 0.00772798 -0.06653207 0.04716974 0.003472268 -0.06133294 0.05169224 0.00705558 -0.06076192 0.05299329 0.007804274 -0.03749591 0.06461191 0.00345546 -0.04197561 0.06191694 0.007504999 -0.03739273 0.06430596 0.003946959 -0.03498947 0.06321811 0.002989172 -0.03600299 0.06308811 0.003635168 -0.03910648 0.06129634 0.006144404 -0.04108536 0.06015384 0.007744431 -0.04612386 0.07968407 0.003962159 -0.0438162 0.07501506 0.004169344 -0.0464282 0.07724678 0.004599332 -0.04743844 0.08096706 0.004310309 -0.05675101 0.09601521 0.004688799 -0.05434751 0.09143882 0.004832983 -0.05704915 0.09357088 0.005227982 -0.05758506 0.08887732 0.007718801 -0.05905848 0.09875214 0.005131185 -0.0670908 0.1125397 0.005173563 -0.06622993 0.1100115 0.005542278 -0.06227058 0.1000901 0.006515622 -0.0634033 0.09881812 0.007776379 -0.07714188 0.1292575 0.005415499 -0.07006776 0.1164901 0.005597293 -0.07644301 0.1269334 0.005811691 -0.08023798 0.1337347 0.005725681 -0.08689349 0.1461525 0.005413889 -0.08539158 0.1416468 0.005940496 -0.08726072 0.1451596 0.005893409 -0.08703154 0.1417878 0.006948649 -0.08824366 0.1420245 0.007777333 -0.09634125 0.1632165 0.005168795 -0.09505957 0.1600023 0.005516886 -0.1014986 0.1716641 0.005337297 -0.1001151 0.168312 0.005582273 -0.1054832 0.1804456 0.004680514 -0.1069017 0.1813336 0.005136013 -0.1053303 0.1783166 0.00526899 -0.1143122 0.1978239 0.003950178 -0.1146566 0.1967068 0.004550099 -0.108888 0.1859978 0.004800975 -0.1114886 0.1899988 0.004944026 -0.1143703 0.1871893 0.00764203 -0.1085569 0.1770691 0.00777477 -0.102518 0.1700744 0.006397187 -0.1043556 0.1696421 0.007716774 -0.1032043 0.1680278 0.007603943 -0.09588128 0.1592406 0.005640745 -0.09878826 0.1604968 0.007492601 -0.09047168 0.1515215 0.005708336 -0.09262412 0.1531803 0.005872964 -0.09580057 0.1522743 0.007744431 -0.09266823 0.15052 0.007221639 -0.08067101 0.1332792 0.005903363 -0.08210808 0.1360239 0.005976557 -0.08475756 0.1351682 0.007669448 -0.08303409 0.1330093 0.007635891 -0.07705247 0.1242364 0.007336497 -0.07861894 0.1255118 0.007429599 -0.07177078 0.1185393 0.005833983 -0.0733937 0.1163635 0.007747173 -0.06699615 0.1067042 0.007521629 -0.06530034 0.1077303 0.005557537 -0.05107623 0.08251601 0.005849778 -0.05320066 0.08130443 0.007728099 -0.04762351 0.07199412 0.007689177 -0.0447697 0.06196981 0.007792174 -0.07133537 0.05858683 0.003981947 -0.0720213 0.05806285 0.003960132 -0.06599891 0.0609163 0.007693946 -0.07161927 0.06010961 0.004902482 -0.04798775 0.06927645 0.007745206 -0.0605123 0.04893767 0.007744431 -0.05598825 0.05302274 0.007744431 -0.04688113 0.05858051 0.007731378 -0.04808878 0.067254 0.007743835 -0.05098533 0.07230228 0.007743716 -0.0522716 0.06934922 0.007742762 -0.05175584 0.06725758 0.007742643 -0.05192905 0.07647043 0.007739365 -0.05697602 0.08267897 0.007743716 -0.0540955 0.07767874 0.007744193 -0.05598634 0.08306902 0.007739663 -0.06008875 0.08803814 0.007743656 -0.058811 0.08946198 0.007733464 -0.06297749 0.09307479 0.007743716 -0.06427168 0.09013342 0.007742762 -0.0635423 0.08805388 0.007716238 -0.06434917 0.09757941 0.007747352 -0.06608873 0.09843015 0.007743537 -0.06897741 0.103467 0.007743775 -0.07057702 0.1002534 0.00775057 -0.07989585 0.09465062 0.007744252 -0.07921528 0.09317082 0.007743179 -0.08399754 0.09462445 0.007744133 -0.08115184 0.08969599 0.007742583 -0.08264499 0.08987236 0.007750511 -0.08087515 0.08703148 0.007746577 -0.07799941 0.08428162 0.007742226 -0.0760796 0.0787822 0.007744431 -0.07511955 0.07923573 0.007743597 -0.07369667 0.08238518 0.007741868 -0.06914365 0.1058875 0.007748007 -0.07209247 0.1088277 0.007743775 -0.0755555 0.1170265 0.007744789 -0.07805716 0.1191672 0.007743716 -0.07924282 0.1233821 0.007747113 -0.08097743 0.1242513 0.007743597 -0.0824508 0.1209191 0.00774455 -0.08148515 0.1194397 0.007741451 -0.07492703 0.1137684 0.007743895 -0.086066 0.1351817 0.007744133 -0.08412879 0.1296542 0.007744133 -0.0869286 0.1345566 0.007743895 -0.08962512 0.1413829 0.007745623 -0.09005701 0.1399515 0.007743716 -0.09297716 0.1450357 0.007743716 -0.0942713 0.1420942 0.007742762 -0.09328204 0.1402577 0.007743299 -0.0942291 0.1493052 0.00774455 -0.09605693 0.1503437 0.007743716 -0.09897708 0.1554278 0.007743656 -0.1002714 0.1524863 0.007742762 -0.09928107 0.1506472 0.007743418 -0.09944325 0.1583681 0.007748007 -0.09717571 0.1594327 0.007480382 -0.1020592 0.160738 0.007743835 -0.1052274 0.16837 0.007744431 -0.1080881 0.1711754 0.007743656 -0.1090139 0.174969 0.007746458 -0.1109771 0.1762121 0.007743597 -0.1122712 0.1732707 0.007742762 -0.1115418 0.1711913 0.007716238 -0.1049267 0.1657292 0.007743895 -0.1138122 0.1846732 0.007649004 -0.1140879 0.1815677 0.007743775 -0.1169669 0.186643 0.007743895 -0.118501 0.1918647 0.007700979 -0.120492 0.1912362 0.007486402 -0.1182686 0.1836868 0.007742166 -0.1177374 0.1810056 0.007369458 -0.1272034 0.1763151 0.007743835 -0.1278952 0.177788 0.007744252 -0.1320607 0.1778052 0.007743477 -0.1291671 0.172852 0.007743835 -0.1325707 0.1765716 0.007750511 -0.1268751 0.1667483 0.007745325 -0.1259986 0.1674193 0.007741928 -0.1231188 0.1623731 0.007743597 -0.1216961 0.1655225 0.007741868 -0.1342893 0.1831611 0.007598459 -0.1263707 0.1643304 0.007294356 -0.1222606 0.1587504 0.007746875 -0.1171191 0.1519809 0.007743775 -0.1168178 0.1493911 0.007746398 -0.111877 0.1407678 0.007745862 -0.1140219 0.1466568 0.007743239 -0.1111666 0.1416741 0.007743597 -0.1139824 0.1412391 0.007608354 -0.1127584 0.1391782 0.007519781 -0.1246688 0.157594 0.007131755 -0.1230229 0.1565178 0.007255733 -0.1199854 0.1569589 0.007744252 -0.1188714 0.1491091 0.007328689 -0.118459 0.1470725 0.007294118 -0.107999 0.1362424 0.007742226 -0.1058269 0.1303765 0.007746994 -0.1051191 0.1311966 0.007743597 -0.103657 0.1345118 0.007744252 -0.1020082 0.1258411 0.007743716 -0.1020605 0.1237639 0.007747232 -0.1043033 0.1229453 0.007342994 -0.1027596 0.1215644 0.007375955 -0.09911942 0.1208044 0.007743775 -0.09851497 0.1257928 0.007742941 -0.09764075 0.1239598 0.007743775 -0.08888459 0.1310236 0.007744431 -0.09627938 0.1137692 0.007744431 -0.09600818 0.115449 0.007743597 -0.09311938 0.1104122 0.007743656 -0.09251505 0.1154006 0.007742941 -0.09165716 0.1137273 0.007744252 -0.09827518 0.1141368 0.007617235 -0.09823662 0.1120687 0.007375955 -0.09184193 0.1060835 0.007744312 -0.08711957 0.1000201 0.007743775 -0.08620464 0.09631919 0.007744252 -0.09000825 0.1050568 0.007743656 -0.08651512 0.1050084 0.007742941 -0.08565717 0.1033351 0.007744252 -0.07620036 0.1088365 0.007744252 -0.07688474 0.1102392 0.007744431 -0.08807533 0.09591829 0.00753498 -0.08636641 0.09442049 0.007649898 -0.0777468 0.07949924 0.007663547 -0.0762825 0.07692945 0.007675886 -0.07198601 0.0738216 0.007744252 -0.07164222 0.07109647 0.007744252 -0.07331311 0.0720244 0.007647275 -0.07260596 0.06991958 0.007673621 -0.06911981 0.06884354 0.007743775 -0.063156 0.05852657 0.007741689 -0.06801462 0.06160867 0.00753653 -0.06598919 0.06343245 0.007743537 -0.06781613 0.07394331 0.007744014 -0.06770843 0.0719785 0.007742285 -0.058483 0.07955569 0.00774753 -0.05754238 0.07766175 0.007716238 -0.06181341 0.06355303 0.007744193 -0.07398802 0.08419924 0.007744431 -0.1039876 0.1361601 0.007744431 -0.1157832 0.157076 0.007743954 -0.1156568 0.155296 0.007744252 -0.1068957 0.1623526 0.007739663 -0.1052819 0.1610419 0.007743239 -0.1099876 0.1465523 0.007744431 -0.1092119 0.1452087 0.007744431 -0.1219874 0.1673366 0.007744431 -0.1340104 0.1931074 -0.0165683 -0.1342658 0.1926151 -0.0165053 -0.133745 0.1932126 -0.01719421 -0.1294148 0.1957126 -0.01719421 -0.1284206 0.1958158 -0.01634263 -0.1291983 0.1958376 -0.01657223 -0.1429177 0.2191004 -0.0170052 -0.1425614 0.2184832 -0.01800519 -0.1297039 0.1962133 -0.01800519 -0.1321688 0.2005848 -0.01678508 -0.1427775 0.2194706 -0.01654672 -0.1479987 0.2163987 -0.01650398 -0.1403651 0.2044667 -0.01669722 -0.1474718 0.2167267 -0.01666045 -0.1468915 0.2159833 -0.01800519 -0.1340339 0.1937133 -0.01800519 -0.05292898 0.05023545 -0.004644811 -0.0529769 0.05005669 -0.007641792 -0.05797684 0.05871683 -0.007641792 -0.05792891 0.05889558 -0.004644811 -0.05572372 0.05481433 -0.007641792 -0.05554497 0.05476641 -0.004644811 -0.06297677 0.06737697 -0.007641792 -0.06292891 0.06755572 -0.004644811 -0.06072366 0.06347447 -0.007641792 -0.0605449 0.06342655 -0.004644811 -0.06797671 0.07603716 -0.007641792 -0.06792879 0.07621586 -0.004644811 -0.06572359 0.07213461 -0.007641792 -0.06554484 0.07208675 -0.004644811 -0.07297664 0.0846973 -0.007641792 -0.07292872 0.084876 -0.004644811 -0.07072353 0.08079475 -0.007641792 -0.07054477 0.08074688 -0.004644811 -0.07797658 0.09335744 -0.007641792 -0.07792872 0.09353613 -0.004644811 -0.07572346 0.08945488 -0.007641792 -0.07554471 0.08940702 -0.004644811 -0.08297652 0.1020175 -0.007641792 -0.08292865 0.1021963 -0.004644811 -0.0807234 0.09811502 -0.007641792 -0.08054465 0.09806716 -0.004644811 -0.08797645 0.1106777 -0.007641792 -0.08792859 0.1108564 -0.004644811 -0.08572334 0.1067752 -0.007641792 -0.08554458 0.1067273 -0.004644811 -0.09297639 0.1193378 -0.007641792 -0.09292852 0.1195166 -0.004644811 -0.09072327 0.1154353 -0.007641792 -0.09054452 0.1153874 -0.004644811 -0.09797632 0.127998 -0.007641792 -0.09792846 0.1281767 -0.004644811 -0.09572321 0.1240954 -0.007641792 -0.09554445 0.1240476 -0.004644811 -0.1029763 0.1366581 -0.007641792 -0.1029284 0.1368368 -0.004644811 -0.1007232 0.1327555 -0.007641792 -0.1005444 0.1327077 -0.004644811 -0.1079762 0.1453183 -0.007641792 -0.1079283 0.145497 -0.004644811 -0.1057231 0.1414157 -0.007641792 -0.1055443 0.1413679 -0.004644811 -0.1129761 0.1539784 -0.007641792 -0.1129282 0.1541572 -0.004644811 -0.110723 0.1500758 -0.007641792 -0.1105443 0.1500279 -0.004644811 -0.04600089 0.05423539 -0.004644811 -0.04582214 0.05418747 -0.007641792 -0.05082207 0.06284767 -0.007641792 -0.04856896 0.05894511 -0.007641792 -0.05100083 0.06289553 -0.004644811 -0.04861688 0.05876636 -0.004644811 -0.05582201 0.07150781 -0.007641792 -0.05356889 0.06760525 -0.007641792 -0.05600076 0.07155567 -0.004644811 -0.05361682 0.06742656 -0.004644811 -0.06082195 0.08016794 -0.007641792 -0.05856883 0.07626539 -0.007641792 -0.0610007 0.08021581 -0.004644811 -0.05861675 0.07608669 -0.004644811 -0.06582188 0.08882808 -0.007641792 -0.06356877 0.08492553 -0.007641792 -0.06600064 0.08887594 -0.004644811 -0.06361669 0.08474683 -0.004644811 -0.07082182 0.09748822 -0.007641792 -0.0685687 0.09358572 -0.007641792 -0.07100057 0.09753608 -0.004644811 -0.06861662 0.09340697 -0.004644811 -0.07582175 0.1061484 -0.007641792 -0.07356864 0.1022459 -0.007641792 -0.07600051 0.1061963 -0.004644811 -0.07361656 0.1020671 -0.004644811 -0.08082169 0.1148085 -0.007641792 -0.07856857 0.110906 -0.007641792 -0.08100044 0.1148564 -0.004644811 -0.07861649 0.1107273 -0.004644811 -0.08582162 0.1234686 -0.007641792 -0.08356851 0.1195662 -0.007641792 -0.08600038 0.1235166 -0.004644811 -0.08361643 0.1193874 -0.004644811 -0.09082156 0.1321287 -0.007641792 -0.08856844 0.1282262 -0.007641792 -0.09100031 0.1321766 -0.004644811 -0.08861637 0.1280475 -0.004644811 -0.09582149 0.1407889 -0.007641792 -0.09356838 0.1368864 -0.007641792 -0.09600025 0.1408367 -0.004644811 -0.0936163 0.1367077 -0.004644811 -0.1008214 0.1494491 -0.007641792 -0.09856832 0.1455465 -0.007641792 -0.1010002 0.1494969 -0.004644811 -0.09861624 0.1453678 -0.004644811 -0.1058214 0.1581092 -0.007641792 -0.1035683 0.1542066 -0.007641792 -0.1036161 0.1540279 -0.004644811 -0.1205441 0.1673483 -0.004644811 -0.1207229 0.1673962 -0.007641792 -0.1229281 0.1714774 -0.004644811 -0.122976 0.1712986 -0.007641792 -0.1158213 0.1754295 -0.007641792 -0.1135681 0.171527 -0.007641792 -0.116 0.1754774 -0.004644811 -0.1104782 0.1786653 -0.004644811 -0.1130942 0.1831963 -0.004644811 -0.1126205 0.1772871 -0.007647752 -0.1103594 0.1733796 -0.007641792 -0.1239316 0.1655436 -0.007641792 -0.1262688 0.1640548 -0.004873335 -0.1234499 0.1596293 -0.004644811 -0.1184499 0.1509692 -0.004644811 -0.1053595 0.1647194 -0.007641792 -0.1026126 0.1599617 -0.007641792 -0.1161849 0.1521258 -0.007641792 -0.1003596 0.1560592 -0.007641792 -0.1139317 0.1482234 -0.007641792 -0.09790152 0.1573387 -0.004873335 -0.1162689 0.1467344 -0.004873335 -0.09547847 0.1526849 -0.004644811 -0.11345 0.142309 -0.004644811 -0.09761273 0.1513016 -0.007641792 -0.111185 0.1434657 -0.007641792 -0.09535962 0.1473991 -0.007641792 -0.1089318 0.1395632 -0.007641792 -0.09290158 0.1486787 -0.004873335 -0.1112689 0.1380743 -0.004873335 -0.09047853 0.1440248 -0.004644811 -0.1084501 0.1336489 -0.004644811 -0.0926128 0.1426414 -0.007641792 -0.106185 0.1348055 -0.007641792 -0.09035968 0.1387389 -0.007641792 -0.1039319 0.1309031 -0.007641792 -0.08790165 0.1400185 -0.004873335 -0.106269 0.1294141 -0.004873335 -0.0854786 0.1353646 -0.004644811 -0.1034501 0.1249887 -0.004644811 -0.08761286 0.1339813 -0.007641792 -0.1011851 0.1261454 -0.007641792 -0.08535975 0.1300788 -0.007641792 -0.0989319 0.1222429 -0.007641792 -0.08290171 0.1313584 -0.004873335 -0.1012691 0.120754 -0.004873335 -0.08047866 0.1267045 -0.004644811 -0.09845018 0.1163287 -0.004644811 -0.08261293 0.1253212 -0.007641792 -0.09618508 0.1174852 -0.007641792 -0.08035981 0.1214187 -0.007641792 -0.09393197 0.1135828 -0.007641792 -0.07790178 0.1226982 -0.004873335 -0.09626913 0.1120938 -0.004873335 -0.07547873 0.1180443 -0.004644811 -0.09345024 0.1076685 -0.004644811 -0.07761299 0.1166611 -0.007641792 -0.09118515 0.1088252 -0.007641792 -0.07535988 0.1127585 -0.007641792 -0.08893203 0.1049226 -0.007641792 -0.07290184 0.1140381 -0.004873335 -0.09126919 0.1034337 -0.004873335 -0.07047879 0.1093842 -0.004644811 -0.08845031 0.09900832 -0.004644811 -0.07261306 0.1080009 -0.007641792 -0.08618521 0.100165 -0.007641792 -0.07035994 0.1040984 -0.007641792 -0.0839321 0.09626251 -0.007641792 -0.0679019 0.1053779 -0.004873335 -0.08626925 0.09477359 -0.004873335 -0.06547886 0.1007241 -0.004644811 -0.08345037 0.09034818 -0.004644811 -0.06761312 0.09934079 -0.007641792 -0.08118528 0.09150487 -0.007641792 -0.06536 0.09543824 -0.007641792 -0.07893216 0.08760237 -0.007641792 -0.06290197 0.09671777 -0.004873335 -0.08126932 0.08611345 -0.004873335 -0.06047892 0.0920639 -0.004644811 -0.07845044 0.08168804 -0.004644811 -0.06261318 0.09068065 -0.007641792 -0.07618534 0.08284473 -0.007641792 -0.06036007 0.0867781 -0.007641792 -0.07393223 0.07894223 -0.007641792 -0.05790203 0.08805769 -0.004873335 -0.07626938 0.07745331 -0.004873335 -0.05547899 0.08340376 -0.004644811 -0.0734505 0.0730279 -0.004644811 -0.05761325 0.08202046 -0.007641792 -0.07118541 0.07418459 -0.007641792 -0.05536013 0.07811796 -0.007641792 -0.06893229 0.0702821 -0.007641792 -0.0529021 0.07939755 -0.004873335 -0.07126945 0.06879317 -0.004873335 -0.05047905 0.07474362 -0.004644811 -0.06845057 0.06436777 -0.004644811 -0.05261331 0.07336032 -0.007641792 -0.06618547 0.06552445 -0.007641792 -0.0503602 0.06945782 -0.007641792 -0.06393235 0.0616219 -0.007641792 -0.04790216 0.07073736 -0.004873335 -0.06626951 0.06013298 -0.004873335 -0.04547911 0.06608349 -0.004644811 -0.06345063 0.05570763 -0.004644811 -0.04761338 0.06470018 -0.007641792 -0.06118553 0.05686432 -0.007641792 -0.04536026 0.06079769 -0.007641792 -0.05893242 0.05296176 -0.007641792 -0.04261344 0.05604004 -0.007641792 -0.0561856 0.04820418 -0.007641792 -0.0527935 0.04232889 -0.007641792 -0.04290223 0.06207722 -0.004873335 -0.06126958 0.05147284 -0.004873335 -0.04027628 0.05752897 -0.004873335 -0.05864357 0.04692459 -0.004873335 -0.1317384 0.1926087 -0.002641856 -0.1337137 0.191816 -0.002641856 -0.129895 0.1936728 -0.002641856 -0.1282209 0.1949874 -0.002641856 -0.1289315 0.1742037 -0.007641792 -0.1312687 0.1727148 -0.004873335 -0.1153594 0.1820396 -0.007641792 -0.1295045 0.1968679 -0.01850521 -0.1272335 0.1959344 -0.01525521 -0.1277353 0.19896 -0.01850521 -0.122105 0.193974 -0.007760107 -0.1265861 0.2015755 -0.01877653 -0.1257197 0.2040213 -0.01850521 -0.1204654 0.2036482 -0.01100528 -0.1255523 0.2067218 -0.01849639 -0.1259983 0.2094126 -0.01850998 -0.1201404 0.2097294 -0.01026552 -0.1249652 0.2109052 -0.01649838 -0.122694 0.215071 -0.01101946 -0.1214933 0.2125484 -0.01100528 -0.1246286 0.2178093 -0.01100528 -0.1268658 0.220009 -0.01100313 -0.1297821 0.2219563 -0.01100528 -0.1333025 0.2192577 -0.01661682 -0.1328411 0.223251 -0.01100528 -0.1360857 0.2239615 -0.01100528 -0.1372451 0.2188029 -0.01850521 -0.1394058 0.2240639 -0.01100528 -0.1395919 0.2187806 -0.01850521 -0.1415677 0.220762 -0.01525521 -0.1418961 0.2183281 -0.01850527 -0.1423683 0.2196487 -0.01650524 -0.1426882 0.2235544 -0.01100528 -0.1422075 0.2218701 -0.01350528 -0.1450725 0.2208678 -0.01350528 -0.1473346 0.2217504 -0.01097166 -0.1477012 0.2193502 -0.01350528 -0.1512199 0.2186285 -0.01100528 -0.1500017 0.2173702 -0.01350528 -0.1493619 0.2162621 -0.01525521 -0.1533023 0.2160407 -0.01100528 -0.14886 0.2132365 -0.01850521 -0.1470779 0.2153434 -0.0185064 -0.1548738 0.2131143 -0.01100528 -0.1500046 0.2106244 -0.01877623 -0.1558808 0.209949 -0.01100528 -0.1508756 0.2081752 -0.01850521 -0.1562889 0.2066526 -0.01100528 -0.1510289 0.2054396 -0.01850521 -0.1560845 0.2033373 -0.01100528 -0.1515043 0.2009122 -0.01652592 -0.1552743 0.200116 -0.01100528 -0.1538867 0.1970965 -0.01100265 -0.1525093 0.1950967 -0.01108103 -0.1505269 0.1921974 -0.01026368 -0.1449874 0.195142 -0.01844483 -0.145092 0.18943 -0.01100528 -0.1421042 0.1908643 -0.01428198 -0.1393504 0.1933935 -0.01850521 -0.1370035 0.1934158 -0.01850521 -0.1350277 0.1914345 -0.01525521 -0.1347006 0.1938679 -0.01850521 -0.1181278 0.2055783 -0.007756471 -0.1270831 0.2160596 0.01049435 -0.1264952 0.215354 -0.01057648 -0.1253075 0.2135981 0.01049435 -0.1286169 0.2175547 -0.01055753 -0.1293179 0.2181131 0.01049435 -0.1311405 0.2192794 -0.01055538 -0.1319203 0.2196748 0.01049435 -0.133961 0.2204566 -0.01055836 -0.1347838 0.2206806 0.01049435 -0.1369627 0.2210376 -0.01057404 -0.1377911 0.2210895 0.01049435 -0.1400199 0.2209981 -0.01056253 -0.1408191 0.2208846 0.01049435 -0.1430085 0.2203391 -0.01000529 -0.143744 0.2200743 0.01049435 -0.1457976 0.2190884 -0.01000529 -0.1464459 0.218692 0.01049435 -0.1482696 0.217302 -0.01062059 -0.1488143 0.2167938 0.01049435 -0.150329 0.215053 -0.01099503 -0.150752 0.214458 0.01049435 -0.1518996 0.2124198 -0.01055175 -0.1521798 0.2117798 0.01049435 -0.1528986 0.2095311 -0.01055026 -0.1530393 0.208869 0.01049435 -0.1532914 0.2065001 -0.010549 -0.1532954 0.2058449 0.01049435 -0.1530616 0.2034522 -0.01054757 -0.1529374 0.202831 0.01049435 -0.1522185 0.2005141 -0.0105462 -0.15198 0.1999509 0.01049435 -0.1507975 0.197808 -0.01054489 -0.1504625 0.1973226 0.01049435 -0.148855 0.1954429 -0.01000529 -0.148447 0.1950535 0.01049435 -0.1464808 0.1935282 -0.01060813 -0.1460159 0.1932365 0.01049435 -0.1437609 0.1921294 -0.01052707 -0.143269 0.1919462 0.01049435 -0.1408154 0.1913117 -0.01044505 -0.1403183 0.1912352 0.01049435 -0.1377654 0.1911085 -0.01044887 -0.1372851 0.1911327 0.01049435 -0.1342933 0.1916429 0.01049435 -0.1314654 0.1927449 0.01049435 -0.1289172 0.1943935 0.01049435 -0.126753 0.1965214 0.01049435 -0.1255843 0.1981402 -0.01055085 -0.1250616 0.1990414 0.01049435 -0.1242356 0.2008807 -0.01061451 -0.123912 0.2018502 0.01049435 -0.1234688 0.2038405 -0.01000529 -0.1233514 0.204833 0.01049435 -0.1233196 0.2068905 -0.01051586 -0.1234026 0.2078676 0.01049435 -0.1237912 0.2099103 -0.01056647 -0.1240637 0.2108297 0.01049435 -0.1248658 0.212775 -0.01000529 -0.1392366 0.2129374 -0.01834952 -0.1327601 0.2018577 -0.01837778 -0.1412245 0.2060187 -0.01826769 -0.1374716 0.1993497 -0.01841008 -0.1307906 0.2118213 -0.0184406 -0.131542 0.2117515 -0.01651644 -0.1305524 0.2091059 -0.01650422 -0.1307545 0.2070979 -0.01647526 -0.1285147 0.2074466 -0.01623243 -0.1276158 0.2089846 -0.01677799 -0.1260779 0.2060571 -0.01398646 -0.1376056 0.2178993 -0.01490974 -0.1315189 0.2073568 -0.01575523 -0.1312705 0.2071 -0.01171499 -0.1318436 0.2071693 -0.01110577 -0.1305639 0.207025 -0.01113909 -0.1394517 0.2200106 -0.01100909 -0.1392447 0.2202399 -0.01115983 -0.1388977 0.2201935 -0.01228171 -0.1242992 0.2059076 -0.01226592 -0.1249534 0.2099943 -0.01281589 -0.1250978 0.2111106 -0.01114594 -0.1265676 0.2056426 -0.01100528 -0.128337 0.207337 -0.01116156 -0.1242769 0.20549 -0.01101297 -0.1458071 0.2003837 -0.0184558 -0.1450547 0.2004446 -0.01651585 -0.1459144 0.2015515 -0.01650536 -0.1458474 0.2051272 -0.01647341 -0.138848 0.1919943 -0.01210975 -0.1375954 0.1925649 -0.0110808 -0.1382416 0.1928539 -0.01155549 -0.1383379 0.1931693 -0.01343798 -0.1425573 0.1928039 -0.0126143 -0.1431673 0.1929147 -0.01098316 -0.1440456 0.1932668 -0.01250195 -0.1501001 0.1985685 -0.01235461 -0.1512635 0.2006384 -0.0112062 -0.1524718 0.2065296 -0.01101601 -0.1516193 0.2020943 -0.01273089 -0.1522968 0.2062345 -0.01235467 -0.1391253 0.1943097 -0.01529669 -0.1504734 0.206227 -0.01494818 -0.1450765 0.2048397 -0.01575523 -0.1444119 0.2040874 -0.01135939 -0.1448091 0.2058373 -0.01100468 -0.1467706 0.2050051 -0.01127839 -0.1453254 0.2050987 -0.01175528 -0.1488311 0.2050925 -0.01106703 -0.1505556 0.2064438 -0.01103788 -0.1424822 0.2171397 -0.01100528 -0.1448399 0.2182394 -0.01104414 -0.1428275 0.2177379 -0.01350528 -0.14581 0.2175154 -0.01350528 -0.1461294 0.2163941 -0.01102727 -0.1455928 0.2153196 -0.01350528 -0.1441662 0.2146682 -0.01100528 -0.1435003 0.2148466 -0.01350528 -0.1307047 0.2092888 -0.01850503 -0.132547 0.2129404 -0.01850491 -0.1458907 0.2029076 -0.01850503 -0.1336261 0.2191505 -0.01298534 -0.1444867 0.2093436 -0.01850521 -0.1454396 0.206085 -0.01850521 -0.1492698 0.2059499 -0.01850426 -0.1468095 0.2116888 -0.01850503 -0.1356933 0.2198537 -0.0124334 -0.1321087 0.2028526 -0.01850521 -0.1311558 0.2061116 -0.01850521 -0.1273255 0.2062465 -0.01850426 -0.129786 0.2005077 -0.01850503 -0.1274967 0.2063655 -0.01700437 -0.1307644 0.2062235 -0.01700496 -0.1322658 0.2032101 -0.01700437 -0.1294026 0.2004785 -0.01700443 -0.1260119 0.2028822 -0.01700294 -0.1278312 0.2048167 -0.01700365 -0.1294956 0.2053456 -0.01700323 -0.1307861 0.2041686 -0.01700323 -0.1301375 0.2021204 -0.01699906 -0.1276024 0.2026236 -0.01699805 -0.1471928 0.211718 -0.01700443 -0.1443296 0.2089864 -0.01700437 -0.1505834 0.2093143 -0.01700294 -0.1490986 0.2058309 -0.01700437 -0.1458309 0.205973 -0.01700496 -0.1469448 0.2102216 -0.01700323 -0.1457678 0.2089311 -0.01700365 -0.148993 0.2095729 -0.01699805 -0.1484896 0.2070378 -0.01699906 -0.1462967 0.2072666 -0.01700329 -0.1330294 0.2191073 -0.01097321 -0.1364471 0.2019199 -0.01100528 -0.1345465 0.2036126 -0.01100528 -0.1302137 0.2024195 -0.01100528 -0.1286109 0.2020837 -0.0110051 -0.1275188 0.2033039 -0.0110051 -0.1283837 0.2051863 -0.01101273 -0.1306686 0.2043771 -0.01102066 -0.1337379 0.2058429 -0.01102095 -0.1348059 0.2090774 -0.01101964 -0.1387109 0.2107647 -0.01100528 -0.1421348 0.2085813 -0.01100528 -0.146736 0.2101036 -0.01100522 -0.1486939 0.2096491 -0.01100522 -0.14903 0.208047 -0.01100796 -0.1478095 0.2069544 -0.01100349 -0.1459271 0.2078194 -0.0110042 -0.1428122 0.2053804 -0.01100516 -0.1417149 0.2031705 -0.01100528 -0.1397151 0.2017527 -0.01100528 -0.1284498 0.1682895 -0.004644811 -0.1261751 0.169457 -0.007656693 -0.05684077 0.04380196 -0.004873335 -0.03847348 0.05440634 -0.004873335 -0.1376078 0.174701 0.005010426 -0.1431246 0.181189 0.003950178 -0.135261 0.1721162 0.0055902 -0.1343234 0.1757265 0.007326126 -0.1409332 0.1870834 0.009497761 -0.14864 0.1894133 0.004883766 -0.1465894 0.189258 0.006944119 -0.1516599 0.1938689 0.007144391 -0.1473588 0.1906155 0.009806573 -0.1509137 0.1931302 0.01000332 -0.1386608 0.1878203 0.009924173 -0.1330543 0.1861593 0.009044468 -0.1295129 0.1914783 0.01046335 -0.134688 0.1894996 0.01047307 -0.1284565 0.1890712 0.009382843 -0.1235496 0.1915732 0.009011745 -0.1220083 0.1971265 0.009803116 -0.1245751 0.1959468 0.01047462 -0.1204414 0.2015172 0.009714841 -0.1200314 0.1967859 0.008951544 -0.1181878 0.2003424 0.006142795 -0.05205506 0.07217872 -5.23031e-5 -0.05288535 0.07213574 -4.91907e-4 -0.05316805 0.06983053 -4.36984e-4 -0.06498897 0.06514775 -4.91907e-4 -0.06242007 0.06431835 -9.8086e-5 -0.05510848 0.07598632 -4.91907e-4 -0.06782782 0.06939077 -4.90816e-4 -0.0669291 0.07130217 -4.69379e-4 -0.05295532 0.06965196 0.007020592 -0.05178731 0.07220274 0.00701034 -0.06236243 0.06406259 0.007064759 -0.06542664 0.06442791 -3.81853e-5 -0.06553232 0.06419473 0.00702548 -0.06786119 0.06862354 2.31909e-4 -0.06829488 0.06889992 0.00702238 -0.06714659 0.07148522 0.007160961 -0.05767738 0.07681566 -9.80903e-5 -0.05773448 0.07707005 0.007020592 -0.05467075 0.07670587 -4.49459e-5 -0.05456495 0.07693928 0.00702697 -0.06863945 0.07507693 -4.82309e-4 -0.05945801 0.07988411 -9.53549e-5 -0.05806899 0.08255654 -4.90583e-4 -0.06841665 0.07469886 2.31909e-4 -0.05913621 0.07980102 0.007021725 -0.06836241 0.07445478 0.00706464 -0.07142645 0.07482016 -4.09776e-5 -0.0721004 0.07746517 -4.91907e-4 -0.074036 0.07934391 -1.14472e-4 -0.0636146 0.08722698 -4.91688e-4 -0.07292854 0.08169466 -4.69052e-4 -0.07153224 0.07458686 0.00702548 -0.0742948 0.07929205 0.00702238 -0.07314664 0.08187741 0.007163226 -0.06373441 0.08746224 0.007020592 -0.06067073 0.08709836 -3.81678e-5 -0.06056505 0.08733141 0.007021129 -0.05779927 0.08262062 0.007021248 -0.06833791 0.09776341 -4.9156e-4 -0.07864499 0.0924223 -9.57143e-5 -0.08003336 0.08976298 -4.90594e-4 -0.06968051 0.09761172 2.31909e-4 -0.06667089 0.09749007 -5.02528e-5 -0.07698881 0.08593207 -4.91907e-4 -0.06435471 0.09179753 -4.91953e-4 -0.07883745 0.09259873 0.007020592 -0.06973683 0.09785956 0.007171809 -0.06656503 0.09772354 0.007021129 -0.06405991 0.09296673 -8.2267e-5 -0.06380242 0.09301853 0.00702238 -0.06515437 0.09061187 -1.88129e-4 -0.06495517 0.09043627 0.007020592 -0.07441991 0.08510273 -9.80871e-5 -0.07436227 0.08484691 0.007064759 -0.07742649 0.08521229 -3.8174e-5 -0.07753199 0.08497911 0.007019639 -0.0803008 0.08969503 0.007021665 -0.07266813 0.1078785 -3.76923e-5 -0.07546615 0.1080785 7.91635e-6 -0.07544207 0.1076548 -4.28287e-4 -0.07310825 0.1071629 -4.91907e-4 -0.0702694 0.1029195 -4.90905e-4 -0.07023602 0.1036871 2.31909e-4 -0.08602118 0.1001346 -4.93432e-4 -0.08298873 0.09632426 -4.91907e-4 -0.07116699 0.1010076 -4.37516e-4 -0.07573425 0.1082466 0.007020592 -0.07256501 0.1081157 0.007020771 -0.06980228 0.1034107 0.00702238 -0.07095509 0.1008285 0.007020592 -0.08041983 0.09549486 -9.80836e-5 -0.08036237 0.09523904 0.007063567 -0.08342641 0.09560441 -3.81903e-5 -0.08353221 0.0953713 0.007026314 -0.08629465 0.1000764 0.00702238 -0.08494353 0.1024832 -1.7058e-4 -0.08514821 0.1026646 0.007236897 -0.07866013 0.1182572 -4.04136e-5 -0.08146607 0.1184707 7.91635e-6 -0.08144199 0.1180469 -4.28287e-4 -0.07910817 0.117555 -4.91907e-4 -0.07626932 0.1133116 -4.90905e-4 -0.07623594 0.1140792 2.31909e-4 -0.0920211 0.1105268 -4.93432e-4 -0.08898866 0.1067164 -4.91907e-4 -0.07716691 0.1113998 -4.37518e-4 -0.08129417 0.1187363 0.007020592 -0.07855355 0.1184891 0.007023394 -0.07580226 0.1138026 0.007018923 -0.07695347 0.1112161 0.00714755 -0.08641976 0.1058871 -9.81255e-5 -0.08636265 0.1056327 0.007020592 -0.08942627 0.1059966 -3.82163e-5 -0.08953195 0.1057636 0.007021129 -0.09229457 0.1104686 0.00702238 -0.09094345 0.1128754 -1.70578e-4 -0.09114491 0.1130515 0.007100045 -0.08466005 0.1286494 -4.04166e-5 -0.087466 0.1288629 7.91635e-6 -0.08744192 0.1284391 -4.28287e-4 -0.0851081 0.1279472 -4.91907e-4 -0.08226925 0.1237038 -4.90905e-4 -0.08223587 0.1244714 2.31909e-4 -0.09802103 0.1209189 -4.93432e-4 -0.09498858 0.1171085 -4.91907e-4 -0.08316683 0.121792 -4.37523e-4 -0.0872941 0.1291285 0.007020592 -0.08455359 0.1288813 0.007023394 -0.08180212 0.124195 0.00702238 -0.08295148 0.1216083 0.007172644 -0.09241962 0.1162793 -9.81276e-5 -0.09236258 0.1160249 0.007020592 -0.0954262 0.1163887 -3.82065e-5 -0.09553182 0.1161557 0.007021129 -0.09829449 0.1208608 0.00702238 -0.09694337 0.1232675 -1.7056e-4 -0.09714484 0.1234437 0.007100045 -0.09065997 0.1390416 -4.04175e-5 -0.09346592 0.1392551 7.91635e-6 -0.09344184 0.1388313 -4.28287e-4 -0.09110802 0.1383394 -4.91907e-4 -0.08826917 0.1340959 -4.90905e-4 -0.08823579 0.1348635 2.31909e-4 -0.1040209 0.131311 -4.93432e-4 -0.1009885 0.1275007 -4.91907e-4 -0.08916676 0.132184 -4.37505e-4 -0.09329402 0.1395207 0.007020592 -0.09055346 0.1392734 0.007023394 -0.08780217 0.1345869 0.007018923 -0.08895331 0.1320004 0.00714761 -0.09841954 0.1266714 -9.81321e-5 -0.0983625 0.1264171 0.007020592 -0.1014261 0.1267809 -3.82639e-5 -0.1015317 0.1265479 0.007021129 -0.1042944 0.131253 0.00702238 -0.1029433 0.1336597 -1.70571e-4 -0.1031447 0.1338359 0.007098019 -0.09665989 0.1494337 -4.04123e-5 -0.09946584 0.1496472 7.91635e-6 -0.09944182 0.1492235 -4.28285e-4 -0.09710794 0.1487315 -4.91907e-4 -0.09426909 0.1444881 -4.90905e-4 -0.09423571 0.1452557 2.31909e-4 -0.1100208 0.1417032 -4.93432e-4 -0.1069884 0.1378929 -4.91907e-4 -0.09516668 0.1425763 -4.37516e-4 -0.09929394 0.1499128 0.007020592 -0.09655344 0.1496656 0.007023394 -0.09380197 0.1449794 0.00702238 -0.09495478 0.1423971 0.007020592 -0.1044195 0.1370636 -9.81235e-5 -0.1043619 0.1368077 0.007064759 -0.107426 0.1371731 -3.82748e-5 -0.1075316 0.13694 0.007019639 -0.1102943 0.1416453 0.007018923 -0.1089432 0.1440519 -1.70579e-4 -0.1091437 0.1442295 0.007125198 -0.1026598 0.1598259 -4.03974e-5 -0.1054658 0.1600394 7.91635e-6 -0.1054417 0.1596156 -4.28286e-4 -0.1031078 0.1591237 -4.91907e-4 -0.100269 0.1548803 -4.90905e-4 -0.1002356 0.1556478 2.31909e-4 -0.1160207 0.1520953 -4.93432e-4 -0.1129883 0.148285 -4.91907e-4 -0.1011666 0.1529685 -4.37533e-4 -0.1052939 0.160305 0.007020592 -0.1025533 0.1600577 0.007023394 -0.09980195 0.1553716 0.00702238 -0.1009547 0.1527893 0.007020592 -0.1104194 0.1474558 -9.81334e-5 -0.110362 0.1471998 0.007063567 -0.1134259 0.1475652 -3.82636e-5 -0.1135315 0.1473322 0.007020771 -0.1162943 0.1520373 0.00702238 -0.1149431 0.154444 -1.70582e-4 -0.1151446 0.1546202 0.007098019 -0.1086677 0.1702315 -3.76868e-5 -0.1114658 0.1704316 7.91635e-6 -0.1114417 0.1700078 -4.28286e-4 -0.1091077 0.1695159 -4.91907e-4 -0.106269 0.1652725 -4.90905e-4 -0.1062355 0.16604 2.31909e-4 -0.1220207 0.1624875 -4.93432e-4 -0.1189882 0.1586772 -4.91907e-4 -0.1071665 0.1633606 -4.37531e-4 -0.1117337 0.1705996 0.007020592 -0.1085644 0.1704687 0.007021129 -0.1058019 0.1657634 0.007018923 -0.1069546 0.1631814 0.007020592 -0.1164194 0.157848 -9.81429e-5 -0.116361 0.1575914 0.007087647 -0.1194258 0.1579574 -3.82606e-5 -0.1195316 0.1577242 0.00702548 -0.1222941 0.1624295 0.00702238 -0.120943 0.1648363 -1.70541e-4 -0.1211458 0.1650153 0.007163286 -0.1163372 0.1809008 -4.9156e-4 -0.1266443 0.1755596 -9.57174e-5 -0.1280327 0.1729003 -4.90594e-4 -0.1176798 0.180749 2.31909e-4 -0.1146702 0.1806275 -5.02426e-5 -0.1249881 0.1690695 -4.91907e-4 -0.1123541 0.1749348 -4.91953e-4 -0.1268368 0.1757361 0.007020592 -0.1145644 0.1808609 0.007021129 -0.1120593 0.1761041 -8.22921e-5 -0.1118018 0.1761558 0.00702238 -0.1131538 0.1737492 -1.88115e-4 -0.1129545 0.1735736 0.007020592 -0.1224192 0.1682401 -9.81433e-5 -0.1223617 0.1679843 0.007064759 -0.1254258 0.1683495 -3.82685e-5 -0.1255313 0.1681165 0.007019639 -0.1283011 0.1728317 0.007048547 -0.1206634 0.1910012 -4.59922e-5 -0.1234656 0.1912159 7.91635e-6 -0.1234415 0.1907921 -4.28287e-4 -0.1199961 0.1883749 -4.91907e-4 -0.1180617 0.1864933 -1.1187e-4 -0.119166 0.1841453 -4.38222e-4 -0.1340152 0.1832839 -4.9344e-4 -0.1309881 0.1794617 -4.91907e-4 -0.1178036 0.186545 0.007009565 -0.1189544 0.1839658 0.007020592 -0.1284192 0.1786323 -9.81415e-5 -0.1283618 0.1783763 0.007063627 -0.1314244 0.1787418 -3.96826e-5 -0.1315294 0.1785091 0.007009804 -0.1329494 0.1856114 -1.65338e-4 -0.06622111 0.04520523 0.002919375 -0.07490777 0.06306844 0.003962278 -0.07250124 0.06208693 0.004670202 -0.07537394 0.0648778 0.00431317 -0.07497692 0.06846362 0.005726158 -0.08374106 0.08044433 0.004689157 -0.080832 0.07577008 0.004816412 -0.08199638 0.07899779 0.005152046 -0.07955169 0.07714831 0.005957722 -0.07856851 0.07915103 0.006947755 -0.08497714 0.08421063 0.005261838 -0.09288728 0.09767091 0.005173981 -0.09133648 0.09557801 0.00539726 -0.09480839 0.1024385 0.005680441 -0.1023392 0.1147323 0.005415618 -0.09932392 0.1110767 0.005905747 -0.1007764 0.1137208 0.005931437 -0.09425538 0.1053871 0.006973147 -0.093019 0.1052516 0.007823705 -0.103993 0.119612 0.005960524 -0.1062862 0.1224792 0.005734324 -0.112095 0.1316246 0.00541377 -0.1085561 0.127528 0.005953729 -0.110964 0.1315011 0.005928993 -0.1148322 0.1370398 0.005650341 -0.12215 0.1483395 0.005168378 -0.1194985 0.1459428 0.005744934 -0.1087495 0.131594 0.0074597 -0.1158152 0.1396394 0.005871236 -0.1245289 0.1540513 0.005579948 -0.1268488 0.1567289 0.005256056 -0.1324937 0.1648609 0.004680216 -0.1294018 0.1645997 0.006528615 -0.06249117 0.04779517 0.006144404 -0.1283159 0.1888092 0.008779823 -0.1552743 0.200116 0.009994387 -0.153886 0.1970983 0.009994387 -0.1539656 0.1989271 0.01049453 -0.1560845 0.2033373 0.009994387 -0.1555866 0.2072598 0.01049482 -0.1562889 0.2066526 0.009994387 -0.1548738 0.2131143 0.009994387 -0.1530687 0.2146263 0.01049435 -0.1504184 0.2195206 0.009988546 -0.1461129 0.221762 0.0104956 -0.1394058 0.2240639 0.009994387 -0.1332537 0.2228629 0.01049554 -0.1270132 0.2201215 0.009994387 -0.1241704 0.2161422 0.01049482 -0.1209027 0.2112046 0.01000058 -0.1211941 0.2082993 0.01049351 -0.1214605 0.2024461 0.01049315 -0.1413367 0.189164 0.01049453 -0.1489278 0.1924686 0.0104959 -0.1227094 0.2150981 0.009994387 -0.1246286 0.2178093 0.009994387 -0.1297821 0.2219563 0.009994387 -0.1328411 0.223251 0.009994387 -0.1360857 0.2239615 0.009994387 -0.143898 0.2232956 0.009996354 -0.1529087 0.2166835 0.009783625 -0.1558808 0.209949 0.009994387 -0.1559495 0.2099902 -0.009505212 -0.156245 0.2042854 -0.009480535 -0.1541457 0.2146325 -0.009505331 -0.1512688 0.2186872 -0.009505212 -0.1472976 0.2216865 -0.009505331 -0.1427145 0.2236261 -0.009505212 -0.1377645 0.22409 -0.009505331 -0.132842 0.223331 -0.009505212 -0.1276043 0.2206268 -0.009476065 -0.1220513 0.2138472 0.003033339 -0.1214933 0.2125484 0.003149688 -0.1279496 0.2208261 -0.003559112 -0.1298663 0.2220197 1.25831e-4 -0.1316498 0.2228254 0.002259373 -0.1349496 0.2237923 0.005108892 -0.1394053 0.2241416 0.007491409 -0.1447763 0.2229067 0.008839786 -0.1488691 0.2207533 0.008966982 -0.1556899 0.2107976 0.004190564 -0.15447 0.2140598 0.006451249 -0.1563015 0.2072038 6.9479e-4 -0.1562265 0.2045005 -0.003559112 -0.1560465 0.2031033 -0.007356464 -0.1531317 0.195903 0.003033339 -0.1257159 0.1541092 -3.37208e-4 -0.1164923 0.1390177 -3.37208e-4 -0.1075185 0.1237869 -3.37208e-4 -0.09879404 0.1084167 -3.37208e-4 -0.09031879 0.09290748 -3.37208e-4 -0.0820927 0.07725918 -3.37208e-4 -0.07411551 0.06147193 -3.37208e-4 -0.06638753 0.04554671 -3.3068e-4 -0.1185612 0.20647 0.004730224 -0.1207898 0.2108899 0.006773829 -0.1196411 0.2034589 0.007270932 -0.1281336 0.1597089 -8.69845e-4 -0.07313001 0.06353873 -0.001374959 -0.1293556 0.1633211 -0.001393735 -0.1288367 0.1642583 -0.001478016 -0.1260696 0.1581088 -0.001387298 -0.1236488 0.1542338 -0.001397728 -0.1207987 0.1496236 -0.001437783 -0.1184387 0.1457576 -0.001397192 -0.1155494 0.1409847 -0.001396536 -0.113315 0.1372524 -0.001393079 -0.110251 0.1320829 -0.001409232 -0.1081477 0.1284981 -0.001421511 -0.1053645 0.1237007 -0.001393377 -0.1023001 0.1164796 -8.54201e-4 -0.1031643 0.1198683 -0.001407921 -0.1001704 0.1145955 -0.001410365 -0.09813314 0.1109766 -0.001396238 -0.124947 0.1577993 -0.001495063 -0.09537506 0.1060065 -0.001397073 -0.09321236 0.1020767 -0.001420855 -0.09053146 0.09714603 -0.00142616 -0.08857685 0.09352064 -0.001394033 -0.08558058 0.08787471 -0.001395642 -0.08345788 0.08384841 -0.001443386 -0.08131945 0.07973396 -0.00140661 -0.07930225 0.07580959 -0.001387298 -0.07893824 0.07683783 -0.001492798 -0.07600671 0.06932651 -0.001390755 -0.07381784 0.06536269 -0.001491844 -0.07228648 0.06234347 -0.001491844 -0.06314957 0.04340517 -0.001490235 -0.06317406 0.04225146 -0.001196861 -0.06189763 0.04001367 -0.001306772 -0.09534549 0.1054401 0.005522429 -0.09435248 0.1059706 -0.001491367 -0.09836435 0.1109169 0.00506854 -0.09693449 0.1116675 -0.00149852 -0.1034251 0.119863 0.005136311 -0.1002992 0.1143628 0.0050987 -0.1054888 0.1234533 0.005144715 -0.1043429 0.1236805 -0.00149095 -0.1085025 0.1286529 0.005138576 -0.1078975 0.1294785 0.006535291 -0.1066108 0.1290913 -0.001493394 -0.1103789 0.1318497 0.005119442 -0.1136015 0.1372582 0.005484402 -0.1153852 0.1402776 0.005022764 -0.1145531 0.1409718 -0.001491904 -0.1188284 0.1459718 0.004933714 -0.1178274 0.1466791 -0.001490712 -0.120924 0.1493676 0.005353033 -0.1239036 0.1542364 0.004758954 -0.1259143 0.1574365 0.005043745 -0.1298906 0.1637371 0.004991948 -0.1264902 0.1639968 -0.001491844 -0.09602522 0.1112354 -0.001491844 -0.09392881 0.1076043 -0.001491844 -0.09139543 0.1032162 -0.001491844 -0.0884549 0.09812319 -0.001491844 -0.0859254 0.09374195 -0.001491844 -0.08382892 0.09011077 -0.001491844 -0.08129554 0.0857228 -0.001491844 -0.07835501 0.0806297 -0.001491844 -0.07582551 0.07624846 -0.001491844 -0.07356083 0.07232642 -0.001491904 -0.07119566 0.06822931 -0.001491844 -0.06807971 0.06282985 -0.001491844 -0.06267648 0.04507404 -0.001491844 -0.0686475 0.06205701 -0.001491844 -0.0722264 0.06861919 -0.00149244 -0.0748986 0.06934738 -0.001491963 -0.07617771 0.07656192 -0.001491844 -0.07851332 0.07954782 -0.00149244 -0.08373355 0.08964896 -0.001491844 -0.08227622 0.08618271 -0.001490235 -0.08450436 0.08789169 -0.001491785 -0.08645278 0.09409165 -0.001492857 -0.08860272 0.09706008 -0.001492798 -0.09383344 0.1071425 -0.001491844 -0.09238636 0.1036068 -0.001493692 -0.09855479 0.1156167 -0.001491844 -0.1014953 0.1207098 -0.001491844 -0.1040287 0.1250978 -0.001491844 -0.1039333 0.1246359 -0.001491844 -0.102459 0.1210943 -0.001496076 -0.09868782 0.1145803 -0.001492857 -0.1061251 0.1287289 -0.001491844 -0.1086547 0.1331101 -0.001491844 -0.1115952 0.1382033 -0.001491844 -0.113974 0.1423242 -0.001491904 -0.1125655 0.1386063 -0.001492857 -0.1087352 0.132107 -0.001495599 -0.116225 0.1462224 -0.001491844 -0.1187545 0.1506036 -0.001491844 -0.121695 0.1556968 -0.001491844 -0.1240649 0.159802 -0.001491904 -0.1227059 0.1560793 -0.001494944 -0.1165773 0.1465359 -0.001491844 -0.1188547 0.1495609 -0.001495599 -0.08588057 0.1411566 0.005220174 -0.08291989 0.1359952 0.005149126 -0.08353984 0.135154 0.006687641 -0.08106106 0.1327957 0.005137562 -0.07783126 0.1273239 0.005518913 -0.07577216 0.1238201 0.005074441 -0.07250064 0.118355 0.005018889 -0.07512921 0.1178176 0.007028043 -0.07061874 0.1152917 0.005493342 -0.06754058 0.1102463 0.005285203 -0.06564605 0.1071398 0.004776656 -0.06191289 0.1011828 0.004965782 -0.05972027 0.09771609 0.005051314 -0.05513292 0.09051573 0.004627346 -0.05616849 0.09037613 0.005716621 -0.05054903 0.08342456 0.003997802 -0.03073853 0.0514723 -0.006052792 -0.02904289 0.04565376 -0.02124994 -0.03135526 0.05230367 -0.006772816 -0.02975231 0.04673838 -0.02125513 -0.03233432 0.05281645 -0.007355868 -0.0308482 0.04747772 -0.02125513 -0.03351289 0.0529254 -0.007705032 -0.03211474 0.04768145 -0.02125513 -0.0336191 0.05996966 0.005145013 -0.02833634 0.04587984 0.005319595 -0.05702924 0.03972715 -0.007755339 -0.05803853 0.03876554 -0.007705032 -0.05853343 0.0376904 -0.007355868 -0.05857884 0.0365861 -0.006772816 -0.05816727 0.0356363 -0.006052792 -0.03379642 0.03895902 -0.02125513 -0.03489792 0.04429346 -0.02125513 -0.03293287 0.04563343 -0.02125513 -0.03130269 0.0452044 -0.02125513 -0.02863907 0.04374754 -0.02125513 -0.03015077 0.04368972 -0.02125513 -0.02892291 0.04200786 -0.02125513 -0.03038018 0.04201972 -0.02125513 -0.02979284 0.04047441 -0.02125513 -0.03174495 0.04069364 -0.02125513 -0.0341044 0.04099369 -0.02125513 -0.03504008 0.04239588 -0.02125513 -0.0425207 0.05587941 -0.002104878 -0.155661 0.2032027 -0.006680071 -0.1557784 0.2071298 -0.009572207 -0.1553771 0.2099111 -0.009505331 -0.1546906 0.2122231 -0.009505331 -0.1531328 0.2154462 -0.009512484 -0.1499 0.2192426 -0.009511828 -0.1460317 0.2218427 -0.009504616 -0.142589 0.2230637 -0.009505331 -0.1390169 0.2236256 -0.009505093 -0.1354056 0.2233574 -0.009505331 -0.1330602 0.2227959 -0.009505331 -0.1308142 0.2219172 -0.009505331 -0.1287103 0.220738 -0.009505331 -0.1274314 0.219941 -0.008558928 -0.1282299 0.2204118 -0.003543138 -0.1297767 0.2213834 -4.94574e-4 -0.1318274 0.2223579 0.002251505 -0.1343663 0.2231507 0.004597306 -0.1382558 0.223613 0.006963193 -0.1413776 0.2233502 0.00812751 -0.1447272 0.2223973 0.008847117 -0.147835 0.2207952 0.00899285 -0.1443593 0.2230573 -0.004073441 -0.1492875 0.2204656 -0.004041373 -0.1456092 0.2220764 -0.004158914 -0.1447137 0.2224267 0.00218749 -0.1486673 0.2208662 0.001281201 -0.1482676 0.2204989 0.001921296 -0.1497373 0.2193561 -0.002487242 -0.1468669 0.2213969 -0.005515038 -0.1440987 0.2226086 -0.005503296 -0.1440987 0.2226086 -0.001553118 -0.1483023 0.2205757 4.56418e-4 -0.1423739 0.2236909 0.002416014 -0.1372964 0.2241892 -0.001167595 -0.1393014 0.2240385 -0.001224935 -0.1423821 0.2236507 -0.00412482 -0.1427987 0.2230734 -0.001456797 -0.1375333 0.2236486 -0.004649937 -0.1371466 0.2241845 -0.005421996 -0.1407216 0.223545 -0.001556754 -0.1364647 0.2235018 -0.001502096 -0.1404089 0.2234981 0.001988291 -0.1429936 0.2229562 0.00251913 -0.1410013 0.2233977 -0.005490183 -0.1540017 0.2139784 0.001533865 -0.1538578 0.2151929 0.00230956 -0.1545322 0.2139269 -0.001301288 -0.1528122 0.2163939 -0.002609848 -0.1542248 0.2146196 -0.005422592 -0.1542861 0.2132126 -0.005530059 -0.1529753 0.2156418 -0.005179524 -0.151025 0.218982 -0.001653432 -0.1515529 0.2175757 -0.002207219 -0.1509159 0.2182588 0.00224924 -0.1508993 0.2190387 0.0018453 -0.1530771 0.2157504 0.001178801 -0.1557955 0.2063614 -4.94575e-4 -0.1556141 0.2086246 0.002251505 -0.1552066 0.2105546 0.004037797 -0.1545472 0.212594 0.005601525 -0.1508923 0.2182897 -0.004268229 -0.1504368 0.2187379 0.008602619 -0.1531423 0.2154608 0.007320165 -0.1375181 0.2236635 0.001584529 -0.06323981 0.04286813 0.006144404 -0.06408596 0.04237961 0.005145013 -0.06347024 0.04722988 0.006144404 -0.03021615 0.04391551 0.006144404 -0.03058445 0.04154956 0.006357133 -0.02873831 0.04353052 0.00614345 -0.03223776 0.04062384 0.006144404 -0.03081208 0.04068201 0.006144404 -0.04875558 0.03032237 0.006144404 -0.04770052 0.03201985 0.006144404 -0.04845726 0.031093 0.006144404 -0.05002069 0.0305227 0.006317913 -0.03343045 0.0407201 0.006144404 -0.04753643 0.03391563 0.006144404 -0.03479385 0.0417115 0.006144404 -0.04926103 0.03555351 0.006144404 -0.03508824 0.04359149 0.006144404 -0.05470043 0.04414403 0.006144404 -0.05158871 0.03506457 0.006144404 -0.05584889 0.04291009 0.006144404 -0.05240851 0.03359162 0.006144404 -0.05822592 0.04299241 0.006144404 -0.05390578 0.03126114 0.006144404 -0.05211412 0.03171163 0.006144404 -0.05335259 0.02949029 0.005783796 -0.04043036 0.05284434 0.006144404 -0.05446106 0.04531639 0.006144404 -0.04179376 0.05383569 0.006144404 -0.05519676 0.04707127 0.006144404 -0.04208815 0.05571568 0.006144404 -0.0567578 0.04770761 0.006144404 -0.04157519 0.05679672 0.006144404 -0.05858862 0.04718875 0.006144404 -0.0595085 0.04499542 0.006144404 -0.03426843 0.04506444 0.006144404 -0.03738009 0.0541439 0.006144404 -0.03852862 0.05290997 0.006144404 -0.03194075 0.04555338 0.006144404 -0.02908027 0.04559415 0.006144404 -0.03444713 0.05944365 0.006144583 -0.03721606 0.05603969 0.006144404 -0.03894072 0.05767756 0.006144404 -0.03817754 0.06182938 0.006144404 -0.04061859 0.05751556 0.006144404 -0.05452513 0.03075975 0.005319595 -0.05170047 0.02887523 0.005144715 -0.04994499 0.02885222 0.005144536 -0.02784091 0.04422146 0.005144894 -0.02897447 0.04095959 0.005144536 -0.02811664 0.04249131 0.005144715 -0.04926103 0.03555351 -0.01625519 -0.04753643 0.03391563 -0.01625519 -0.05158871 0.03506457 -0.01625519 -0.05240851 0.03359162 -0.01625519 -0.05211412 0.03171163 -0.01625519 -0.05004763 0.03053414 -0.01625519 -0.04790467 0.0315659 -0.01625519 -0.04955893 0.03458672 -0.01625567 -0.04846417 0.03349226 -0.01625561 -0.05105739 0.03418356 -0.01625508 -0.05145031 0.03270179 -0.01624691 -0.05070906 0.03179252 -0.01625519 -0.05017268 0.03159737 -0.0162301 -0.04888123 0.03201556 -0.01624238 -0.03087663 0.04494702 -0.01625519 -0.03243762 0.0455833 -0.01625519 -0.03426843 0.04506444 -0.01625519 -0.03508824 0.04359149 -0.01625519 -0.03479385 0.0417115 -0.01625519 -0.03343045 0.0407201 -0.01625519 -0.03152871 0.04078578 -0.01625519 -0.03011065 0.04269528 -0.01625519 -0.03223866 0.04458659 -0.01625567 -0.0311439 0.04349213 -0.01625561 -0.03373712 0.04418343 -0.01625508 -0.03413009 0.04270172 -0.01624691 -0.03338879 0.04179239 -0.01625519 -0.03285241 0.04159724 -0.0162301 -0.03156095 0.04201543 -0.01624238 -0.03715068 0.0558139 0.001144468 -0.03777343 0.05347973 0.001220703 -0.03996151 0.05267709 0.001144468 -0.04191124 0.05403923 0.001144468 -0.04206621 0.05574369 0.001293659 -0.04108041 0.05732983 0.001144468 -0.03871756 0.05759483 0.001302421 -0.05447095 0.04581409 0.001144468 -0.05504179 0.04352253 0.00112158 -0.05655115 0.04276204 0.001292467 -0.05842459 0.04311805 0.001144468 -0.05935329 0.04453593 0.001350939 -0.0592181 0.04641777 0.001144468 -0.05788379 0.04751998 0.001290261 -0.05603802 0.04760324 0.001144468 -0.04747104 0.03368991 0.001144468 -0.04805332 0.03138381 0.001144468 -0.05028194 0.03055304 0.001144468 -0.0517621 0.03135979 0.001144468 -0.05251801 0.03310608 0.001144468 -0.05140078 0.03520578 0.001144468 -0.04903811 0.03547906 0.001144468 -0.04848796 0.03348594 0.001133918 -0.04886418 0.03199803 0.001145064 -0.05032438 0.03159457 0.001145184 -0.0511412 0.0321272 0.001136422 -0.05145281 0.03331589 0.001096606 -0.05104249 0.03416287 0.001128554 -0.04956555 0.03456294 0.001130878 -0.03015077 0.04368972 0.001144468 -0.03038018 0.04201972 0.001144468 -0.03174495 0.04069364 0.001144468 -0.0341044 0.04099369 0.001144468 -0.03519773 0.04310595 0.001144468 -0.03457528 0.04467254 0.001144468 -0.03293287 0.04563343 0.001144468 -0.03130269 0.0452044 0.001144468 -0.03116768 0.04348582 0.001133918 -0.03154385 0.0419979 0.001145064 -0.03300416 0.04159444 0.001145184 -0.03382092 0.04212707 0.001136422 -0.03413254 0.04331576 0.001096606 -0.03372222 0.0441628 0.001128554 -0.03224521 0.04456281 0.001130878 -0.03963869 0.05521565 2.43242e-4 -0.05695897 0.04521578 2.43242e-4 -0.03118968 0.0427041 -0.007555305 -0.03157854 0.04415243 -0.007555365 -0.03303152 0.04453909 -0.007555544 -0.03403675 0.04254764 -0.00833553 -0.03224146 0.04164505 -0.007552802 -0.04850995 0.03270423 -0.007555305 -0.04889881 0.03415256 -0.007555365 -0.05035185 0.03453922 -0.007555544 -0.05135703 0.03254777 -0.00833553 -0.04956179 0.03164517 -0.007552802 -0.1162462 0.1467746 0.007020175 -0.1136494 0.1423566 0.007017433 -0.1054348 0.1703067 0.007041513 -0.108059 0.1747729 0.007017433 -0.09367495 0.1526449 0.006727635 -0.0953626 0.1528617 0.007020413 -0.0979591 0.1572794 0.007017433 -0.09604644 0.1117877 0.007020175 -0.09344506 0.1073614 0.007017612 -0.08833104 0.09453928 0.006250023 -0.08589607 0.09420984 0.007023572 -0.08332455 0.08983278 0.007022976 -0.07579618 0.07671636 0.007023572 -0.07339423 0.07263189 0.007020592 -0.07775938 0.1222924 0.007017433 -0.05843067 0.09057623 0.006380856 -0.05934721 0.09054303 0.007234573 -0.06309354 0.0968911 0.007020592 -0.05493009 0.08282691 0.007089376 -0.05760133 0.08737134 0.007106304 -0.06503468 0.1003315 0.007044255 -0.06768965 0.1048489 0.007049143 -0.05299365 0.07939761 0.007020592 -0.05303961 0.08006018 0.007050096 -0.05222636 0.0804854 0.00619173 -0.04832118 0.08008742 0.004400849 -0.06852912 0.1081087 0.006285011 -0.08546376 0.1356375 0.007020592 -0.0878632 0.1397979 0.007018327 -0.09349536 0.1020829 0.005472958 -0.09066748 0.09689557 0.005328655 -0.09256929 0.1040543 0.006271183 -0.0837028 0.08385533 0.004607141 -0.08143335 0.07951116 0.00440669 -0.08242738 0.08667647 0.006430089 -0.07415372 0.06517046 0.004321932 -0.07240396 0.06906288 0.006355285 -0.0469554 0.05925977 0.007020592 -0.05636304 0.05367183 0.007020592 -0.05953288 0.05380314 0.007019996 -0.1089105 0.1780821 0.006348848 -0.09785145 0.1626881 0.005394816 -0.1005862 0.1677111 0.004768073 -0.08964633 0.1430225 0.00723499 -0.08878231 0.1430474 0.006357669 -0.09339314 0.1493715 0.007020592 -0.0934391 0.1500341 0.007050096 -0.09093755 0.1502854 0.00561285 -0.1035398 0.1248461 0.007018268 -0.1118584 0.1391133 0.007235109 -0.1081117 0.1327642 0.007020592 -0.1080508 0.1320956 0.007272601 -0.1179885 0.149849 0.007006108 -0.1237446 0.1598418 0.007017612 -0.121734 0.1565791 0.007391989 -0.1061573 0.1292999 0.007021069 -0.1100708 0.1780364 0.007385492 -0.1070808 0.1772314 0.006577074 -0.1024172 0.1713134 0.004969537 -0.1057244 0.1775798 0.004784524 -0.1036607 0.1669387 0.007384955 -0.09996664 0.1605405 0.007385194 -0.08795768 0.1447934 0.005120694 -0.09784406 0.1151972 0.007384955 -0.1015381 0.1215952 0.007385253 -0.08774423 0.09770363 0.007384955 -0.0882765 0.09668606 0.006269812 -0.09143829 0.1041017 0.007385253 -0.08902937 0.09386414 0.005247831 -0.0855779 0.08722126 0.005175411 -0.08440774 0.08378618 0.005370616 -0.0843656 0.08740484 0.006462872 -0.07771772 0.08033829 0.007384419 -0.08132314 0.08636701 0.007043123 -0.08016997 0.07583868 0.004921555 -0.07959258 0.07594621 0.004216372 -0.07619696 0.0690751 0.00455445 -0.08346098 0.1319516 0.007384955 -0.07976686 0.1255536 0.007385194 -0.07534563 0.1239798 0.005773186 -0.07336109 0.1144582 0.007384955 -0.07283341 0.1154693 0.006256818 -0.06966704 0.1080601 0.007385194 -0.06282782 0.09802132 0.006807863 -0.05031543 0.08402061 0.004656791 -0.06754451 0.06271672 0.007384955 -0.07123851 0.06911468 0.007385253 -0.04825413 0.07301902 0.006730616 -0.0494821 0.07331544 0.007020592 -0.1354053 0.2095453 -0.01350528 -0.1373705 0.2105672 -0.01350528 -0.140495 0.2101019 -0.01350528 -0.1425713 0.2077137 -0.01350528 -0.1427292 0.2053168 -0.01350528 -0.1185771 -0.1588537 -0.007641792 -0.116324 -0.1549512 -0.007641792 -0.1185292 -0.1590324 -0.004644811 -0.1161453 -0.1549032 -0.004644811 -0.1103988 -0.1637265 -0.004644811 -0.1080149 -0.1595973 -0.004644811 -0.11022 -0.1636787 -0.007641792 -0.107967 -0.1597761 -0.007641792 -0.1053594 -0.1612816 -0.007641792 -0.1076124 -0.165184 -0.007641792 -0.1029013 -0.1625611 -0.004873335 -0.1211847 -0.1573482 -0.007641792 -0.1236427 -0.1560686 -0.004873335 -0.1184498 -0.1475313 -0.004644811 -0.1129281 -0.1507193 -0.004644811 -0.1210658 -0.1520624 -0.004644811 -0.1260657 -0.1607225 -0.004644811 -0.120544 -0.1639105 -0.004644811 -0.1290915 -0.163513 5.4077e-4 -0.1329224 -0.1702104 5.79239e-4 -0.1320269 -0.1701838 0.001088321 -0.1285194 -0.1642466 0.001093924 -0.1342278 -0.1673623 6.38774e-4 -0.1343858 -0.1675133 0.004816174 -0.1330415 -0.1705998 0.007375299 -0.1318777 -0.1636936 5.89809e-4 -0.1319382 -0.163538 0.004441022 -0.1129253 -0.1817241 5.6843e-4 -0.1090091 -0.1749956 5.98528e-4 -0.109869 -0.175029 0.00111258 -0.1133763 -0.1809577 0.001141309 -0.1135928 -0.1809207 0.007020592 -0.1098631 -0.17447 0.007025659 -0.1088322 -0.1746752 0.007242143 -0.1077939 -0.1776344 5.27778e-4 -0.1076114 -0.1775598 0.004494249 -0.1098138 -0.1815232 6.21834e-4 -0.1293743 -0.159918 -0.001433134 -0.129874 -0.1640859 -0.001513779 -0.1340246 -0.1678697 -0.001486063 -0.1133403 -0.1820958 0.007166445 -0.1096664 -0.181715 0.00506711 -0.1280748 -0.1561778 -8.69784e-4 -0.1351889 -0.1656253 -3.37922e-4 -0.1257157 -0.1506714 -3.37208e-4 -0.08501821 -0.08143746 -8.67763e-4 -0.09031873 -0.08946967 -3.37208e-4 -0.08209264 -0.07382136 -3.37208e-4 -0.07598745 -0.06585294 -0.00138396 -0.07411551 -0.05803412 -3.37208e-4 -0.06970834 -0.05129718 -9.07954e-4 -0.06638705 -0.04210805 -3.37208e-4 -0.06317675 -0.03883165 -0.001200139 -0.06189757 -0.03657585 -0.001306772 -0.1164923 -0.1355798 -3.37208e-4 -0.1236504 -0.1507986 -0.001397848 -0.1207922 -0.1461737 -0.001425027 -0.1258488 -0.1543298 -0.001411616 -0.1133165 -0.1338126 -0.001391768 -0.1075184 -0.120349 -3.37208e-4 -0.1102514 -0.1286462 -0.001409292 -0.1156557 -0.1377194 -0.001387178 -0.1146255 -0.1374619 -0.001492738 -0.105229 -0.1200324 -0.001396059 -0.09879392 -0.1049789 -3.37208e-4 -0.1031671 -0.1164354 -0.001408696 -0.0954765 -0.1027492 -0.001387298 -0.09321272 -0.09863948 -0.001419663 -0.09441536 -0.1024707 -0.001496553 -0.08849841 -0.08992785 -0.001389503 -0.0834546 -0.08044129 -0.001426756 -0.09053266 -0.09371089 -0.001425266 -0.07939553 -0.07255667 -0.001389443 -0.0813201 -0.07629907 -0.001449346 -0.07391381 -0.06172573 -0.00141263 -0.07228469 -0.0589056 -0.001491844 -0.06314897 -0.03997004 -0.001490235 -0.09803646 -0.1073595 -0.001396775 -0.1001709 -0.111159 -0.001411378 -0.1080137 -0.1248279 -0.001414179 -0.1185001 -0.1424223 -0.001431107 -0.1287751 -0.1704953 -0.001491844 -0.1289995 -0.1708838 -0.001598238 -0.1264884 -0.160562 -0.001491963 -0.1240704 -0.1563681 -0.001491844 -0.1216949 -0.1522589 -0.001491844 -0.1187544 -0.1471658 -0.001491844 -0.1162248 -0.1427845 -0.001491844 -0.1166857 -0.1431298 -0.001494348 -0.1189154 -0.146106 -0.001493573 -0.1288359 -0.1608206 -0.001491546 -0.1226959 -0.1526624 -0.001492381 -0.1247667 -0.1547201 -0.00162059 -0.1141284 -0.1391534 -0.001491844 -0.111595 -0.1347654 -0.001491844 -0.1086546 -0.1296724 -0.001491844 -0.106125 -0.1252911 -0.001491844 -0.1064773 -0.1256045 -0.001491844 -0.1087865 -0.1286376 -0.001492679 -0.1075479 -0.12572 -0.00149101 -0.1140331 -0.1386916 -0.001491844 -0.1125154 -0.1351978 -0.001496136 -0.1040285 -0.1216599 -0.001491844 -0.1014952 -0.117272 -0.001491844 -0.09855467 -0.1121788 -0.001491844 -0.09602516 -0.1077976 -0.001491844 -0.09637737 -0.1081111 -0.001491844 -0.09870088 -0.1111443 -0.00149393 -0.09756255 -0.1082341 -0.001491904 -0.1039603 -0.1210775 -0.001493752 -0.1024535 -0.1176749 -0.001492679 -0.05645811 -0.04523831 -0.001491844 -0.09392869 -0.1041665 -0.001491844 -0.09139531 -0.09977847 -0.001491844 -0.09383338 -0.1037046 -0.001491844 -0.09238058 -0.1001819 -0.001492798 -0.08845484 -0.09468537 -0.001491844 -0.08592534 -0.09030407 -0.001491844 -0.08627754 -0.09061759 -0.001491844 -0.08861708 -0.09362381 -0.001493573 -0.0880081 -0.09080708 -0.001491546 -0.08382886 -0.0866729 -0.001491844 -0.08129549 -0.08228498 -0.001491844 -0.07835495 -0.07719188 -0.001491844 -0.07599216 -0.07309985 -0.001491904 -0.07851326 -0.07611 -0.00149244 -0.07877737 -0.07339125 -0.001491844 -0.08373349 -0.08621114 -0.001491844 -0.08227616 -0.08274483 -0.001490235 -0.08458912 -0.0843032 -0.001494944 -0.07372897 -0.06917941 -0.001491844 -0.0711956 -0.0647915 -0.001491844 -0.06809806 -0.0594201 -0.001491844 -0.06267648 -0.04163616 -0.001491844 -0.06864744 -0.0586192 -0.001491844 -0.07363367 -0.06871765 -0.001491844 -0.07171469 -0.06515544 -0.001491844 -0.07232642 -0.06499129 -0.001491844 -0.07490891 -0.065894 -0.001491904 -0.04252064 -0.05244153 -0.002104878 -0.1153182 -0.1785309 -0.001518845 -0.1157501 -0.1792789 -0.002104878 -0.04288589 -0.05307418 -0.001491844 -0.1103113 -0.18157 -0.001492023 -0.114961 -0.183663 -0.004997789 -0.1115747 -0.188911 -0.007291555 -0.1077786 -0.1814509 -3.37929e-4 -0.04246902 -0.05941015 0.001749038 -0.04146838 -0.05892276 0.002439141 -0.04273426 -0.05861032 0.002370834 -0.03782504 -0.06166166 0.003470659 -0.03848373 -0.06162977 0.001751601 -0.04670846 -0.06651687 0.001749455 -0.04738473 -0.0664398 0.002734303 -0.04494464 -0.07140123 0.002156615 -0.0448181 -0.06967121 0.001744508 -0.04421401 -0.07070356 0.003838598 -0.04519069 -0.07135415 0.005031764 -0.04723513 -0.06708788 0.007615447 -0.04738098 -0.06636667 0.007008969 -0.05937087 -0.05063819 -8.97199e-4 -0.061993 -0.05509316 -8.19303e-4 -0.0616247 -0.05605244 -0.001402914 -0.05799865 -0.05027234 -0.001396715 -0.05640989 -0.05051749 -8.0148e-4 -0.04673308 -0.05733579 -0.00149101 -0.04715156 -0.05602818 -8.89668e-4 -0.04610931 -0.05837994 -9.53668e-4 -0.05095958 -0.06222993 -0.001483917 -0.04872465 -0.06282579 -9.84017e-4 -0.05139577 -0.0630474 -9.53231e-4 -0.06094354 -0.05744391 -9.28279e-4 -0.05129498 -0.06334388 0.007165908 -0.0485 -0.0630716 0.007015883 -0.06083762 -0.05798435 0.007020592 -0.0623089 -0.05517339 0.007021546 -0.05961626 -0.05043047 0.007015824 -0.07047301 -0.0562399 0.002345263 -0.06636267 -0.05510085 0.00174278 -0.070827 -0.05527126 0.002256929 -0.06553727 -0.04537504 0.001773655 -0.06594824 -0.04477304 0.003218889 -0.06586325 -0.05585283 0.002465963 -0.06112331 -0.04771709 0.002380013 -0.06218957 -0.04783928 0.001746118 -0.06572127 -0.0558502 0.00700742 -0.0613178 -0.04822486 0.007007479 -0.07034039 -0.05631232 0.005267739 -0.07173728 -0.05516558 0.004203855 -0.1342288 -0.1738374 -0.003357768 -0.1353013 -0.1714553 -0.003522157 -0.1348847 -0.173832 -0.00390917 -0.1420654 -0.1810848 -0.004005551 -0.143152 -0.1812895 -0.003353953 -0.1422503 -0.1820057 -0.003262221 -0.1388105 -0.1816932 -0.003366947 -0.1390155 -0.1807333 -0.003999948 -0.1363738 -0.1710435 -0.003929734 -0.1354076 -0.1704225 0.005759775 -0.1338267 -0.1737865 0.007015407 -0.1364272 -0.1783705 0.007020592 -0.1384494 -0.1819669 0.008405148 -0.115401 -0.184814 -0.002793252 -0.1153512 -0.1856899 -0.003732144 -0.1149979 -0.1846497 -0.003181993 -0.1198927 -0.1925402 -0.003110826 -0.1192377 -0.1925476 -0.003659188 -0.1122356 -0.1844949 -0.003687739 -0.1177061 -0.196028 -0.003774523 -0.1170933 -0.1957922 -0.002790272 -0.1119472 -0.1855129 -0.002790272 -0.1184446 -0.1957769 -0.002790272 -0.1183604 -0.1967115 0.006468236 -0.1201056 -0.1933773 0.009111046 -0.1202054 -0.1922847 0.008307099 -0.1179237 -0.18839 0.007481753 -0.1156061 -0.1844111 0.007001221 -0.1332929 -0.1782976 -0.007635533 -0.1396948 -0.1725562 -0.007234454 -0.1332473 -0.1728678 -0.004806041 -0.1392002 -0.1824386 -0.007762789 -0.1429793 -0.1829634 -0.007764279 -0.1418221 -0.1757845 -0.007755339 -0.1436059 -0.1813137 0.005304098 -0.1412988 -0.1779373 0.004180192 -0.136425 -0.1704985 0.004519462 -0.1197526 -0.186273 -0.007634818 -0.1180599 -0.1848613 -0.006851255 -0.1203528 -0.1933002 -0.007762134 -0.1132601 -0.1922748 -0.007755339 -0.1188275 -0.1971476 -0.007757008 -0.1115118 -0.1852188 0.004519283 -0.115386 -0.192898 0.004180192 -0.1174058 -0.1970502 0.005257248 -0.1116513 -0.1840937 0.005683064 -0.1228155 -0.189714 -0.007740497 -0.1181287 -0.2021429 -0.007756352 -0.1358988 -0.1825738 -0.007759034 -0.1293223 -0.1714431 -0.002104878 -0.1465688 -0.20392 -0.01636952 -0.1473398 -0.2024261 -0.01850515 -0.1469873 -0.2048391 -0.01850521 -0.1488001 -0.2055909 -0.01684582 -0.1500874 -0.2030208 -0.01563465 -0.1510379 -0.2032718 -0.01849961 -0.1475867 -0.202495 -0.01652735 -0.1504797 -0.2058619 -0.01850217 -0.1517803 -0.1986595 -0.01131808 -0.1507701 -0.1982402 -0.01790952 -0.1515024 -0.1978942 -0.01249659 -0.147394 -0.2014496 -0.01850473 -0.1509397 -0.2008283 -0.01852512 -0.1512063 -0.2004943 -0.01386678 -0.1488066 -0.19594 -0.01469391 -0.1466823 -0.1980143 -0.01850515 -0.1490314 -0.1957661 -0.0184943 -0.1284047 -0.2087829 -0.01581424 -0.1299127 -0.2073066 -0.01850515 -0.1275753 -0.2095565 -0.01850521 -0.1302788 -0.2105365 -0.01643997 -0.129267 -0.2116466 -0.01850992 -0.1318302 -0.2088358 -0.01651757 -0.1270788 -0.2042135 -0.01632726 -0.1292011 -0.2038713 -0.01850473 -0.1249115 -0.2049049 -0.01734334 -0.1256899 -0.2072805 -0.01325297 -0.1246561 -0.206051 -0.0110867 -0.1248018 -0.2067266 -0.0165798 -0.1264768 -0.2074755 -0.01852947 -0.1279886 -0.1998237 -0.01704639 -0.1278201 -0.1999571 -0.01850545 -0.1261178 -0.1994602 -0.01850521 -0.127496 -0.2025764 -0.01684606 -0.1254849 -0.2020366 -0.01840722 -0.1292554 -0.2028948 -0.01850515 -0.1300944 -0.2014397 -0.01636731 -0.1299237 -0.200876 -0.01850521 -0.134448 -0.1893628 -0.01100564 -0.134512 -0.1893319 -0.01350528 -0.1348788 -0.1879654 -0.01350528 -0.1348286 -0.1881538 -0.01036918 -0.1276285 -0.1933029 -0.01100414 -0.1286475 -0.1927178 -0.01350528 -0.1274662 -0.1924049 -0.01050066 -0.1272807 -0.1923522 -0.01350528 -0.1248211 -0.1875908 -0.00776273 -0.1276052 -0.1921406 -0.004644811 -0.1186158 -0.1765706 -0.004644811 -0.118568 -0.1767493 -0.007641792 -0.1266755 -0.1913041 -0.01350528 -0.131937 -0.1833819 -0.007643103 -0.1342736 -0.1869173 -0.01350528 -0.1255439 -0.1725707 -0.004644811 -0.1257227 -0.1726185 -0.007641792 -0.1345333 -0.1881406 -0.004644811 -0.1421946 -0.2004105 -0.01350528 -0.14119 -0.1992133 -0.01350528 -0.1392245 -0.1981914 -0.01350528 -0.1360999 -0.198657 -0.01350528 -0.1340239 -0.2010452 -0.01350528 -0.1338659 -0.2034418 -0.01350528 -0.1344004 -0.2049104 -0.01350528 -0.05153179 -0.03873628 -0.008264362 -0.04880702 -0.0343312 -0.02125471 -0.05206859 -0.03998035 -0.0076406 -0.05256235 -0.03886425 -0.007764518 -0.0499354 -0.03428614 -0.02125513 -0.05327159 -0.03235995 -0.02125513 -0.05702924 -0.03628927 -0.007755339 -0.03690624 -0.04180794 -0.02125483 -0.03968578 -0.04559206 -0.008293747 -0.03699153 -0.04051935 -0.02125513 -0.03957384 -0.04622668 -0.007857441 -0.03516691 -0.04004979 -0.02125513 -0.03440099 -0.03779804 -0.02125513 -0.03374886 -0.04195922 -0.02125513 -0.03211468 -0.04424357 -0.02125513 -0.03184711 -0.04202491 -0.02125513 -0.0308482 -0.04403984 -0.02125513 -0.02975231 -0.0433005 -0.02125513 -0.03332901 -0.04387378 -0.02125519 -0.03048372 -0.0410335 -0.02125513 -0.02902221 -0.04215735 -0.02125513 -0.02863907 -0.04030966 -0.02125513 -0.03027892 -0.03866392 -0.02125513 -0.02979284 -0.03703653 -0.02125513 -0.03211271 -0.03714925 -0.02125513 -0.03114068 -0.03589975 -0.02125513 -0.03179645 -0.03552114 -0.02125513 -0.02892291 -0.03856998 -0.02125513 -0.03279644 -0.03525322 -0.02125513 -0.03379642 -0.03552114 -0.02125513 -0.03452843 -0.03625321 -0.02125513 -0.04052835 -0.04664534 0.002358496 -0.03552842 -0.0379852 0.002358496 -0.04052728 -0.04664468 -0.007641494 -0.03452843 -0.03625321 -0.004469811 -0.04607188 -0.02758777 -0.02125298 -0.0462743 -0.02729862 -0.002807676 -0.04576081 -0.02822846 -0.002668976 -0.04680144 -0.02685803 -0.001641392 -0.04458069 -0.03044748 -0.001898109 -0.04589223 -0.02918571 -0.00463885 -0.04523468 -0.02785307 -0.002010345 -0.04433739 -0.03058999 0.002358496 -0.04576832 -0.03031378 0.002358496 -0.04596763 -0.03036183 -0.002125859 -0.04706943 -0.03132206 0.002358496 -0.04606944 -0.02959001 -0.02125513 -0.0520693 -0.03998219 0.002358496 -0.03626048 -0.03525322 0.002358496 -0.05204522 -0.04692423 0.002358496 -0.04665237 -0.05015468 0.002363502 -0.03525221 -0.03655427 0.002358496 -0.05289542 -0.04839676 0.002182126 -0.03626048 -0.03525322 -0.001641392 -0.03426694 -0.03589761 -0.00463885 -0.03447633 -0.03492742 -0.002764582 -0.03355395 -0.03540223 -0.004268527 -0.03263533 -0.03525054 -0.002274513 -0.03529006 -0.03637653 -0.002090573 -0.03640013 -0.03439986 -0.002594828 -0.03179645 -0.03552114 -0.001641392 -0.03034234 -0.03636068 0.005144417 -0.04825556 -0.0260185 0.005144417 -0.04745721 -0.02647942 -0.02125513 -0.04680144 -0.02685803 -0.02125513 -0.05396217 -0.05024439 -0.002373933 -0.04811871 -0.05280846 -0.001860976 -0.04896926 -0.05428171 -0.002641856 -0.05446213 -0.05111044 -0.002641856 -0.05351585 -0.04947137 -0.001407861 -0.04783499 -0.05231714 0.001639306 -0.05339062 -0.04925447 0.001135826 -0.05204522 -0.04692423 -0.002641856 -0.04655236 -0.05009549 -0.002641856 -0.04514122 -0.04930859 -0.004644811 -0.04491454 -0.04917776 -0.007641792 -0.0520693 -0.04530864 -0.004644811 -0.0520693 -0.04504692 -0.007641792 -0.03499054 -0.05978214 0.002978205 -0.03702396 -0.06098794 0.003760218 -0.04207032 -0.05834203 0.007664382 -0.04306566 -0.05880427 0.007145524 -0.04310351 -0.05788511 0.007728636 -0.061594 -0.0471524 0.007504999 -0.06640285 -0.04416465 0.003595113 -0.06559461 -0.04256558 0.003635168 -0.06621545 -0.04175561 0.00297445 -0.06249111 -0.04435735 0.006144404 -0.06051224 -0.04549986 0.007744431 -0.0749067 -0.05962848 0.003962159 -0.07264375 -0.05867332 0.004599332 -0.07536047 -0.0614084 0.004310309 -0.0837363 -0.07699739 0.004688799 -0.08097475 -0.07262772 0.004832983 -0.08147037 -0.07603341 0.005227982 -0.07713764 -0.0741508 0.007718801 -0.08495277 -0.08036416 0.005131185 -0.09287697 -0.0942142 0.005173563 -0.09121495 -0.09227764 0.005510628 -0.08449709 -0.08382737 0.00653398 -0.08283752 -0.08415985 0.007776379 -0.1023296 -0.1112775 0.005415499 -0.09480965 -0.09876751 0.005597293 -0.1006662 -0.1095103 0.005811691 -0.1046588 -0.1161974 0.005725622 -0.1120851 -0.1281702 0.005413889 -0.1089341 -0.1246166 0.005940496 -0.1110417 -0.1279917 0.005893409 -0.1082361 -0.1261074 0.006948649 -0.1078351 -0.1272756 0.007777333 -0.1221392 -0.1448842 0.005168795 -0.1200762 -0.1423275 0.005524456 -0.1268764 -0.1535744 0.005337297 -0.1246651 -0.1507002 0.005582273 -0.132489 -0.161416 0.004680514 -0.1324594 -0.1630918 0.005174219 -0.1307216 -0.160219 0.00526899 -0.1431245 -0.1777513 0.003950178 -0.1419849 -0.177491 0.004550099 -0.135595 -0.1671406 0.004800975 -0.1377597 -0.1713935 0.004944026 -0.134247 -0.1696006 0.006476879 -0.1338858 -0.1724959 0.007640719 -0.1280282 -0.1623895 0.00777477 -0.12499 -0.1536622 0.006397187 -0.1236966 -0.1550378 0.007716774 -0.1228743 -0.1532334 0.007603883 -0.117806 -0.1448291 0.007818281 -0.1149458 -0.1339535 0.005708336 -0.1153061 -0.136647 0.005872905 -0.1129333 -0.1389449 0.007744431 -0.1129801 -0.1353551 0.007221698 -0.1040478 -0.1163448 0.005903363 -0.1057062 -0.1189616 0.005976557 -0.1036405 -0.1208283 0.007669389 -0.1026324 -0.1182563 0.007635951 -0.09802591 -0.1086896 0.007336497 -0.09834706 -0.1106839 0.007429599 -0.09573274 -0.1012669 0.005833983 -0.09303694 -0.1015846 0.007747232 -0.08788299 -0.09121471 0.007515847 -0.08968794 -0.09022426 0.005589902 -0.07496815 -0.06517618 0.00573194 -0.07277154 -0.0665673 0.007728099 -0.06749713 -0.05708217 0.007689177 -0.06140714 -0.04931455 0.007721543 -0.04321235 -0.07110875 0.003993153 -0.04871577 -0.06745684 0.007693946 -0.06496143 -0.05603879 0.007745206 -0.0410853 -0.05671596 0.007744431 -0.0449779 -0.05834609 0.007719159 -0.04688507 -0.05484056 0.007744431 -0.05609273 -0.04964584 0.007738649 -0.060023 -0.04965484 0.007743239 -0.0631594 -0.05511504 0.007743835 -0.06608313 -0.0601477 0.007743716 -0.06288254 -0.05978512 0.007742762 -0.061329 -0.05829268 0.007742643 -0.06922101 -0.06304913 0.007739365 -0.07207423 -0.07052415 0.007743716 -0.06918418 -0.0655294 0.007744193 -0.07290691 -0.06986212 0.007739663 -0.07515907 -0.07589942 0.007743656 -0.07703101 -0.07550477 0.007733464 -0.0780766 -0.0809195 0.007743716 -0.07488214 -0.08056956 0.007742762 -0.07344597 -0.07889813 0.007716238 -0.08129185 -0.08435976 0.007747352 -0.08115881 -0.08629155 0.007743537 -0.08407652 -0.09131163 0.007743775 -0.08049356 -0.09109014 0.00775057 -0.07098209 -0.09635913 0.007744252 -0.070109 -0.09506565 0.007744431 -0.06606894 -0.09497833 0.007743 -0.06890857 -0.09989821 0.007744133 -0.06295049 -0.08953219 0.007742226 -0.06475013 -0.09484666 0.00775206 -0.05917286 -0.08516341 0.007744312 -0.06002056 -0.08451527 0.007743597 -0.06345951 -0.08485776 0.007741868 -0.08608961 -0.09266585 0.007748007 -0.08715581 -0.0966798 0.007744133 -0.09253025 -0.1037881 0.007744789 -0.09313344 -0.1070251 0.007743716 -0.09619086 -0.1101594 0.007747113 -0.09607619 -0.1120961 0.007743597 -0.09245365 -0.1117061 0.00774455 -0.09165531 -0.1101301 0.007741451 -0.09002363 -0.1016165 0.007743656 -0.1029978 -0.1219682 0.007744133 -0.09917956 -0.1175267 0.007744133 -0.1020261 -0.1224043 0.007743656 -0.1065887 -0.128151 0.007745623 -0.1051333 -0.1278094 0.007743716 -0.1080762 -0.1328804 0.007743716 -0.1048817 -0.1325305 0.007742762 -0.1037858 -0.1307555 0.007743299 -0.1111477 -0.1360994 0.00774455 -0.1111332 -0.1382015 0.007743716 -0.1140761 -0.1432726 0.007743656 -0.1108816 -0.1429226 0.007742762 -0.1097839 -0.1411456 0.007743418 -0.1163892 -0.1451464 0.007748007 -0.1171337 -0.1485968 0.007743835 -0.122134 -0.1551131 0.007744312 -0.1231583 -0.1590368 0.007743656 -0.1259807 -0.1617352 0.007746458 -0.1260759 -0.164057 0.007743597 -0.1228814 -0.163707 0.007742762 -0.1214452 -0.1620355 0.007716238 -0.1200234 -0.1535774 0.007743656 -0.1319855 -0.1707424 0.007649242 -0.1291584 -0.169429 0.007743775 -0.1321142 -0.1744597 0.007743895 -0.1358748 -0.1784028 0.007701575 -0.134334 -0.1798172 0.007486939 -0.1288813 -0.1740992 0.007742762 -0.1268469 -0.1723084 0.007369458 -0.1189879 -0.1794898 0.007747113 -0.1180281 -0.1781737 0.007742702 -0.1169129 -0.183111 0.007743477 -0.1140708 -0.17813 0.007743835 -0.1156105 -0.182973 0.007749974 -0.1096046 -0.1725146 0.007744312 -0.1109502 -0.1726696 0.007741928 -0.10802 -0.1676527 0.007743597 -0.111459 -0.1679951 0.007741868 -0.1204377 -0.1877205 0.007598459 -0.108089 -0.1714474 0.007294356 -0.1053098 -0.1650945 0.007746994 -0.1020199 -0.1572606 0.007743775 -0.0999276 -0.1557046 0.007746398 -0.09493011 -0.1471141 0.007745862 -0.09893584 -0.1518856 0.007743775 -0.09607017 -0.1469522 0.007743597 -0.09428542 -0.1491732 0.007608354 -0.09311282 -0.1470827 0.007519841 -0.1054963 -0.1668676 0.007386863 -0.1030003 -0.1646437 0.007285952 -0.1048979 -0.1622319 0.007744252 -0.09865748 -0.1573366 0.007366061 -0.09809935 -0.1555593 0.007738888 -0.09295004 -0.1414931 0.007742226 -0.08982753 -0.138212 0.007745862 -0.09002012 -0.1364761 0.007743597 -0.09362232 -0.1368674 0.007744252 -0.08856731 -0.1398367 0.007381021 -0.08699369 -0.1383798 0.00735706 -0.08693766 -0.1311042 0.007743716 -0.08511084 -0.1301077 0.007747411 -0.08326989 -0.1316425 0.007316946 -0.08286166 -0.1296168 0.007392644 -0.08402007 -0.1260841 0.007743775 -0.08864235 -0.1280548 0.007742941 -0.0874921 -0.1263812 0.007743775 -0.09798544 -0.1223776 0.007743954 -0.07934743 -0.1201069 0.007744431 -0.08093786 -0.1207121 0.007743597 -0.07802021 -0.1156919 0.007743656 -0.08264255 -0.1176625 0.007742941 -0.08162236 -0.116083 0.007744252 -0.07866787 -0.1220192 0.007617235 -0.07707971 -0.1206165 0.007556378 -0.07524842 -0.1130258 0.007746338 -0.07202029 -0.1052998 0.007743775 -0.06927269 -0.1026569 0.007744252 -0.07408314 -0.1141858 0.007606923 -0.07286226 -0.1121102 0.007486462 -0.07493788 -0.1103198 0.007743656 -0.07664263 -0.1072704 0.007742941 -0.07562243 -0.1056908 0.007744252 -0.08508479 -0.1001011 0.00774306 -0.08598566 -0.1015933 0.007743954 -0.06853348 -0.1045362 0.007460772 -0.06771492 -0.1028316 0.00771296 -0.0589351 -0.08692228 0.007663547 -0.05744171 -0.08436924 0.007675886 -0.05689853 -0.07909446 0.007744252 -0.05504906 -0.07803881 0.007746636 -0.05402052 -0.07412326 0.007743775 -0.04806768 -0.06379997 0.007741689 -0.04830753 -0.06954866 0.00753653 -0.05089968 -0.06870645 0.007743537 -0.05908888 -0.07554411 0.007744014 -0.05744111 -0.07446843 0.007742285 -0.06861591 -0.07026761 0.00774753 -0.06744605 -0.068506 0.007716238 -0.053092 -0.06515049 0.007744193 -0.06488484 -0.08601707 0.007744431 -0.09488439 -0.137978 0.007744431 -0.1071003 -0.1586512 0.007743954 -0.1056221 -0.1576517 0.007744252 -0.1159289 -0.15355 0.007744073 -0.1157856 -0.1515398 0.007743239 -0.1009762 -0.1483483 0.007744431 -0.1001381 -0.1469847 0.007743954 -0.1128841 -0.1691545 0.007744431 -0.1291907 -0.1924521 -0.01656836 -0.1286367 -0.1924272 -0.0165053 -0.1294147 -0.1922749 -0.01719421 -0.1337447 -0.1897749 -0.01719421 -0.1343311 -0.1889653 -0.01634263 -0.1339734 -0.1896657 -0.01657176 -0.1472476 -0.2131626 -0.0170052 -0.1468914 -0.2125455 -0.01800519 -0.1340338 -0.1902755 -0.01800519 -0.141617 -0.2033402 -0.01670724 -0.147809 -0.213135 -0.01650524 -0.1423676 -0.216212 -0.01650398 -0.1429151 -0.2159197 -0.01666045 -0.1359757 -0.203813 -0.01669043 -0.1425613 -0.2150455 -0.01800519 -0.1297037 -0.1927755 -0.01800519 -0.04600083 -0.05079752 -0.004644811 -0.04582208 -0.05074965 -0.007641792 -0.05082201 -0.05940979 -0.007641792 -0.05100077 -0.05945765 -0.004644811 -0.0485689 -0.0555073 -0.007641792 -0.04861682 -0.05532854 -0.004644811 -0.05582195 -0.06806993 -0.007641792 -0.0560007 -0.06811785 -0.004644811 -0.05356884 -0.06416743 -0.007641792 -0.05361676 -0.06398868 -0.004644811 -0.06082189 -0.07673007 -0.007641792 -0.06100064 -0.07677799 -0.004644811 -0.05856877 -0.07282757 -0.007641792 -0.05861669 -0.07264882 -0.004644811 -0.06582182 -0.08539021 -0.007641792 -0.06600058 -0.08543813 -0.004644811 -0.06356871 -0.08148771 -0.007641792 -0.06361663 -0.08130896 -0.004644811 -0.07082176 -0.0940504 -0.007641792 -0.07100051 -0.09409826 -0.004644811 -0.06856864 -0.09014785 -0.007641792 -0.0686165 -0.08996909 -0.004644811 -0.07582169 -0.1027106 -0.007641792 -0.07600045 -0.1027584 -0.004644811 -0.07356858 -0.09880799 -0.007641792 -0.07361644 -0.09862923 -0.004644811 -0.08082163 -0.1113706 -0.007641792 -0.08100038 -0.1114186 -0.004644811 -0.07856851 -0.1074682 -0.007641792 -0.07861638 -0.1072894 -0.004644811 -0.0858215 -0.1200308 -0.007641792 -0.08600032 -0.1200788 -0.004644811 -0.08356845 -0.1161283 -0.007641792 -0.08361631 -0.1159496 -0.004644811 -0.09082144 -0.128691 -0.007641792 -0.09100019 -0.1287388 -0.004644811 -0.08856838 -0.1247885 -0.007641792 -0.08861625 -0.1246097 -0.004644811 -0.09582138 -0.1373511 -0.007641792 -0.09600013 -0.137399 -0.004644811 -0.09356826 -0.1334486 -0.007641792 -0.09361618 -0.1332699 -0.004644811 -0.1008214 -0.1460113 -0.007641792 -0.1010001 -0.1460592 -0.004644811 -0.0985682 -0.1421087 -0.007641792 -0.09861612 -0.1419301 -0.004644811 -0.1058213 -0.1546714 -0.007641792 -0.106 -0.1547192 -0.004644811 -0.1035681 -0.1507689 -0.007641792 -0.103616 -0.1505901 -0.004644811 -0.05292892 -0.04679757 -0.004644811 -0.05297684 -0.04661887 -0.007641792 -0.05797678 -0.05527901 -0.007641792 -0.05572366 -0.05137646 -0.007641792 -0.05792886 -0.05545771 -0.004644811 -0.05554491 -0.05132859 -0.004644811 -0.06297671 -0.06393915 -0.007641792 -0.0607236 -0.06003659 -0.007641792 -0.06292885 -0.0641179 -0.004644811 -0.06054484 -0.05998873 -0.004644811 -0.06797665 -0.07259929 -0.007641792 -0.06572353 -0.06869679 -0.007641792 -0.06792873 -0.07277804 -0.004644811 -0.06554478 -0.06864887 -0.004644811 -0.07297658 -0.08125942 -0.007641792 -0.07072347 -0.07735693 -0.007641792 -0.07292866 -0.08143818 -0.004644811 -0.07054471 -0.07730901 -0.004644811 -0.07797652 -0.08991956 -0.007641792 -0.0757234 -0.08601707 -0.007641792 -0.0779286 -0.09009832 -0.004644811 -0.07554465 -0.08596915 -0.004644811 -0.08297646 -0.0985797 -0.007641792 -0.08072334 -0.0946772 -0.007641792 -0.08292853 -0.09875845 -0.004644811 -0.08054459 -0.09462928 -0.004644811 -0.08797639 -0.1072399 -0.007641792 -0.08572328 -0.1033374 -0.007641792 -0.08792847 -0.1074186 -0.004644811 -0.08554452 -0.1032894 -0.004644811 -0.09297627 -0.1159 -0.007641792 -0.09072315 -0.1119976 -0.007641792 -0.0929284 -0.1160788 -0.004644811 -0.09054446 -0.1119496 -0.004644811 -0.0979762 -0.1245602 -0.007641792 -0.09572309 -0.1206576 -0.007641792 -0.09792834 -0.1247389 -0.004644811 -0.09554439 -0.1206097 -0.004644811 -0.1029762 -0.1332203 -0.007641792 -0.100723 -0.1293178 -0.007641792 -0.1029282 -0.133399 -0.004644811 -0.1005443 -0.1292699 -0.004644811 -0.1079761 -0.1418804 -0.007641792 -0.105723 -0.1379779 -0.007641792 -0.1079282 -0.1420592 -0.004644811 -0.1055442 -0.1379301 -0.004644811 -0.112976 -0.1505406 -0.007641792 -0.1107229 -0.146638 -0.007641792 -0.1105442 -0.1465902 -0.004644811 -0.1136159 -0.1679104 -0.004644811 -0.113568 -0.1680892 -0.007641792 -0.1159999 -0.1720395 -0.004644811 -0.1158212 -0.1719917 -0.007641792 -0.1229759 -0.1678609 -0.007641792 -0.1207228 -0.1639583 -0.007641792 -0.122928 -0.1680396 -0.004644811 -0.1284497 -0.1648516 -0.004644811 -0.1310657 -0.1693827 -0.004644811 -0.1261847 -0.1660083 -0.007641792 -0.1239315 -0.1621059 -0.007641792 -0.1103593 -0.1699417 -0.007641792 -0.1079013 -0.1712213 -0.004873335 -0.1054782 -0.1665674 -0.004644811 -0.1004782 -0.1579072 -0.004644811 -0.1189315 -0.1534457 -0.007641792 -0.1161756 -0.148687 -0.007649719 -0.1026125 -0.156524 -0.007641792 -0.1139316 -0.1447855 -0.007641792 -0.1003594 -0.1526214 -0.007641792 -0.1162688 -0.1432966 -0.004873335 -0.09790146 -0.153901 -0.004873335 -0.1134499 -0.1388713 -0.004644811 -0.09547835 -0.149247 -0.004644811 -0.1111848 -0.1400278 -0.007641792 -0.09761261 -0.1478638 -0.007641792 -0.1089317 -0.1361254 -0.007641792 -0.0953595 -0.1439613 -0.007641792 -0.1112688 -0.1346364 -0.004873335 -0.09290152 -0.1452408 -0.004873335 -0.1084499 -0.1302111 -0.004644811 -0.09047847 -0.140587 -0.004644811 -0.1061849 -0.1313678 -0.007641792 -0.09261268 -0.1392037 -0.007641792 -0.1039317 -0.1274652 -0.007641792 -0.09035956 -0.1353011 -0.007641792 -0.1062689 -0.1259763 -0.004873335 -0.08790159 -0.1365807 -0.004873335 -0.10345 -0.1215509 -0.004644811 -0.08547854 -0.1319268 -0.004644811 -0.101185 -0.1227076 -0.007641792 -0.08761274 -0.1305435 -0.007641792 -0.09893184 -0.1188051 -0.007641792 -0.08535963 -0.126641 -0.007641792 -0.101269 -0.1173161 -0.004873335 -0.08290165 -0.1279205 -0.004873335 -0.09845012 -0.1128908 -0.004644811 -0.0804786 -0.1232667 -0.004644811 -0.09618502 -0.1140475 -0.007641792 -0.08261281 -0.1218834 -0.007641792 -0.09393191 -0.110145 -0.007641792 -0.08035969 -0.1179808 -0.007641792 -0.09626901 -0.1086561 -0.004873335 -0.07790172 -0.1192604 -0.004873335 -0.09345018 -0.1042307 -0.004644811 -0.07547867 -0.1146065 -0.004644811 -0.09118509 -0.1053873 -0.007641792 -0.07761287 -0.1132232 -0.007641792 -0.08893197 -0.1014848 -0.007641792 -0.07535982 -0.1093207 -0.007641792 -0.09126907 -0.09999591 -0.004873335 -0.07290178 -0.1106002 -0.004873335 -0.08845025 -0.0955705 -0.004644811 -0.07047873 -0.1059464 -0.004644811 -0.08618515 -0.09672719 -0.007641792 -0.07261294 -0.104563 -0.007641792 -0.08393204 -0.09282463 -0.007641792 -0.07035988 -0.1006606 -0.007641792 -0.08626914 -0.09133577 -0.004873335 -0.06790184 -0.10194 -0.004873335 -0.08345031 -0.08691036 -0.004644811 -0.0654788 -0.09728622 -0.004644811 -0.08118522 -0.08806705 -0.007641792 -0.06761306 -0.09590291 -0.007641792 -0.0789321 -0.0841645 -0.007641792 -0.06535995 -0.09200042 -0.007641792 -0.08126926 -0.08267557 -0.004873335 -0.06290191 -0.09327995 -0.004873335 -0.07845038 -0.07825022 -0.004644811 -0.06047886 -0.08862608 -0.004644811 -0.07618528 -0.07940691 -0.007641792 -0.06261312 -0.08724278 -0.007641792 -0.07393217 -0.07550436 -0.007641792 -0.06036001 -0.08334028 -0.007641792 -0.07626932 -0.07401543 -0.004873335 -0.05790197 -0.08461982 -0.004873335 -0.07345044 -0.06959009 -0.004644811 -0.05547893 -0.07996594 -0.004644811 -0.07118535 -0.07074671 -0.007641792 -0.05761319 -0.07858264 -0.007641792 -0.06893223 -0.06684422 -0.007641792 -0.05536007 -0.07468008 -0.007641792 -0.07126939 -0.0653553 -0.004873335 -0.0529021 -0.07595968 -0.004873335 -0.06845051 -0.06092995 -0.004644811 -0.05047899 -0.07130581 -0.004644811 -0.06618547 -0.06208658 -0.007641792 -0.05261325 -0.0699225 -0.007641792 -0.06393229 -0.05818408 -0.007641792 -0.05036014 -0.06601995 -0.007641792 -0.06626945 -0.05669516 -0.004873335 -0.04790216 -0.06729954 -0.004873335 -0.06345063 -0.05226981 -0.004644811 -0.04547905 -0.06264567 -0.004644811 -0.06118547 -0.05342644 -0.007641792 -0.04761332 -0.06126236 -0.007641792 -0.05893236 -0.04952394 -0.007641792 -0.0453602 -0.05735981 -0.007641792 -0.05618554 -0.0447663 -0.007641792 -0.04261338 -0.05260217 -0.007641792 -0.03922134 -0.04672694 -0.007641792 -0.06126952 -0.04803502 -0.004873335 -0.04290223 -0.05863934 -0.004873335 -0.05864357 -0.04348677 -0.004873335 -0.04027628 -0.05409109 -0.004873335 -0.1298949 -0.1902351 -0.002641856 -0.1282208 -0.1915495 -0.002641856 -0.1317383 -0.1891708 -0.002641856 -0.1337136 -0.1883782 -0.002641856 -0.1153593 -0.1786019 -0.007641792 -0.1129012 -0.1798815 -0.004873335 -0.1289314 -0.1707659 -0.007641792 -0.1347004 -0.1904302 -0.01850521 -0.1350275 -0.1879968 -0.01525521 -0.1373968 -0.189944 -0.01850521 -0.1402366 -0.1902565 -0.01877647 -0.1427879 -0.1907292 -0.01850521 -0.1450918 -0.1859923 -0.01100528 -0.1452103 -0.1919344 -0.01849639 -0.1473177 -0.1936659 -0.01850998 -0.1505208 -0.1887513 -0.01026546 -0.1492041 -0.1936064 -0.01650172 -0.1538783 -0.1936459 -0.01101702 -0.1522858 -0.1913325 -0.01100528 -0.1552742 -0.1966781 -0.01100528 -0.1560607 -0.1997156 -0.01100289 -0.1562888 -0.2032147 -0.01100528 -0.1521916 -0.2049143 -0.01661682 -0.1558805 -0.2065112 -0.01100528 -0.1548736 -0.2096766 -0.01100528 -0.1498265 -0.2081012 -0.01850521 -0.1533021 -0.2126029 -0.01100528 -0.1486337 -0.2101224 -0.01850521 -0.1493617 -0.2128243 -0.01525521 -0.1470898 -0.2118917 -0.01850527 -0.1512198 -0.2151907 -0.01100528 -0.1500015 -0.2139324 -0.01350528 -0.1477009 -0.2159124 -0.01350528 -0.1473346 -0.2183126 -0.01097166 -0.1450724 -0.2174301 -0.01350528 -0.1426879 -0.2201166 -0.01100528 -0.1422073 -0.2184323 -0.01350528 -0.1415675 -0.2173241 -0.01525521 -0.1394057 -0.2206261 -0.01100528 -0.1391983 -0.2153769 -0.01850521 -0.141914 -0.2148868 -0.0185064 -0.1360856 -0.2205238 -0.01100528 -0.1363637 -0.215062 -0.01877623 -0.1328408 -0.2198132 -0.01100528 -0.1338073 -0.2145917 -0.01850521 -0.129782 -0.2185184 -0.01100528 -0.1313614 -0.2133567 -0.01850521 -0.127013 -0.2166836 -0.01100528 -0.1272031 -0.2115048 -0.01652586 -0.1246284 -0.2143714 -0.01100528 -0.1227043 -0.2116538 -0.01100403 -0.1216641 -0.2094674 -0.01108103 -0.1201445 -0.2063009 -0.01026362 -0.1254643 -0.2029752 -0.01844471 -0.1204653 -0.2002105 -0.01100528 -0.1232013 -0.1983399 -0.01428198 -0.1267686 -0.1972197 -0.01850521 -0.1279613 -0.1951984 -0.01850521 -0.1238555 -0.1919172 -0.01100528 -0.1272334 -0.1924967 -0.01525521 -0.1295044 -0.1934301 -0.01850521 -0.1479322 -0.1849328 -0.007756471 -0.1525316 -0.197929 0.01049435 -0.1522145 -0.197067 -0.01057648 -0.1512878 -0.1951605 0.01049435 -0.1530596 -0.200005 -0.01055753 -0.1531926 -0.2008911 0.01049435 -0.1532914 -0.2030526 -0.01055532 -0.1532438 -0.2039257 0.01049435 -0.1529005 -0.2060841 -0.0105583 -0.1526833 -0.2069085 0.01049435 -0.1519029 -0.2089739 -0.01057404 -0.1515336 -0.2097173 0.01049435 -0.15034 -0.2116019 -0.01056253 -0.1498421 -0.2122373 0.01049435 -0.148275 -0.2138606 -0.01000529 -0.147678 -0.2143652 0.01049435 -0.1457974 -0.2156507 -0.01000529 -0.1451299 -0.2160139 0.01049435 -0.1430141 -0.2168984 -0.01062059 -0.142302 -0.2171158 0.01049435 -0.1400369 -0.2175573 -0.01099503 -0.1393101 -0.217626 0.01049435 -0.1369712 -0.2176008 -0.01055175 -0.1362769 -0.2175235 0.01049435 -0.13397 -0.2170217 -0.01055014 -0.1333263 -0.2168126 0.01049435 -0.1311487 -0.2158463 -0.01054894 -0.1305792 -0.2155222 0.01049435 -0.128624 -0.2141233 -0.01054757 -0.1281483 -0.2137052 0.01049435 -0.1265012 -0.2119243 -0.0105462 -0.1261327 -0.211436 0.01049435 -0.124868 -0.2093405 -0.01054477 -0.1246153 -0.2088077 0.01049435 -0.123791 -0.2064757 -0.01000529 -0.1236579 -0.2059276 0.01049435 -0.1233201 -0.2034622 -0.01060813 -0.1232998 -0.2029137 0.01049435 -0.1234686 -0.2004073 -0.01052707 -0.1235558 -0.1998896 0.01049435 -0.1242333 -0.1974477 -0.01044517 -0.1244155 -0.1969788 0.01049435 -0.1255822 -0.1947047 -0.01044887 -0.1258433 -0.1943007 0.01049435 -0.127781 -0.1919648 0.01049435 -0.1301494 -0.1900668 0.01049435 -0.1328513 -0.1886843 0.01049435 -0.1357761 -0.1878741 0.01049435 -0.1377624 -0.1876713 -0.01055079 -0.1388041 -0.1876692 0.01049435 -0.14081 -0.1878735 -0.01061451 -0.1418115 -0.1880781 0.01049435 -0.1437567 -0.1886893 -0.01000529 -0.144675 -0.1890839 0.01049435 -0.1464728 -0.1900852 -0.0105158 -0.1472774 -0.1906456 0.01049435 -0.1488521 -0.1920036 -0.01056653 -0.1495121 -0.1926992 0.01049435 -0.1507957 -0.1943665 -0.01000529 -0.1437516 -0.2068942 -0.01834946 -0.1368927 -0.1947198 -0.01844227 -0.139311 -0.1993843 -0.01812976 -0.1367653 -0.2051553 -0.01826769 -0.1328653 -0.1985692 -0.01841008 -0.1470075 -0.1990206 -0.0184406 -0.1465834 -0.1986361 -0.01652735 -0.1472242 -0.2012884 -0.01649975 -0.1429599 -0.1965815 -0.01648533 -0.1449576 -0.1961952 -0.01667612 -0.1443568 -0.1948621 -0.01623237 -0.1452566 -0.1939923 -0.01647478 -0.1442198 -0.1919971 -0.01368999 -0.1451865 -0.1904253 -0.01218771 -0.1441698 -0.1924801 -0.01101422 -0.1427769 -0.1974191 -0.01575523 -0.142676 -0.1970724 -0.01171594 -0.1424521 -0.1976066 -0.01110577 -0.1429671 -0.1964262 -0.01113909 -0.1499922 -0.2107242 -0.01101291 -0.1502059 -0.2102122 -0.01228326 -0.1444175 -0.1944995 -0.01116377 -0.1435801 -0.1953302 -0.01113641 -0.1435046 -0.1959716 -0.01138979 -0.1446718 -0.189895 -0.01100748 -0.1483438 -0.1930519 -0.01281589 -0.149474 -0.1941218 -0.01117449 -0.1295938 -0.2063065 -0.0184558 -0.1300228 -0.2056853 -0.01651585 -0.1305515 -0.2069835 -0.01650536 -0.1336664 -0.2087423 -0.01648318 -0.1324463 -0.2099561 -0.01642644 -0.1253838 -0.197086 -0.0121451 -0.1269285 -0.1952856 -0.0110808 -0.1269268 -0.1961128 -0.01160871 -0.1270564 -0.1961915 -0.01351439 -0.1243112 -0.2012228 -0.01250201 -0.1244454 -0.2002856 -0.01098316 -0.1258753 -0.2091168 -0.01235461 -0.1270864 -0.2111595 -0.0112062 -0.1315841 -0.2151513 -0.01101601 -0.1281693 -0.2121953 -0.01273089 -0.131416 -0.2148522 -0.01235461 -0.1323257 -0.2132723 -0.01493555 -0.1338181 -0.2079018 -0.01575523 -0.1340488 -0.2085701 -0.01143246 -0.1331757 -0.2097751 -0.01136595 -0.1323223 -0.2134218 -0.01104599 -0.132151 -0.2108067 -0.01128369 -0.1348159 -0.2081689 -0.01100468 -0.133918 -0.2082468 -0.01175528 -0.1457675 -0.2118051 -0.01100528 -0.1455411 -0.2143967 -0.01104414 -0.1461129 -0.2124033 -0.01350528 -0.144429 -0.2148748 -0.01350528 -0.1432981 -0.2145909 -0.01102727 -0.142636 -0.213589 -0.01350528 -0.1427851 -0.2120277 -0.01100528 -0.1432725 -0.2115403 -0.01350528 -0.1448571 -0.1976799 -0.01850503 -0.1317379 -0.207641 -0.01850503 -0.1252484 -0.1996356 -0.01356756 -0.1519369 -0.2051408 -0.01298546 -0.1374818 -0.2090889 -0.01850521 -0.1341842 -0.209228 -0.01850521 -0.132683 -0.2120884 -0.01850426 -0.1388832 -0.2128272 -0.01850503 -0.1522702 -0.2017878 -0.0124334 -0.1515123 -0.2072828 -0.0124334 -0.1490492 -0.2080424 -0.0150485 -0.1391132 -0.196232 -0.01850521 -0.142411 -0.1960929 -0.01850521 -0.1439121 -0.1932325 -0.01850426 -0.1377119 -0.1924937 -0.01850503 -0.1435323 -0.1920832 -0.0170049 -0.1432102 -0.1953159 -0.01700496 -0.1408542 -0.1965447 -0.01700496 -0.1379165 -0.1949007 -0.01700437 -0.1383023 -0.1916528 -0.01700496 -0.1405482 -0.1904468 -0.0169931 -0.1423956 -0.194292 -0.01699805 -0.1419335 -0.1921939 -0.01700365 -0.1403819 -0.1951904 -0.01700323 -0.1390917 -0.1940133 -0.01700365 -0.1397404 -0.1919651 -0.01699805 -0.1386786 -0.2104201 -0.01700437 -0.1382926 -0.2136683 -0.01700496 -0.1349399 -0.2149083 -0.01700294 -0.1326656 -0.2118807 -0.01700437 -0.1350898 -0.2087528 -0.01700443 -0.1374781 -0.2126443 -0.01699805 -0.137016 -0.2105463 -0.01700365 -0.1354647 -0.2135427 -0.01700323 -0.1341741 -0.2123657 -0.01700365 -0.1348229 -0.2103175 -0.01699805 -0.1521979 -0.2046019 -0.01097315 -0.1356042 -0.1989687 -0.01100528 -0.1380205 -0.198169 -0.01100528 -0.1391537 -0.1938201 -0.01100528 -0.1396642 -0.1922642 -0.0110051 -0.141267 -0.1919285 -0.0110051 -0.1424648 -0.1936186 -0.01101273 -0.1406214 -0.1951928 -0.01102066 -0.1403561 -0.1985839 -0.01102095 -0.1426234 -0.2011258 -0.0110197 -0.1421322 -0.2053515 -0.01100528 -0.1385295 -0.207225 -0.01100528 -0.1373945 -0.2123472 -0.01100528 -0.1357042 -0.2135449 -0.01100444 -0.1342363 -0.2121725 -0.01099359 -0.1347467 -0.2106166 -0.01100325 -0.1368093 -0.2104244 -0.01100516 -0.1354187 -0.2062112 -0.01100516 -0.1340534 -0.2041561 -0.01100528 -0.1338254 -0.2017152 -0.01100528 -0.1104781 -0.1752275 -0.004644811 -0.1126124 -0.1738442 -0.007641792 -0.03847342 -0.05096846 -0.004873335 -0.05684071 -0.04036414 -0.004873335 -0.1108179 -0.1855884 0.004911422 -0.1149012 -0.1931273 0.004662334 -0.1143121 -0.194386 0.003950178 -0.1193103 -0.20459 0.004855155 -0.1198672 -0.1990461 0.008077383 -0.1203585 -0.2027664 0.009806573 -0.1206104 -0.195872 0.009642481 -0.1209747 -0.2080175 0.00675702 -0.1207588 -0.2071021 0.01000332 -0.121995 -0.1936699 0.009806513 -0.1236515 -0.1881501 0.009044408 -0.1287632 -0.1860476 0.009581983 -0.1277157 -0.1892246 0.01047539 -0.1330703 -0.1825956 0.008997142 -0.1385545 -0.1837885 0.009703576 -0.1333636 -0.1863871 0.01047402 -0.1434032 -0.1823609 0.006188094 -0.06544125 -0.06101232 -5.22931e-5 -0.06498891 -0.06170988 -4.91907e-4 -0.06285113 -0.06080216 -4.36985e-4 -0.05255389 -0.06723237 -4.91678e-4 -0.05344301 -0.06604981 2.31909e-4 -0.06721204 -0.06556046 -4.91907e-4 -0.05514037 -0.07327795 -4.90816e-4 -0.05724507 -0.07345539 -4.69378e-4 -0.06280291 -0.06052857 0.007020592 -0.06559592 -0.0607925 0.00701034 -0.05325877 -0.06588065 0.007064759 -0.05204308 -0.068717 -3.81744e-5 -0.05178827 -0.06869202 0.00702548 -0.05445933 -0.07292324 2.31909e-4 -0.0544818 -0.07343703 0.00702238 -0.0572949 -0.07373523 0.007160961 -0.0666458 -0.06819987 -9.80914e-5 -0.06683754 -0.06837654 0.007020592 -0.06805402 -0.06554114 -4.49515e-5 -0.06830906 -0.06556624 0.00702697 -0.05965894 -0.07682394 -4.82309e-4 -0.06841278 -0.07127618 -9.5382e-5 -0.07142174 -0.07140946 -4.90583e-4 -0.05944293 -0.076442 2.31909e-4 -0.06850177 -0.07095593 0.007021725 -0.05925869 -0.07627296 0.00706464 -0.05804306 -0.07910919 -4.09715e-5 -0.05999678 -0.08101534 -4.91907e-4 -0.06065595 -0.08363097 -1.14463e-4 -0.07269364 -0.07854735 -4.91688e-4 -0.06324553 -0.08384728 -4.69051e-4 -0.05778819 -0.07908415 0.00702548 -0.06048172 -0.08382922 0.00702238 -0.06329476 -0.08412748 0.007163226 -0.07283747 -0.07876867 0.007020592 -0.07405418 -0.07593351 -3.81595e-5 -0.07430881 -0.07595854 0.007021129 -0.07161206 -0.07120794 0.007021248 -0.07863116 -0.08897912 -4.06976e-4 -0.06967771 -0.09416168 -9.57326e-5 -0.06668049 -0.09403437 -4.90594e-4 -0.08005356 -0.08632564 -5.02514e-5 -0.07921183 -0.08634483 -4.91907e-4 -0.06488513 -0.08948224 -4.91907e-4 -0.07628178 -0.08147352 -4.91953e-4 -0.06973427 -0.09441655 0.007020592 -0.07884061 -0.08916562 0.007171809 -0.08030873 -0.08635073 0.007021129 -0.07744175 -0.0818029 -8.22452e-5 -0.07761532 -0.08160573 0.00702238 -0.07485514 -0.08157324 -1.88124e-4 -0.07480269 -0.08131295 0.007020592 -0.06545132 -0.08684283 -9.80888e-5 -0.06525856 -0.08666503 0.007064759 -0.06404286 -0.08950138 -3.8164e-5 -0.06378823 -0.08947622 0.007019639 -0.0664879 -0.09423196 0.007021725 -0.08604389 -0.09670001 -4.03947e-5 -0.08482581 -0.09923684 7.91635e-6 -0.08447092 -0.09900403 -4.2829e-4 -0.08521175 -0.09673702 -4.91907e-4 -0.08295631 -0.09215676 -4.90905e-4 -0.08363777 -0.09251165 2.31909e-4 -0.07266867 -0.1044058 -4.93432e-4 -0.07055366 -0.09840887 -4.91678e-4 -0.08085179 -0.09197819 -4.3751e-4 -0.08514797 -0.09922009 0.007138133 -0.08629798 -0.09672379 0.007023394 -0.08361524 -0.09199786 0.00702238 -0.08080261 -0.09170514 0.007020592 -0.07144278 -0.09722632 2.31909e-4 -0.07125836 -0.09705734 0.007063567 -0.07004278 -0.09989356 -3.81712e-5 -0.06978797 -0.09986859 0.007026314 -0.07248157 -0.1046136 0.00702238 -0.0752415 -0.1046468 -1.70583e-4 -0.0752933 -0.1049094 0.007100105 -0.09204381 -0.1070922 -4.03936e-5 -0.09082573 -0.109629 7.91635e-6 -0.09047079 -0.1093963 -4.2829e-4 -0.09121167 -0.1071292 -4.91907e-4 -0.08895623 -0.102549 -4.90905e-4 -0.08963769 -0.1029039 2.31909e-4 -0.07866859 -0.114798 -4.93432e-4 -0.07655358 -0.1088011 -4.91678e-4 -0.08685171 -0.1023703 -4.37516e-4 -0.0911417 -0.109613 0.007020592 -0.09229791 -0.1071159 0.007023394 -0.08961492 -0.1023901 0.007018923 -0.08680075 -0.1020938 0.007127344 -0.0774427 -0.1076185 2.31909e-4 -0.07725942 -0.1074506 0.007020592 -0.07604271 -0.1102858 -3.81612e-5 -0.07578808 -0.1102606 0.007021129 -0.07848143 -0.1150057 0.00702238 -0.08124142 -0.115039 -1.70586e-4 -0.08129322 -0.1153016 0.007100045 -0.09804373 -0.1174843 -4.03997e-5 -0.09682565 -0.1200212 7.91635e-6 -0.09647065 -0.1197885 -4.28287e-4 -0.09721159 -0.1175214 -4.91907e-4 -0.09495609 -0.1129412 -4.90905e-4 -0.09563761 -0.113296 2.31909e-4 -0.08466845 -0.1251901 -4.93432e-4 -0.0825535 -0.1191932 -4.91678e-4 -0.09285163 -0.1127625 -4.37515e-4 -0.09714162 -0.1200051 0.007020592 -0.09829783 -0.1175081 0.007023394 -0.09561508 -0.1127823 0.00702238 -0.09280025 -0.1124842 0.007172763 -0.08344256 -0.1180106 2.31909e-4 -0.08325934 -0.1178427 0.007020592 -0.08204263 -0.1206779 -3.81826e-5 -0.081788 -0.1206528 0.007021129 -0.08448135 -0.1253979 0.00702238 -0.08724129 -0.1254311 -1.70593e-4 -0.08729314 -0.1256937 0.007100045 -0.1040437 -0.1278766 -4.03566e-5 -0.1028255 -0.1304134 7.91635e-6 -0.1024706 -0.1301807 -4.28286e-4 -0.1032115 -0.1279135 -4.91907e-4 -0.100956 -0.1233333 -4.90905e-4 -0.1016376 -0.1236882 2.31909e-4 -0.09066838 -0.1355823 -4.93432e-4 -0.08855342 -0.1295854 -4.91678e-4 -0.09885156 -0.1231546 -4.37512e-4 -0.1031416 -0.1303973 0.007020592 -0.1042978 -0.1279003 0.007023394 -0.1016147 -0.1231744 0.007018923 -0.09880053 -0.1228782 0.007127285 -0.08944249 -0.1284028 2.31909e-4 -0.08925926 -0.1282349 0.007020592 -0.08804255 -0.1310701 -3.81394e-5 -0.08778786 -0.1310451 0.007021129 -0.09048128 -0.1357901 0.00702238 -0.09324121 -0.1358233 -1.70596e-4 -0.09329307 -0.1360858 0.007098019 -0.1100436 -0.1382687 -4.03512e-5 -0.1088255 -0.1408056 7.91635e-6 -0.1084705 -0.1405728 -4.28288e-4 -0.1092115 -0.1383057 -4.91907e-4 -0.106956 -0.1337255 -4.90905e-4 -0.1076374 -0.1340804 2.31909e-4 -0.0966683 -0.1459744 -4.93432e-4 -0.09455329 -0.1399776 -4.91678e-4 -0.1048515 -0.1335468 -4.37516e-4 -0.1091415 -0.1407895 0.007020592 -0.1102977 -0.1382924 0.007023394 -0.1076149 -0.1335666 0.00702238 -0.1048023 -0.1332738 0.007020592 -0.09544241 -0.138795 2.31909e-4 -0.09525817 -0.1386259 0.007064759 -0.09404242 -0.1414623 -3.81385e-5 -0.09378784 -0.1414371 0.007019639 -0.09648144 -0.1461822 0.007018923 -0.09924113 -0.1462155 -1.70558e-4 -0.09929341 -0.146478 0.00710541 -0.1160435 -0.1486608 -4.03493e-5 -0.1148254 -0.1511977 7.91635e-6 -0.1144705 -0.1509649 -4.28289e-4 -0.1152114 -0.1486979 -4.91907e-4 -0.1129559 -0.1441176 -4.90905e-4 -0.1136373 -0.1444725 2.31909e-4 -0.1026682 -0.1563666 -4.93432e-4 -0.1005533 -0.1503697 -4.91678e-4 -0.1108514 -0.143939 -4.37491e-4 -0.1151413 -0.1511817 0.007020592 -0.1162976 -0.1486846 0.007023394 -0.1136148 -0.1439588 0.00702238 -0.1108022 -0.143666 0.007020592 -0.1014423 -0.1491872 2.31909e-4 -0.1012579 -0.1490182 0.007063567 -0.1000424 -0.1518545 -3.81715e-5 -0.09978777 -0.1518294 0.007020771 -0.1024811 -0.1565744 0.00702238 -0.105241 -0.1566078 -1.70509e-4 -0.1052929 -0.1568701 0.007098078 -0.1220511 -0.1590666 -3.76292e-5 -0.1208253 -0.1615899 7.91635e-6 -0.1204704 -0.1613571 -4.2829e-4 -0.1212113 -0.15909 -4.91907e-4 -0.1189558 -0.1545098 -4.90905e-4 -0.1196372 -0.1548647 2.31909e-4 -0.1086682 -0.1667588 -4.93432e-4 -0.1065531 -0.1607619 -4.91678e-4 -0.1168513 -0.1543313 -4.37501e-4 -0.1208368 -0.1619061 0.007020592 -0.1223081 -0.159096 0.007021129 -0.1196145 -0.1543509 0.007018983 -0.1167988 -0.1540518 0.007216811 -0.1074423 -0.1595794 2.31909e-4 -0.107259 -0.1594114 0.007020592 -0.1060423 -0.1622467 -3.81629e-5 -0.1057875 -0.1622217 0.00702548 -0.1084811 -0.1669666 0.00702238 -0.1112409 -0.1669999 -1.7048e-4 -0.1112948 -0.1672649 0.007163405 -0.1266304 -0.1721165 -4.0699e-4 -0.117677 -0.177299 -9.58104e-5 -0.1146798 -0.1771717 -4.90595e-4 -0.1280529 -0.169463 -5.02482e-5 -0.1272112 -0.1694822 -4.91907e-4 -0.1128844 -0.1726197 -4.91907e-4 -0.1242811 -0.164611 -4.91953e-4 -0.1177335 -0.177554 0.007020592 -0.128308 -0.1694881 0.007021129 -0.1254411 -0.1649402 -8.23217e-5 -0.1256147 -0.1647431 0.00702238 -0.1228545 -0.1647107 -1.88158e-4 -0.1228021 -0.1644504 0.007020592 -0.1134507 -0.1699802 -9.81257e-5 -0.1132579 -0.1698024 0.007064759 -0.1120422 -0.1726388 -3.81599e-5 -0.1117875 -0.1726136 0.007019639 -0.1144872 -0.1773694 0.007021725 -0.1340422 -0.1798436 -4.46802e-5 -0.1328251 -0.1823742 7.91635e-6 -0.1324703 -0.1821414 -4.28292e-4 -0.1320995 -0.1779491 -4.91907e-4 -0.1314373 -0.175333 -1.11897e-4 -0.1288516 -0.1751154 -4.382e-4 -0.1206811 -0.1875445 -4.9344e-4 -0.1185529 -0.1815463 -4.91678e-4 -0.131611 -0.1751354 0.007009565 -0.1288019 -0.1748425 0.007020592 -0.1194421 -0.1803637 2.31909e-4 -0.1192577 -0.1801947 0.007063567 -0.1180428 -0.1830298 -3.96975e-5 -0.1177887 -0.1830044 0.007009863 -0.1232296 -0.1877853 -1.65401e-4 -0.1139153 -0.1840232 0.007386505 -0.03600299 -0.0596503 0.003635168 -0.04612517 -0.07624822 0.003962278 -0.04588037 -0.07373124 0.004564821 -0.047459 -0.07755661 0.00431317 -0.05076295 -0.0790053 0.005738794 -0.05339956 -0.07798212 0.00783044 -0.05675643 -0.09258598 0.004689157 -0.05416291 -0.08772957 0.004816412 -0.05637603 -0.09035181 0.005152046 -0.05599671 -0.08730995 0.005957722 -0.05822265 -0.08745986 0.006947755 -0.0591728 -0.09536057 0.005185246 -0.06710195 -0.1091201 0.005173981 -0.06617194 -0.1065435 0.005516886 -0.06203907 -0.0965684 0.006453394 -0.06344646 -0.09545058 0.00781846 -0.07027024 -0.1131677 0.005680441 -0.07715159 -0.1258364 0.005415618 -0.0759086 -0.1219803 0.005949556 -0.07708489 -0.1240251 0.005927264 -0.07246005 -0.1149117 0.005726456 -0.08055061 -0.1297085 0.005960524 -0.08188706 -0.1331282 0.005734264 -0.08690285 -0.1427313 0.00541377 -0.08562278 -0.1387907 0.005960941 -0.08736151 -0.1416902 0.005928993 -0.09022402 -0.1478096 0.005650341 -0.09635084 -0.1597967 0.005168378 -0.09556037 -0.1561741 0.005725502 -0.09198379 -0.1499605 0.005871236 -0.100108 -0.1647127 0.005579948 -0.1012669 -0.1680606 0.005256056 -0.1048004 -0.1747371 0.005061089 -0.105487 -0.1770154 0.004680216 -0.1068773 -0.1777979 0.00517106 -0.1068325 -0.1741545 0.006585717 -0.1028033 -0.166627 0.006586194 -0.03910642 -0.05785846 0.006144404 -0.1397936 -0.1823828 0.008884549 -0.1404005 -0.1832595 0.009360253 -0.1283158 -0.1853715 0.008779823 -0.1246284 -0.2143714 0.009994387 -0.1227093 -0.2116603 0.009994387 -0.1242534 -0.2126439 0.01049453 -0.127013 -0.2166836 0.009994387 -0.1321377 -0.219042 0.01049548 -0.129782 -0.2185184 0.009994387 -0.137038 -0.2206748 0.01000654 -0.1417353 -0.2195197 0.01049453 -0.1438612 -0.2198685 0.009988605 -0.1505236 -0.2151893 0.01049566 -0.1548736 -0.2096766 0.009994387 -0.154873 -0.2066816 0.01049435 -0.1562888 -0.2032147 0.009994387 -0.1548327 -0.1969068 0.01049554 -0.1525946 -0.1917192 0.009992182 -0.1479233 -0.1883173 0.01049697 -0.1433233 -0.185001 0.009780883 -0.1400216 -0.1855388 0.01049453 -0.1235265 -0.1941323 0.01049435 -0.1212325 -0.2001953 0.01049363 -0.1214223 -0.2061223 0.01049411 -0.1490437 -0.1882063 0.009970724 -0.1538857 -0.1936606 0.009994387 -0.1552742 -0.1966781 0.009994387 -0.1560842 -0.1998995 0.009994387 -0.1558805 -0.2065112 0.009994387 -0.1533021 -0.2126029 0.009994387 -0.1503903 -0.2161095 0.009996354 -0.1328408 -0.2198132 0.009994387 -0.1328422 -0.2198933 -0.009505212 -0.1268901 -0.2165958 -0.009201049 -0.1377643 -0.2206523 -0.009505331 -0.142715 -0.2201882 -0.009505212 -0.1472975 -0.2182487 -0.009505331 -0.1512686 -0.2152496 -0.009505212 -0.1541455 -0.2111946 -0.009505331 -0.1559494 -0.2065519 -0.009505212 -0.1562264 -0.2006641 -0.009476065 -0.1562262 -0.2010627 -0.003559112 -0.1561755 -0.2046595 0.00159657 -0.1555536 -0.2078493 0.004578232 -0.1533699 -0.2126411 0.00749129 -0.1488685 -0.2173158 0.008967101 -0.1447753 -0.2194692 0.008839666 -0.1394047 -0.2207038 0.00749129 -0.1349493 -0.2203544 0.005108773 -0.1322174 -0.219621 0.002894759 -0.12987 -0.2185842 8.75628e-5 -0.1279495 -0.2173883 -0.003559112 -0.151012 -0.1894634 0.005560398 -0.09956461 -0.1657697 -3.37208e-4 -0.09110677 -0.1502361 -3.37208e-4 -0.08240342 -0.1348491 -3.37208e-4 -0.07345479 -0.1196084 -3.37208e-4 -0.06426095 -0.1045141 -3.37208e-4 -0.0548222 -0.08956593 -3.37208e-4 -0.04513871 -0.07476389 -3.37208e-4 -0.03521102 -0.0601086 -3.30678e-4 -0.1522858 -0.1913325 0.003149688 -0.1467214 -0.1862855 0.007465422 -0.1032052 -0.1706634 -8.69845e-4 -0.04691135 -0.07414466 -0.001387298 -0.1057416 -0.1735629 -0.001404404 -0.1089351 -0.1757985 -0.001490116 -0.1026426 -0.1676626 -0.001439869 -0.1007065 -0.1640424 -0.001397669 -0.09813094 -0.1592564 -0.001425087 -0.09597057 -0.1552917 -0.001397192 -0.0932818 -0.1504032 -0.001396536 -0.09116673 -0.1466019 -0.001393079 -0.08820575 -0.1413081 -0.00140351 -0.08340585 -0.1329407 -0.001393377 -0.07868444 -0.1266762 -8.54201e-4 -0.08118695 -0.129119 -0.001407921 -0.07811766 -0.1238898 -0.001410365 -0.07603341 -0.1203701 -0.001395881 -0.07307696 -0.1154423 -0.001397073 -0.07075488 -0.1116045 -0.001420855 -0.06782531 -0.1068175 -0.00142616 -0.06546574 -0.1030056 -0.001387476 -0.06651002 -0.1033113 -0.00149542 -0.06227087 -0.09788972 -0.001396298 -0.05984604 -0.09404283 -0.001443386 -0.05735206 -0.09013366 -0.00140661 -0.05496203 -0.08642452 -0.001387298 -0.05603456 -0.08662343 -0.001492798 -0.05099529 -0.08032894 -0.001390755 -0.04844719 -0.07643646 -0.001471996 -0.04680794 -0.07361567 -0.001491844 -0.0349754 -0.05623364 -0.001490235 -0.03396397 -0.05567795 -0.001196861 -0.03266423 -0.05345368 -0.001306772 -0.07355284 -0.1145468 -0.001491904 -0.07598894 -0.1207422 0.00508213 -0.07734251 -0.1192121 -0.001493632 -0.08105182 -0.1293421 0.00513637 -0.07785159 -0.1238851 0.0050987 -0.08312934 -0.1329246 0.005144715 -0.0838989 -0.1320459 -0.00149095 -0.08597302 -0.1378728 0.0051288 -0.08696919 -0.1376079 -0.001492559 -0.08795601 -0.1413578 0.005119383 -0.09102845 -0.1468528 0.005484461 -0.09275144 -0.1499074 0.005022764 -0.09376877 -0.1495338 -0.001491904 -0.09596127 -0.1557363 0.004933714 -0.09696286 -0.1559917 0.006182312 -0.09707427 -0.155223 -0.001490712 -0.09785431 -0.1592492 0.005353093 -0.100581 -0.1642638 0.004758954 -0.1023065 -0.1675103 0.004838764 -0.1035743 -0.1669809 -0.001491904 -0.1058105 -0.174169 0.004829347 -0.1068037 -0.1735249 -0.001491844 -0.1077404 -0.1713841 -0.001491844 -0.07728022 -0.1186199 -0.001491844 -0.07518374 -0.1149888 -0.001491844 -0.07265037 -0.1106008 -0.001491844 -0.06970989 -0.1055077 -0.001491844 -0.06718033 -0.1011264 -0.001491844 -0.06508392 -0.09749531 -0.001491844 -0.06255048 -0.09310734 -0.001491844 -0.05961 -0.08801424 -0.001491844 -0.0570805 -0.083633 -0.001491844 -0.05481624 -0.07971072 -0.001491904 -0.05245065 -0.07561385 -0.001491844 -0.04933255 -0.07021564 -0.001491844 -0.03665715 -0.05665838 -0.001491844 -0.04837936 -0.07032096 -0.001491844 -0.05227291 -0.0767014 -0.00149244 -0.05156743 -0.07937973 -0.001491963 -0.05717587 -0.08409476 -0.001491844 -0.05859392 -0.08761042 -0.00149244 -0.06473165 -0.09718185 -0.001491844 -0.06245845 -0.09418666 -0.001490235 -0.06282436 -0.09697073 -0.001491785 -0.0672757 -0.1015883 -0.001491844 -0.06871527 -0.1051043 -0.001492798 -0.07483154 -0.1146754 -0.001491844 -0.07249313 -0.1116542 -0.001493692 -0.07980972 -0.1230013 -0.001491844 -0.0827502 -0.1280943 -0.001491844 -0.08528363 -0.1324824 -0.001491844 -0.08493137 -0.1321688 -0.001491844 -0.08260142 -0.1291211 -0.001496076 -0.07884567 -0.1225983 -0.001492857 -0.08738005 -0.1361135 -0.001491844 -0.08990955 -0.1404948 -0.001491844 -0.09285008 -0.1455878 -0.001491844 -0.09522944 -0.1497085 -0.001491904 -0.09271401 -0.1466297 -0.001492857 -0.08747541 -0.1365753 -0.001491844 -0.08900052 -0.1400629 -0.001495599 -0.09747993 -0.153607 -0.001491844 -0.1000095 -0.1579882 -0.001491844 -0.1029499 -0.1630814 -0.001491844 -0.1053202 -0.1671863 -0.001491904 -0.1027756 -0.1641481 -0.001494944 -0.09757524 -0.1540688 -0.001491844 -0.09905636 -0.1575536 -0.001495599 -0.1082651 -0.1247951 0.005220115 -0.1052755 -0.1196503 0.005149126 -0.1042369 -0.1197665 0.0066877 -0.103434 -0.1164407 0.005137443 -0.1003103 -0.1109077 0.005518913 -0.09830534 -0.1073727 0.005074441 -0.09520822 -0.1018069 0.005018889 -0.09342867 -0.1038147 0.007028043 -0.09349632 -0.0986455 0.005493342 -0.09066593 -0.09345692 0.005285203 -0.08890789 -0.09023553 0.004768848 -0.08562606 -0.08407038 0.004684984 -0.08372414 -0.08041876 0.005050599 -0.0797823 -0.07284677 0.00462377 -0.07914388 -0.07367342 0.005716681 -0.07603484 -0.06552696 0.004011571 -0.05816727 -0.03219848 -0.006052792 -0.0539357 -0.02777361 -0.02125513 -0.05857884 -0.03314822 -0.006772816 -0.05456066 -0.02897745 -0.02125513 -0.05853337 -0.03425252 -0.007355868 -0.05465298 -0.03029614 -0.02125513 -0.05803847 -0.03532773 -0.007705032 -0.05419617 -0.03149485 -0.02125513 -0.0640859 -0.0389418 0.005145013 -0.05452513 -0.02732187 0.005319595 -0.03485023 -0.04909431 -0.007755339 -0.03351289 -0.04948753 -0.007705032 -0.03233432 -0.04937857 -0.007355868 -0.03135526 -0.04886579 -0.006772816 -0.03073847 -0.04803442 -0.006052792 -0.04580146 -0.02859002 -0.02125513 -0.04987055 -0.03221118 -0.02125513 -0.05201351 -0.03117936 -0.02125513 -0.05245703 -0.02955305 -0.02125513 -0.05252712 -0.02651792 -0.02125513 -0.05172121 -0.02779817 -0.02125513 -0.05087858 -0.02589392 -0.02125513 -0.04943299 -0.02714937 -0.02125513 -0.04911565 -0.02588051 -0.02125513 -0.04802256 -0.02807259 -0.02125513 -0.04740959 -0.02987408 -0.02125513 -0.04815608 -0.03138548 -0.02125513 -0.05609279 -0.04460567 -0.002104878 -0.1271083 -0.2162498 -0.006679832 -0.1304504 -0.2183148 -0.009572207 -0.1330599 -0.219358 -0.009505331 -0.1354054 -0.2199196 -0.009505331 -0.1389753 -0.220182 -0.009512424 -0.14388 -0.2192805 -0.009511828 -0.1480655 -0.2172306 -0.009504616 -0.1508444 -0.2148596 -0.009505331 -0.1531172 -0.2120468 -0.009505093 -0.1546905 -0.2087854 -0.009505331 -0.1553769 -0.2064734 -0.009505331 -0.155739 -0.2040891 -0.009505331 -0.1557697 -0.2016775 -0.009505331 -0.1557189 -0.2001713 -0.008558928 -0.1557274 -0.2010983 -0.003543138 -0.1557953 -0.2029237 -4.94574e-4 -0.1556139 -0.2051868 0.002251505 -0.155031 -0.2077821 0.004597306 -0.1534869 -0.2113811 0.006962954 -0.1516981 -0.2139537 0.00812751 -0.1491989 -0.2163774 0.008846998 -0.1462565 -0.2182687 0.00899285 -0.1499537 -0.2163895 -0.004073381 -0.1452451 -0.2193616 -0.004041373 -0.1484792 -0.2169815 -0.004158914 -0.1492307 -0.2163808 0.00218749 -0.1459022 -0.2190246 0.001281201 -0.1457834 -0.2184953 0.001920998 -0.1440593 -0.2191964 -0.002487123 -0.147262 -0.2177308 -0.005515038 -0.1498972 -0.2157682 -0.003463804 -0.1458332 -0.2185633 4.56477e-4 -0.1514952 -0.2149868 0.002415895 -0.1544655 -0.2108387 -0.001167714 -0.1532185 -0.2126284 -0.001094281 -0.1538787 -0.2107737 -0.004649937 -0.1545364 -0.2107067 -0.005421996 -0.1507225 -0.2157877 -0.002693474 -0.152195 -0.2134827 -0.001556754 -0.1542859 -0.2097749 -0.001502096 -0.1523104 -0.213189 0.00198847 -0.1519272 -0.213652 -0.005490064 -0.1521765 -0.2133488 1.11704e-4 -0.13727 -0.2202006 0.001533865 -0.1383935 -0.2206833 0.002309501 -0.13696 -0.2206344 -0.001301288 -0.1399566 -0.2203782 -0.002609848 -0.1377133 -0.2207143 -0.005422711 -0.1364646 -0.2200639 -0.005530059 -0.139223 -0.2201434 -0.00518006 -0.1430913 -0.2201246 -0.001653611 -0.1416099 -0.2198785 -0.002207159 -0.1425201 -0.2196683 0.00224924 -0.1432035 -0.220044 0.0018453 -0.1392666 -0.2202859 0.001178741 -0.1297765 -0.2179455 -4.94575e-4 -0.1318271 -0.2189201 0.002251505 -0.1337024 -0.2195321 0.004037797 -0.1357983 -0.2199808 0.005601525 -0.1425584 -0.2196634 -0.004268109 -0.1431737 -0.2194932 0.008602499 -0.1389833 -0.2201976 0.007319867 -0.1538992 -0.210768 0.001584529 -0.03361904 -0.05653178 0.005145013 -0.03446292 -0.05603873 0.006144464 -0.03812688 -0.05842292 0.006144404 -0.05188405 -0.02796763 0.006144404 -0.04966503 -0.0271117 0.006144404 -0.0522896 -0.02649533 0.00614345 -0.04941546 -0.02650403 0.006144404 -0.04802256 -0.02807259 0.006144404 -0.0308423 -0.03722667 0.006144404 -0.03283995 -0.0371617 0.006144404 -0.03165888 -0.03735363 0.006144404 -0.03068882 -0.03806394 0.006438851 -0.02782285 -0.040798 0.005770266 -0.03007984 -0.03963905 0.006144404 -0.04750961 -0.02915364 0.006144404 -0.03397494 -0.03754061 0.006144404 -0.04768651 -0.03083008 0.006144404 -0.0351268 -0.03905522 0.006144404 -0.04916739 -0.03202503 0.006144404 -0.03489738 -0.04072529 0.006144404 -0.04055964 -0.04939025 0.006144404 -0.03353261 -0.04205137 0.006144404 -0.03819698 -0.04966354 0.006144404 -0.03117316 -0.04175132 0.006144404 -0.03707975 -0.05176323 0.006144404 -0.02908021 -0.04215627 0.006144404 -0.05450952 -0.04127782 0.006144404 -0.05468642 -0.04295432 0.006144404 -0.04212671 -0.05117946 0.006144404 -0.0561673 -0.04414921 0.006144404 -0.04189723 -0.05284947 0.006144404 -0.05735999 -0.04424554 0.006144404 -0.04053252 -0.05417555 0.006144404 -0.03817307 -0.0538755 0.006144404 -0.05085289 -0.0320515 0.006144404 -0.05787992 -0.03939038 0.006144404 -0.05551725 -0.03966367 0.006144404 -0.05244016 -0.03028017 0.006144404 -0.05390578 -0.02782326 0.006144404 -0.06323981 -0.03943026 0.006144404 -0.05944699 -0.04117959 0.006144404 -0.05886471 -0.0434857 0.006144404 -0.06347018 -0.04379218 0.006144404 -0.02818 -0.04250538 0.005145013 -0.02811664 -0.03905344 0.005144715 -0.02897441 -0.03752171 0.005144536 -0.05333667 -0.02606362 0.005144894 -0.04994499 -0.02541434 0.005144536 -0.05170047 -0.02543735 0.005144715 -0.03511989 -0.04028004 -0.01625519 -0.03456377 -0.03796756 -0.01625519 -0.03353261 -0.04205137 -0.01625519 -0.03117316 -0.04175132 -0.01625519 -0.03007984 -0.03963905 -0.01625519 -0.03070229 -0.03807246 -0.01625519 -0.03234469 -0.03711152 -0.01625519 -0.03413373 -0.04005461 -0.01625567 -0.03373324 -0.03855925 -0.01625561 -0.03303533 -0.04115074 -0.01625508 -0.03155565 -0.0407502 -0.01624691 -0.03113877 -0.03965359 -0.01625519 -0.03123801 -0.03909152 -0.0162301 -0.03224581 -0.03818213 -0.01624238 -0.05244016 -0.03028017 -0.01625519 -0.05188405 -0.02796763 -0.01625519 -0.05085289 -0.0320515 -0.01625519 -0.0484935 -0.03175145 -0.01625519 -0.04755777 -0.03034925 -0.01625519 -0.04769998 -0.02845162 -0.01625519 -0.04966503 -0.0271117 -0.01625519 -0.051454 -0.03005474 -0.01625567 -0.05105352 -0.02855944 -0.01625561 -0.05035561 -0.03115087 -0.01625508 -0.04887592 -0.03075033 -0.01624691 -0.04845911 -0.02965372 -0.01625519 -0.04855829 -0.02909159 -0.0162301 -0.04956614 -0.02818226 -0.01624238 -0.05765455 -0.03932297 0.001293897 -0.05912399 -0.04052793 0.001144468 -0.05532938 -0.03980487 0.001144468 -0.05452239 -0.0412817 0.001293718 -0.0548039 -0.04315787 0.001144468 -0.0568704 -0.04433536 0.001144468 -0.05842155 -0.04379135 0.001237034 -0.0594871 -0.0421741 0.001144468 -0.04140084 -0.04992222 0.001144468 -0.03910857 -0.04928165 0.001294374 -0.03727883 -0.0507881 0.001144468 -0.03748363 -0.05315768 0.001144468 -0.03955012 -0.05433523 0.001144468 -0.04169309 -0.05330348 0.001144468 -0.04211395 -0.0516057 0.001276135 -0.0394783 -0.05205559 5.71646e-4 -0.03440099 -0.03779804 0.001144468 -0.03283995 -0.0371617 0.001144468 -0.03100913 -0.03768056 0.001144468 -0.03018933 -0.03915351 0.001144468 -0.03048372 -0.0410335 0.001144468 -0.03184711 -0.04202491 0.001144468 -0.03374886 -0.04195922 0.001144468 -0.03516691 -0.04004979 0.001144468 -0.0337159 -0.03857672 0.001133918 -0.03223919 -0.03815859 0.001145064 -0.03115969 -0.03922152 0.001145184 -0.03121256 -0.0401951 0.001136422 -0.03208619 -0.04105931 0.001096606 -0.0330249 -0.0411275 0.001128554 -0.03410983 -0.04004842 0.001130878 -0.05172121 -0.02779817 0.001144468 -0.05016022 -0.02716183 0.001144468 -0.04832941 -0.02768075 0.001144468 -0.04740959 -0.02987408 0.001144468 -0.04815608 -0.03138548 0.001144468 -0.04987055 -0.03221118 0.001144468 -0.05201351 -0.03117936 0.001144468 -0.05245703 -0.02955305 0.001144468 -0.05103617 -0.02857685 0.001133918 -0.04955953 -0.02815872 0.001145064 -0.04847997 -0.02922159 0.001145184 -0.04853284 -0.03019529 0.001136422 -0.04940646 -0.03105944 0.001096606 -0.05034518 -0.03112763 0.001128554 -0.0514301 -0.03004854 0.001130878 -0.05695897 -0.0417779 2.43242e-4 -0.05034822 -0.02820509 -0.007555305 -0.05140805 -0.02926599 -0.007555365 -0.05101639 -0.03071767 -0.007555544 -0.04878914 -0.03059244 -0.00833553 -0.04890507 -0.02858644 -0.007552802 -0.03302788 -0.03820496 -0.007555305 -0.03408777 -0.03926587 -0.007555365 -0.03369611 -0.04071754 -0.007555544 -0.03146886 -0.04059231 -0.00833553 -0.03158479 -0.03858625 -0.007552802 -0.09796941 -0.1539393 0.007029771 -0.09541982 -0.1494436 0.007017433 -0.1237326 -0.1563046 0.007041513 -0.1262884 -0.1608102 0.007017433 -0.1143169 -0.1372895 0.006727695 -0.1136609 -0.1388593 0.007020413 -0.1161886 -0.1433168 0.007017433 -0.07774782 -0.1189144 0.007020175 -0.0752201 -0.1144566 0.007017433 -0.06666457 -0.1036151 0.0062536 -0.06767404 -0.1014658 0.007036626 -0.0650953 -0.09691953 0.007022976 -0.05750036 -0.08384156 0.007023572 -0.05498653 -0.07940626 0.007082879 -0.09598875 -0.1083298 0.007017433 -0.07818615 -0.07573252 0.006380856 -0.07769918 -0.07650965 0.007234573 -0.08132356 -0.08292812 0.007020592 -0.07322531 -0.06882631 0.007089376 -0.07582527 -0.07341182 0.007106304 -0.08333247 -0.08632946 0.007044255 -0.08591711 -0.09088736 0.007049143 -0.07122367 -0.06543463 0.007020592 -0.07177454 -0.06580573 0.007050096 -0.0725494 -0.06531399 0.00619173 -0.07415765 -0.06173288 0.004401028 -0.08832037 -0.09324431 0.006285071 -0.1036937 -0.1216745 0.007020592 -0.1060972 -0.1258328 0.007018327 -0.07061886 -0.1118527 0.005472958 -0.0675404 -0.1068101 0.005328655 -0.05971843 -0.0942769 0.005032181 -0.05710214 -0.09012091 0.00440669 -0.06281054 -0.09456443 0.006430089 -0.04652303 -0.0736953 0.003854334 -0.04832243 -0.07664632 0.004322052 -0.05256837 -0.07707703 0.006355285 -0.05680429 -0.05012822 0.007200002 -0.0472598 -0.05548965 0.007020592 -0.04578858 -0.05830049 0.007019996 -0.1287286 -0.1632022 0.006348848 -0.1209264 -0.1459279 0.005394816 -0.1239092 -0.1508078 0.004768073 -0.1186196 -0.1457252 0.006283938 -0.1079981 -0.1289893 0.00723505 -0.1084516 -0.1282535 0.006357729 -0.1116231 -0.1354086 0.007020592 -0.1121739 -0.1357797 0.007050096 -0.1136423 -0.1337389 0.00561285 -0.08531022 -0.1319332 0.007018923 -0.09350651 -0.1462709 0.00723505 -0.08988147 -0.1398515 0.007020592 -0.08933287 -0.1394645 0.007272601 -0.09973889 -0.1569476 0.007006108 -0.1023085 -0.1686171 0.005363106 -0.1036947 -0.1635563 0.007391989 -0.08785837 -0.1364265 0.007021427 -0.0827704 -0.1331996 0.005844116 -0.1281088 -0.1641842 0.007385492 -0.1289062 -0.1611922 0.006577253 -0.1261132 -0.1541947 0.004969537 -0.1298865 -0.1601919 0.004784524 -0.121703 -0.1530842 0.007384955 -0.118009 -0.1466859 0.007385194 -0.1184436 -0.1436802 0.006822228 -0.1189066 -0.1424751 0.005567312 -0.110376 -0.1284122 0.005120694 -0.07980173 -0.1221759 0.007384955 -0.08349555 -0.1285742 0.007385253 -0.06970185 -0.1046825 0.007384955 -0.07339572 -0.1110806 0.007385253 -0.06562465 -0.1038414 0.005367517 -0.06190359 -0.09787374 0.005175054 -0.05967622 -0.08731663 0.007384419 -0.06309461 -0.0934534 0.007043123 -0.05455338 -0.0871905 0.004921555 -0.05493521 -0.08674424 0.004216372 -0.05068242 -0.08036804 0.00455445 -0.1015031 -0.1180971 0.007384955 -0.09780931 -0.111699 0.007385194 -0.09865695 -0.1070831 0.005773186 -0.0914033 -0.1006036 0.007384955 -0.0925427 -0.1006523 0.006256759 -0.08770942 -0.09420543 0.007385194 -0.08243513 -0.08326315 0.006807863 -0.07694584 -0.06618022 0.004688382 -0.04950219 -0.06969553 0.007384955 -0.05319595 -0.07609367 0.007385253 -0.06806939 -0.05814075 0.006730675 -0.06771218 -0.05935245 0.007020592 -0.08606088 -0.08378142 0.005323946 -0.1427291 -0.201879 -0.01350528 -0.1426313 -0.2040923 -0.01350528 -0.140666 -0.2065652 -0.01350528 -0.1375598 -0.2071692 -0.01350528 -0.135405 -0.2061076 -0.01350528 0.1255159 0.1830042 0.001158058 0.1271951 0.1870754 6.38793e-4 0.1228247 0.1824038 5.46944e-4 0.1254148 0.1896535 5.79242e-4 0.1245376 0.1894716 0.001088261 0.1221144 0.1830155 0.001093804 0.1273245 0.1872513 0.004816174 0.1254926 0.1900461 0.007212281 0.1256043 0.1829114 0.004441022 0.09937798 0.1925995 5.3963e-4 0.1036261 0.1974925 5.60721e-4 0.1006665 0.1968224 0.001142561 0.1010359 0.1902117 5.99427e-4 0.1018742 0.1903959 0.001092851 0.1042972 0.1968417 0.001098811 0.1045191 0.1968444 0.007020592 0.1019662 0.1898441 0.007025659 0.1009153 0.1898673 0.007242143 0.09918147 0.192503 0.004929959 0.1237055 0.1788879 -0.001417577 0.1265259 0.1876835 -0.001489818 0.1284434 0.1855319 -3.38348e-4 0.1207541 0.1790342 -0.00149244 0.09975379 0.1928991 -0.001409947 0.1003158 0.1866014 -0.001494288 0.09816676 0.1883906 -0.001460433 0.1040665 0.1979578 0.007166385 0.1005395 0.1969248 0.004745185 0.1230778 0.1749922 -8.69784e-4 0.1217107 0.1691598 -3.37208e-4 0.09365373 0.09391069 -8.67763e-4 0.09747898 0.1027413 -3.37208e-4 0.09209513 0.08590227 -3.37208e-4 0.08858424 0.07749819 -8.54144e-4 0.08698058 0.0689696 -3.37208e-4 0.08381044 0.0615704 -9.07959e-4 0.08213508 0.05194348 -3.37208e-4 0.07954251 0.04816085 -0.001200377 0.07867449 0.04571574 -0.001306772 0.1152479 0.1526959 -3.37208e-4 0.1196544 0.1689257 -0.001397848 0.1176429 0.1638756 -0.001425147 0.1213524 0.1731309 -0.001387 0.1203427 0.1726306 -0.001494765 0.1124274 0.150404 -0.001391768 0.1090552 0.1361381 -3.37208e-4 0.1103059 0.1447839 -0.001409292 0.1140524 0.1546576 -0.001387178 0.1130828 0.1542252 -0.001492738 0.1068556 0.1354289 -0.001396059 0.1031322 0.1194865 -3.37208e-4 0.1054496 0.1315283 -0.001408696 0.1002781 0.1167891 -0.001387298 0.0987367 0.1122743 -0.001419663 0.09925574 0.1162561 -0.001496553 0.09560674 0.1028764 -0.001389503 0.09228682 0.0926581 -0.001426756 0.09695315 0.1069552 -0.001425266 0.08964866 0.0841571 -0.001389563 0.08746582 0.07699459 -0.001395106 0.09090411 0.08820813 -0.001449346 0.08614116 0.07257038 -0.00141257 0.08502632 0.06950992 -0.001491844 0.07931751 0.04927563 -0.001490235 0.1019729 0.1216995 -0.001396775 0.1034151 0.1258118 -0.001411378 0.1087652 0.1406349 -0.00141412 0.1160371 0.159783 -0.001431107 0.1212812 0.1892137 -0.001491844 0.1214347 0.1896354 -0.001598238 0.119101 0.1744841 -0.001491844 0.1174752 0.1700249 -0.001491844 0.1154637 0.1644986 -0.001491844 0.1137335 0.1597447 -0.001491844 0.1141273 0.1601648 -0.001494348 0.1158065 0.1634828 -0.001493573 0.1230051 0.179692 -0.001491844 0.1183907 0.1705963 -0.001492738 0.1122994 0.1558046 -0.001491844 0.1105665 0.1510434 -0.001491844 0.1085551 0.1455171 -0.001491844 0.1068248 0.1407631 -0.001491844 0.1071173 0.141133 -0.001491844 0.1088649 0.144521 -0.001492679 0.1081517 0.1414326 -0.00149101 0.1122857 0.1553333 -0.001491844 0.1113978 0.1516291 -0.001496136 0.1053907 0.1368231 -0.001491844 0.1036579 0.1320618 -0.001491844 0.1016464 0.1265355 -0.001491844 0.0999161 0.1217816 -0.001491844 0.1002086 0.1221515 -0.001491844 0.1019701 0.1255421 -0.00149393 0.1013542 0.1224784 -0.001491904 0.1054245 0.1362379 -0.001493752 0.1045317 0.1326251 -0.001492679 0.0718134 0.05330204 -0.001491844 0.09848201 0.1178416 -0.001491844 0.09674912 0.1130804 -0.001491844 0.0984683 0.1173703 -0.001491844 0.09764933 0.1136488 -0.001492798 0.09473764 0.107554 -0.001491844 0.09300738 0.1028 -0.001491844 0.0932998 0.1031699 -0.001491844 0.0950818 0.1065368 -0.001493573 0.09497117 0.1036571 -0.001491546 0.09157329 0.09886002 -0.001491844 0.08984041 0.0940988 -0.001491844 0.08782899 0.0885725 -0.001491844 0.08621263 0.08413231 -0.001491904 0.08817273 0.08753454 -0.00149244 0.08900988 0.08493143 -0.001491785 0.09155958 0.09838873 -0.001491844 0.09072637 0.09472203 -0.001490235 0.09273356 0.09665834 -0.001494944 0.08466464 0.0798785 -0.001491844 0.08293169 0.07511729 -0.001491844 0.08081394 0.06928968 -0.001491844 0.07856279 0.05083441 -0.001491844 0.08149403 0.06859624 -0.001491844 0.08465093 0.07940715 -0.001491844 0.08337968 0.07556587 -0.001491844 0.0840106 0.07551044 -0.001491844 0.08639711 0.07684785 -0.001491904 0.0568369 0.05797564 -0.002104878 0.1066334 0.1947904 -0.001518845 0.1069288 0.1956022 -0.002104878 0.05708676 0.05866211 -0.001491844 0.1012219 0.1968821 -0.001483142 0.1054551 0.1996377 -0.004883885 0.09870117 0.1963569 -3.37844e-4 0.1010395 0.2040171 -0.006993174 0.05851823 0.07257503 0.001748263 0.05557596 0.0648294 0.001749038 0.05585539 0.06376785 0.002342879 0.05919635 0.07260584 0.002734303 0.05591803 0.07713651 0.002353668 0.05612444 0.07568377 0.00177133 0.05126249 0.06632339 0.001753568 0.05054396 0.06566864 0.003158628 0.05533337 0.07625424 0.003838598 0.0561822 0.07706451 0.005031764 0.05893641 0.0732181 0.007615447 0.05920529 0.07253319 0.007008969 0.07374435 0.05913484 -9.82204e-4 0.07554817 0.06396877 -9.54372e-4 0.07476097 0.06493115 -0.001491904 0.07113212 0.0594474 -0.001491844 0.07115232 0.05845361 -9.51175e-4 0.0601269 0.06348419 -0.001491904 0.06100869 0.06209611 -8.44786e-4 0.0593397 0.0644465 -9.54358e-4 0.06375575 0.06896787 -0.001491844 0.06114602 0.06928575 -9.86722e-4 0.06404453 0.06991839 -9.04637e-4 0.07387948 0.06632047 -8.39336e-4 0.06358069 0.07023578 0.007169783 0.06087946 0.0694825 0.007015883 0.07391309 0.06661492 0.007020592 0.07585012 0.06410217 0.007021546 0.07402205 0.05896371 0.007015764 0.08458226 0.06589645 0.003817677 0.08370506 0.06657016 0.002345263 0.08396518 0.06562006 0.001776635 0.08077281 0.05528974 0.001747786 0.08119124 0.05453354 0.002987742 0.07923251 0.0653885 0.002465963 0.07974606 0.06473016 0.001745581 0.07597696 0.05655312 0.002386271 0.07701021 0.0568785 0.001747369 0.07909315 0.0653612 0.00700742 0.07608067 0.05708712 0.007007479 0.08356177 0.06661844 0.005267739 0.129151 0.2018343 -0.003043234 0.1260706 0.1934518 -0.003336012 0.1297011 0.2021023 -0.003891527 0.1267185 0.1935607 -0.00390917 0.1288355 0.1913952 -0.003323137 0.1336024 0.2023031 -0.003351032 0.1282029 0.191071 -0.004001855 0.1325129 0.2028515 -0.003991901 0.1275701 0.1912182 -0.003040313 0.1278144 0.1903201 0.006015419 0.1256815 0.1933254 0.007032871 0.1274495 0.1982982 0.007020592 0.1288425 0.2022659 0.008440434 0.1056238 0.2009927 -0.002793252 0.1087034 0.2093839 -0.003188848 0.1050545 0.200725 -0.003605306 0.1076196 0.2092868 -0.00375539 0.106451 0.2126337 -0.003753364 0.1053886 0.2120943 -0.002887368 0.102558 0.2001272 -0.003679513 0.1021012 0.201081 -0.002790272 0.1065078 0.2131859 0.006469964 0.1089187 0.209891 0.009074389 0.1090579 0.209184 0.008307158 0.1074872 0.2049522 0.007481753 0.1058958 0.2006313 0.007001221 0.1332114 0.1966882 -0.007755339 0.1294743 0.2027812 -0.007756114 0.134917 0.204939 -0.0077551 0.1328365 0.2038584 -0.007777929 0.1297417 0.2025797 0.008944749 0.1334938 0.2034882 0.006241083 0.1339809 0.2023997 0.005226492 0.1096749 0.2031532 -0.007645308 0.1020157 0.2072718 -0.007729828 0.107629 0.2124162 -0.007752895 0.1016579 0.2004852 0.004541993 0.1040441 0.2089906 0.004535496 0.1055012 0.213389 0.005235671 0.1022208 0.1996518 0.005758166 0.1120709 0.2071086 -0.00774008 0.1090373 0.2102177 -0.007781147 0.1062166 0.2153859 -0.007755398 0.105301 0.2185319 -0.007756352 0.1261711 0.2023493 -0.007767379 0.1246207 0.1986287 -0.007691979 0.1316814 0.1931499 -0.00723958 0.1244183 0.1958189 -0.006954848 0.1252809 0.1923417 -0.004801571 0.1216555 0.1902422 -0.002104878 0.1331686 0.2259094 -0.01605314 0.134019 0.2238832 -0.01850515 0.1332528 0.2261981 -0.01850521 0.1331478 0.2241593 -0.01648736 0.1365979 0.2249596 -0.0156669 0.1377261 0.2255446 -0.01821261 0.1355177 0.2274387 -0.01599997 0.1365147 0.2278122 -0.01850217 0.1390278 0.2213977 -0.01277178 0.1381241 0.2203565 -0.01790952 0.1389054 0.220143 -0.01249659 0.1357755 0.2184393 -0.01608669 0.1341379 0.2194242 -0.01850515 0.1368414 0.2176182 -0.0184943 0.114268 0.2268553 -0.0158143 0.1160093 0.2256634 -0.01850515 0.1133168 0.2274731 -0.01850521 0.115809 0.2289077 -0.01644003 0.1146198 0.2298253 -0.01850992 0.1176321 0.2275024 -0.01651757 0.1119245 0.2224548 -0.01365596 0.1158252 0.2221347 -0.0184974 0.1123269 0.2223299 -0.01850509 0.111855 0.2249044 -0.01325285 0.1110506 0.223514 -0.0110867 0.1109392 0.2237906 -0.01644814 0.1125962 0.2252328 -0.01852947 0.1132717 0.2172041 -0.01411247 0.1168941 0.2188894 -0.01850521 0.1136345 0.2172771 -0.01850521 0.1140561 0.2203332 -0.01634663 0.1125639 0.2197045 -0.01840722 0.1161281 0.2212044 -0.01850515 0.1158968 0.2210937 -0.01652735 0.1171041 0.2196314 -0.01636463 0.1235916 0.2087798 -0.01100564 0.12366 0.2087604 -0.01350528 0.1242585 0.2074784 -0.01350528 0.1241763 0.2076551 -0.01036906 0.1161913 0.2114758 -0.01100414 0.1172966 0.2110765 -0.01350528 0.1161876 0.2105631 -0.01050066 0.1160141 0.2104791 -0.01350528 0.1144187 0.205363 -0.00776273 0.1163703 0.210327 -0.004644811 0.1102212 0.1934326 -0.004644811 0.110143 0.1936002 -0.007641792 0.1156001 0.2093418 -0.01350528 0.1221531 0.202444 -0.007628738 0.1238446 0.2063411 -0.01350528 0.1177387 0.1906965 -0.004644811 0.1179065 0.1907747 -0.007641792 0.1238877 0.207591 -0.004644811 0.1293021 0.2210047 -0.01350528 0.1285207 0.2196514 -0.01350528 0.1267625 0.2183036 -0.01350528 0.1236046 0.2182195 -0.01350528 0.1211453 0.2202109 -0.01350528 0.1205736 0.2225438 -0.01350528 0.120845 0.2240828 -0.01350528 0.06617259 0.04123198 -0.02125471 0.06761163 0.04518657 -0.009096741 0.06824851 0.04613071 -0.008179664 0.06908369 0.04634833 -0.007764518 0.06729161 0.04138356 -0.02125513 0.07090556 0.04006874 -0.02125501 0.0739299 0.04458814 -0.007755339 0.05315428 0.04652863 -0.02125483 0.05523449 0.05073797 -0.008293688 0.05346202 0.04527443 -0.02125513 0.05501401 0.05134344 -0.007857441 0.05174666 0.0444951 -0.02125513 0.05138337 0.04214459 -0.02125513 0.0500186 0.04612934 -0.02125513 0.04801261 0.04809522 -0.02125513 0.047692 0.04563558 -0.02125513 0.04680067 0.04767465 -0.02125513 0.04588627 0.04681408 -0.0212413 0.04927057 0.04794269 -0.02125519 0.04532939 0.04550373 -0.02125513 0.04677671 0.04344028 -0.02125513 0.0458545 0.04195362 -0.02125513 0.04769325 0.0417726 -0.02125513 0.04697746 0.04059451 -0.02125513 0.04924255 0.04110831 -0.02125513 0.04850226 0.03970903 -0.02125513 0.04921382 0.03945004 -0.02125513 0.04527282 0.04361754 -0.02125513 0.0502451 0.0393598 -0.02125513 0.0511834 0.03979736 -0.02125513 0.05177718 0.04064536 -0.02125513 0.05588138 0.05192154 0.002358496 0.0524612 0.04252475 0.002358496 0.05588042 0.05192065 -0.007641494 0.05177718 0.04064536 -0.004469811 0.06464999 0.03411608 -0.02125298 0.06382972 0.03463989 -0.002547264 0.06421786 0.03486758 -0.003916561 0.06489956 0.03386646 -0.002807676 0.06549519 0.03352409 -0.001641392 0.06268489 0.03667342 -0.001898109 0.06419557 0.03565853 -0.00463885 0.06377941 0.03423202 -0.002010345 0.06031304 0.03684788 -0.002657115 0.06242048 0.03677153 0.002358496 0.06387764 0.03674799 0.002358496 0.06406557 0.03682988 -0.002125859 0.0649839 0.03796684 0.002358496 0.06429988 0.03608751 -0.02125513 0.06840407 0.04736369 0.002358496 0.06840425 0.04736179 -0.007641375 0.05365657 0.03996133 0.002358496 0.06717485 0.05419605 0.002358496 0.06130295 0.05644094 0.002363502 0.05243766 0.0410676 0.002358496 0.06775641 0.05579388 0.002182126 0.05365657 0.03996133 -0.001641392 0.05158138 0.04024982 -0.00463885 0.05251431 0.04086804 -0.002339601 0.05300855 0.03948676 -0.002589881 0.05087459 0.03956407 -0.002696573 0.05008691 0.03932923 -0.002274513 0.04921382 0.03945004 -0.001641392 0.04763597 0.04002434 0.005144417 0.06707304 0.0329498 0.005144417 0.06620675 0.03326517 -0.02125513 0.06549519 0.03352409 -0.02125513 0.06848609 0.05779868 -0.002373933 0.06228619 0.05930906 -0.001860976 0.06286799 0.06090766 -0.002641856 0.0688281 0.05873835 -0.002641856 0.06818079 0.05695986 -0.001407861 0.06209212 0.0587759 0.001639306 0.06809514 0.05672454 0.001135826 0.06717485 0.05419605 -0.002641856 0.06121474 0.05636537 -0.002641856 0.05996167 0.05534529 -0.004644811 0.05976116 0.05517709 -0.007641792 0.06747913 0.0526092 -0.004644811 0.06752455 0.05235147 -0.007641792 0.04897689 0.06395292 0.003488898 0.04993963 0.06543767 0.003760218 0.05536878 0.0637083 0.007664382 0.05626875 0.06433635 0.007145524 0.05646562 0.0634377 0.007728636 0.07630062 0.05607938 0.00773853 0.08169978 0.05408084 0.003642678 0.08127528 0.0522564 0.003635168 0.0820263 0.05156356 0.002989172 0.0779078 0.05348205 0.006144404 0.0757606 0.05426359 0.007744431 0.08748292 0.07067716 0.003962159 0.08538955 0.06590813 0.004169344 0.08542019 0.06934356 0.004599332 0.08762073 0.07250881 0.004310309 0.09316229 0.08931547 0.004688799 0.09111177 0.08422613 0.004819154 0.09109818 0.08797264 0.005227982 0.0895453 0.08535122 0.006058633 0.09377562 0.09284228 0.005131185 0.09917443 0.1078579 0.005173563 0.09787398 0.1056621 0.005510628 0.09272551 0.09617376 0.00653398 0.09103339 0.09621304 0.007776379 0.1055204 0.1263034 0.005415499 0.1002871 0.1126776 0.005597293 0.1028301 0.1216315 0.005886852 0.1041461 0.1253482 0.005928337 0.1069601 0.1315531 0.005725622 0.1121944 0.1446335 0.005413889 0.1111763 0.1441546 0.005915999 0.1087622 0.1419336 0.00694859 0.1081644 0.1430144 0.007777333 0.1191933 0.1628395 0.005168795 0.1176056 0.1599634 0.005524516 0.1265152 0.1809173 0.004680514 0.1213212 0.1692905 0.005319118 0.1261951 0.1825625 0.005174219 0.1248857 0.1792726 0.005238413 0.1225109 0.1819147 0.007412016 0.1341526 0.1988512 0.003950178 0.1330755 0.198397 0.004550099 0.1283941 0.1874657 0.005012929 0.1259319 0.1922356 0.007708609 0.1211771 0.1720199 0.005857646 0.1189658 0.1727531 0.007728755 0.1149355 0.1620327 0.007818281 0.1140074 0.1508258 0.005708336 0.1138945 0.1535408 0.005872905 0.1111586 0.1553918 0.007744431 0.1118283 0.1518645 0.007221579 0.1067312 0.1324282 0.006101012 0.105153 0.1359367 0.007669389 0.1046068 0.1332287 0.007635891 0.1017313 0.1230075 0.007336556 0.1017014 0.1250272 0.007429659 0.1006573 0.1154354 0.005866587 0.0980522 0.1151441 0.007747232 0.08681803 0.08668112 0.007733464 0.08628576 0.08452254 0.007647931 0.08658009 0.07615125 0.00573194 0.08417528 0.07713979 0.007728099 0.08062809 0.06688284 0.007689177 0.07771915 0.06362193 0.007716 0.05427658 0.07647931 0.003993153 0.06033051 0.07383859 0.007693946 0.05468112 0.0619359 0.007744431 0.05823147 0.06421715 0.007719159 0.06071841 0.06109607 0.007744431 0.07075172 0.05744218 0.007744431 0.07455581 0.05827152 0.007741451 0.07670181 0.06418979 0.007746815 0.07870322 0.06965625 0.007743716 0.07561427 0.0687434 0.007742762 0.07434344 0.0670039 0.007742643 0.08128964 0.07305854 0.007739365 0.08280146 0.08091545 0.007743716 0.08082264 0.0754947 0.007744193 0.08373641 0.08040803 0.007739663 0.08490604 0.08674466 0.007743656 0.0869075 0.09219515 0.007743716 0.08382236 0.09129583 0.007742762 0.08269822 0.08940041 0.007716238 0.08947652 0.09614145 0.007747352 0.08901005 0.09802085 0.007743537 0.0910117 0.1034713 0.007743775 0.08752173 0.102631 0.00775057 0.07723975 0.1061682 0.007744252 0.0765435 0.1046957 0.007743179 0.07458317 0.1092935 0.007744133 0.07051563 0.09805041 0.007742226 0.07136505 0.1035965 0.00775206 0.06755405 0.09309202 0.007744312 0.06850141 0.09260088 0.007743597 0.07182866 0.0935353 0.007741868 0.09275907 0.1051545 0.007748007 0.09454852 0.1039279 0.007380723 0.09481847 0.1060509 0.007167994 0.09312474 0.109361 0.007744133 0.09717053 0.1172262 0.007744789 0.09720242 0.1205187 0.007743716 0.09966909 0.1241363 0.007747113 0.09921991 0.1260238 0.007743597 0.09572023 0.1250105 0.00774455 0.09520757 0.1233199 0.007741451 0.09507304 0.1146172 0.007744133 0.1043221 0.1369476 0.007744133 0.1013078 0.1318186 0.007743239 0.1032894 0.1372085 0.007743656 0.106785 0.1436604 0.007745623 0.1054108 0.1430711 0.007743716 0.1074284 0.1485759 0.007743716 0.1043434 0.1476767 0.007742762 0.1035723 0.1457384 0.007743299 0.1098943 0.1522794 0.00774455 0.109515 0.154347 0.007743716 0.1115325 0.1598521 0.007743656 0.1084474 0.1589528 0.007742762 0.107675 0.1570122 0.007743418 0.1134853 0.1620994 0.007748007 0.113636 0.1656821 0.007743775 0.117412 0.1729121 0.007744312 0.1177234 0.1768996 0.007743716 0.1200504 0.1801016 0.007746458 0.1197409 0.1824046 0.007743597 0.1166558 0.1815052 0.007742762 0.1158834 0.1795645 0.007743418 0.1184687 0.1711861 0.007457137 0.115594 0.1709979 0.007744133 0.1250402 0.1938855 0.007744431 0.1218438 0.1882301 0.007743775 0.1238811 0.1936978 0.007743895 0.1244076 0.1900011 0.007489562 0.1269037 0.1982281 0.007693648 0.1251369 0.1993592 0.007486999 0.1207599 0.1927813 0.007742762 0.1190674 0.1906644 0.007369458 0.1093894 0.1949009 0.007743835 0.1100631 0.1964044 0.007744431 0.1074084 0.1995779 0.007743477 0.1054744 0.194179 0.007743835 0.1061499 0.199216 0.007749974 0.1020804 0.1879525 0.007744431 0.1033494 0.1882598 0.007741928 0.1013349 0.1828102 0.007743597 0.1048725 0.1838362 0.007744252 0.1100792 0.2047295 0.007598459 0.100537 0.1869249 0.007666826 0.09938091 0.1806057 0.007747471 0.09723055 0.1715342 0.007743775 0.09544032 0.1696385 0.007746398 0.09201037 0.1603106 0.007745862 0.09512674 0.1657053 0.007743775 0.09316128 0.1603492 0.007743597 0.09056442 0.1621473 0.00753957 0.09022462 0.1599629 0.007503688 0.09703093 0.181028 0.007189095 0.09729355 0.178792 0.007327318 0.09920161 0.1769296 0.007744252 0.09390604 0.1710251 0.007366061 0.09366506 0.1691778 0.007738888 0.09103655 0.1544312 0.007742226 0.08825582 0.1499634 0.007744312 0.08902233 0.1489818 0.007743597 0.09250169 0.1499925 0.007744252 0.08700799 0.1520391 0.007381021 0.08600544 0.1500079 0.007480919 0.08691948 0.1431561 0.007743716 0.08529347 0.1418574 0.007747411 0.08404749 0.1432811 0.007578432 0.08316367 0.1409835 0.007392644 0.08491808 0.1377058 0.007743775 0.08912783 0.140449 0.007742941 0.0883975 0.1387162 0.007744252 0.09879457 0.1349762 0.007744431 0.09931492 0.1364805 0.007743954 0.08135426 0.1310079 0.007744431 0.0828154 0.13188 0.007743597 0.08081394 0.1264295 0.007743656 0.08502364 0.1291729 0.007742941 0.08429336 0.1274401 0.007744252 0.08035302 0.1327722 0.007627069 0.07981377 0.1299904 0.007599949 0.07831901 0.1226683 0.007744312 0.07670968 0.1151534 0.007743775 0.07446271 0.1120736 0.007744252 0.0726369 0.1039456 0.007742583 0.07705771 0.1242802 0.007602274 0.07635384 0.1220053 0.007469713 0.07871121 0.1206038 0.007743656 0.08091944 0.1178967 0.007742941 0.08000844 0.1160848 0.007744073 0.09110653 0.1139282 0.007743954 0.07302767 0.1131336 0.007615268 0.07286405 0.1110509 0.007611095 0.06701451 0.09478288 0.007663547 0.06598711 0.0920093 0.007675886 0.0663681 0.08672034 0.007744252 0.06473004 0.08535951 0.007746636 0.06439709 0.08132493 0.007743775 0.06032729 0.07012468 0.007741689 0.05956524 0.07582777 0.00753653 0.06226426 0.07544845 0.007743537 0.06914174 0.08360427 0.007744014 0.06770581 0.08225882 0.007742285 0.07944023 0.08006221 0.00774753 0.07859402 0.07812422 0.007716238 0.06504076 0.07232713 0.007744193 0.073031 0.09492456 0.007744431 0.09355187 0.1513054 0.007744431 0.1019923 0.1737858 0.007743954 0.1007102 0.1725448 0.007744252 0.1115728 0.1702952 0.007744073 0.1112948 0.1684911 0.00774157 0.09775048 0.162576 0.007744431 0.09716171 0.1610876 0.007743954 0.1058645 0.1851339 0.007744431 0.1178941 0.210859 -0.01657223 0.1173365 0.2107885 -0.0165053 0.118129 0.2107735 -0.01719421 0.1228275 0.2090634 -0.01719421 0.1235455 0.208368 -0.01634263 0.1230624 0.2089779 -0.01657223 0.1320639 0.2344406 -0.0170052 0.1318203 0.2337709 -0.01800519 0.1230252 0.2096065 -0.01800519 0.1282222 0.2237837 -0.0167073 0.1326217 0.2345109 -0.01650524 0.1267285 0.2365962 -0.01650398 0.1223225 0.2225987 -0.01669633 0.1273185 0.2364035 -0.01666045 0.1271205 0.2354713 -0.01802438 0.1183267 0.2113166 -0.01800519 0.06054967 0.05696094 -0.004644811 0.06038194 0.05688273 -0.007641792 0.06380212 0.06627953 -0.007641792 0.06396985 0.06635773 -0.004644811 0.06226092 0.06204503 -0.007641792 0.06233912 0.06187731 -0.004644811 0.06722229 0.07567632 -0.007641792 0.06739002 0.07575452 -0.004644811 0.06568109 0.07144182 -0.007641792 0.0657593 0.07127416 -0.004644811 0.07064247 0.08507311 -0.007641792 0.07081019 0.08515137 -0.004644811 0.06910121 0.08083868 -0.007641792 0.06917941 0.08067095 -0.004644811 0.07406258 0.09446996 -0.007641792 0.07423031 0.09454816 -0.004644811 0.07252138 0.09023547 -0.007641792 0.07259958 0.09006774 -0.004644811 0.07748275 0.1038667 -0.007641792 0.07765048 0.1039449 -0.004644811 0.0759415 0.09963226 -0.007641792 0.07601976 0.09946453 -0.004644811 0.08090287 0.1132635 -0.007641792 0.0810706 0.1133417 -0.004644811 0.07936167 0.1090291 -0.007641792 0.07943987 0.1088613 -0.004644811 0.08432304 0.1226604 -0.007641792 0.08449077 0.1227385 -0.004644811 0.08278185 0.1184259 -0.007641792 0.08286005 0.1182581 -0.004644811 0.08774322 0.1320571 -0.007641792 0.08791089 0.1321353 -0.004644811 0.08620196 0.1278227 -0.007641792 0.08628016 0.127655 -0.004644811 0.09116339 0.1414539 -0.007641792 0.09133106 0.1415321 -0.004644811 0.08962213 0.1372195 -0.007641792 0.08970034 0.1370518 -0.004644811 0.09458351 0.1508507 -0.007641792 0.09475123 0.1509289 -0.004644811 0.09304231 0.1466163 -0.007641792 0.09312051 0.1464486 -0.004644811 0.09800368 0.1602476 -0.007641792 0.09817141 0.1603258 -0.004644811 0.09646242 0.1560131 -0.007641792 0.09654062 0.1558454 -0.004644811 0.1014239 0.1696444 -0.007641792 0.1015915 0.1697226 -0.004644811 0.0998826 0.1654099 -0.007641792 0.0999608 0.1652422 -0.004644811 0.104844 0.1790412 -0.007641792 0.1050117 0.1791194 -0.004644811 0.1033027 0.1748067 -0.007641792 0.1033809 0.174639 -0.004644811 0.06806713 0.05422478 -0.004644811 0.06814533 0.05405706 -0.007641792 0.0715655 0.06345391 -0.007641792 0.07002431 0.05921941 -0.007641792 0.0714873 0.06362158 -0.004644811 0.06985658 0.05914121 -0.004644811 0.07498568 0.0728507 -0.007641792 0.07344442 0.06861621 -0.007641792 0.07490748 0.07301843 -0.004644811 0.07327675 0.06853801 -0.004644811 0.07840579 0.08224749 -0.007641792 0.0768646 0.078013 -0.007641792 0.07832759 0.08241522 -0.004644811 0.07669687 0.0779348 -0.004644811 0.08182597 0.09164434 -0.007641792 0.08028471 0.08740985 -0.007641792 0.08174777 0.09181201 -0.004644811 0.08011704 0.08733165 -0.004644811 0.08524614 0.1010411 -0.007641792 0.08370488 0.09680664 -0.007641792 0.08516788 0.1012089 -0.004644811 0.08353716 0.09672844 -0.004644811 0.08866626 0.1104379 -0.007641792 0.08712506 0.1062034 -0.007641792 0.08858805 0.1106057 -0.004644811 0.08695733 0.1061252 -0.004644811 0.09208643 0.1198347 -0.007641792 0.09054517 0.1156003 -0.007641792 0.09200823 0.1200024 -0.004644811 0.0903775 0.1155221 -0.004644811 0.09550654 0.1292315 -0.007641792 0.09396535 0.1249971 -0.007641792 0.09542834 0.1293992 -0.004644811 0.09379762 0.1249189 -0.004644811 0.09892672 0.1386284 -0.007641792 0.09738552 0.1343938 -0.007641792 0.09884852 0.138796 -0.004644811 0.09721779 0.1343156 -0.004644811 0.1023468 0.1480252 -0.007641792 0.1008056 0.1437906 -0.007641792 0.1022686 0.1481928 -0.004644811 0.100638 0.1437124 -0.004644811 0.105767 0.1574219 -0.007641792 0.1042258 0.1531875 -0.007641792 0.1056888 0.1575896 -0.004644811 0.1040581 0.1531093 -0.004644811 0.1091871 0.1668187 -0.007641792 0.107646 0.1625843 -0.007641792 0.1091089 0.1669864 -0.004644811 0.1074783 0.1625061 -0.004644811 0.1126073 0.1762156 -0.007641792 0.1110661 0.171981 -0.007641792 0.1125291 0.1763833 -0.004644811 0.1108984 0.1719028 -0.004644811 0.1068011 0.1840358 -0.004644811 0.1067229 0.1842035 -0.007641792 0.1084319 0.1885162 -0.004644811 0.1082642 0.188438 -0.007641792 0.1160275 0.1856124 -0.007641792 0.1144863 0.1813778 -0.007641792 0.1159493 0.1857801 -0.004644811 0.1143186 0.1812996 -0.004644811 0.1219407 0.1835994 -0.004644811 0.1237301 0.1885158 -0.004644811 0.1195051 0.1843469 -0.00764501 0.1179679 0.1801106 -0.007641792 0.1205281 0.1790502 -0.004873335 0.1032412 0.1854708 -0.007641792 0.1005983 0.186304 -0.004873335 0.1185205 0.1742026 -0.004644811 0.0990203 0.1813001 -0.004644811 0.1160889 0.1749483 -0.007641792 0.1013624 0.1803084 -0.007641792 0.1145478 0.1707139 -0.007641792 0.09982109 0.1760739 -0.007641792 0.1171079 0.1696534 -0.004873335 0.09717828 0.1769072 -0.004873335 0.1151004 0.1648057 -0.004644811 0.09560012 0.1719033 -0.004644811 0.1126688 0.1655515 -0.007641792 0.09794217 0.1709116 -0.007641792 0.1111276 0.1613171 -0.007641792 0.09640091 0.1666771 -0.007641792 0.1136878 0.1602566 -0.004873335 0.0937581 0.1675104 -0.004873335 0.1116802 0.1554089 -0.004644811 0.09217995 0.1625065 -0.004644811 0.1092486 0.1561548 -0.007641792 0.09452199 0.1615148 -0.007641792 0.1077075 0.1519202 -0.007641792 0.0929808 0.1572803 -0.007641792 0.1102676 0.1508598 -0.004873335 0.09033793 0.1581136 -0.004873335 0.10826 0.1460122 -0.004644811 0.08875983 0.1531097 -0.004644811 0.1058285 0.1467579 -0.007641792 0.09110188 0.152118 -0.007641792 0.1042873 0.1425234 -0.007641792 0.08956062 0.1478835 -0.007641792 0.1068475 0.1414629 -0.004873335 0.08691781 0.1487168 -0.004873335 0.1048399 0.1366153 -0.004644811 0.08533966 0.1437128 -0.004644811 0.1024084 0.1373611 -0.007641792 0.08768171 0.1427211 -0.007641792 0.1008672 0.1331266 -0.007641792 0.08614051 0.1384867 -0.007641792 0.1034273 0.1320661 -0.004873335 0.08349764 0.13932 -0.004873335 0.1014198 0.1272185 -0.004644811 0.08191949 0.134316 -0.004644811 0.09898823 0.1279643 -0.007641792 0.08426153 0.1333243 -0.007641792 0.09744703 0.1237299 -0.007641792 0.08272033 0.1290899 -0.007641792 0.1000072 0.1226694 -0.004873335 0.08007746 0.1299232 -0.004873335 0.09799963 0.1178218 -0.004644811 0.07849937 0.1249192 -0.004644811 0.09556806 0.1185675 -0.007641792 0.08084142 0.1239275 -0.007641792 0.09402686 0.114333 -0.007641792 0.07930016 0.1196931 -0.007641792 0.096587 0.1132726 -0.004873335 0.07665735 0.1205264 -0.004873335 0.09457945 0.108425 -0.004644811 0.0750792 0.1155225 -0.004644811 0.09214794 0.1091707 -0.007641792 0.07742124 0.1145308 -0.007641792 0.09060668 0.1049362 -0.007641792 0.07588005 0.1102963 -0.007641792 0.09316688 0.1038757 -0.004873335 0.07323718 0.1111295 -0.004873335 0.09115934 0.09902817 -0.004644811 0.07165908 0.1061256 -0.004644811 0.08872777 0.09977394 -0.007641792 0.07400107 0.1051339 -0.007641792 0.08718657 0.09553945 -0.007641792 0.07245987 0.1008995 -0.007641792 0.08974671 0.09447896 -0.004873335 0.069817 0.1017327 -0.004873335 0.08773916 0.08963131 -0.004644811 0.06823891 0.09672886 -0.004644811 0.08530759 0.09037709 -0.007641792 0.07058095 0.09573715 -0.007641792 0.0837664 0.08614259 -0.007641792 0.0690397 0.09150266 -0.007641792 0.08632659 0.08508217 -0.004873335 0.06639689 0.09233593 -0.004873335 0.08431899 0.08023452 -0.004644811 0.06481873 0.08733201 -0.004644811 0.08188748 0.0809803 -0.007641792 0.06716078 0.08634036 -0.007641792 0.08034622 0.0767458 -0.007641792 0.06561958 0.08210587 -0.007641792 0.08290642 0.07568538 -0.004873335 0.06297671 0.08293914 -0.004873335 0.08089888 0.07083773 -0.004644811 0.06139862 0.07793521 -0.004644811 0.0784673 0.0715835 -0.007641792 0.06374067 0.07694357 -0.007641792 0.07692611 0.06734901 -0.007641792 0.06219941 0.07270908 -0.007641792 0.07948625 0.06628853 -0.004873335 0.05955654 0.07354235 -0.004873335 0.0774787 0.06144088 -0.004644811 0.05797845 0.06853842 -0.004644811 0.07504713 0.06218665 -0.007641792 0.06032049 0.06754672 -0.007641792 0.07350593 0.05795216 -0.007641792 0.05877923 0.06331223 -0.007641792 0.07162702 0.05278986 -0.007641792 0.05690032 0.05814993 -0.007641792 0.05458003 0.05177491 -0.007641792 0.07606607 0.05689173 -0.004873335 0.05613642 0.06414556 -0.004873335 0.07426989 0.05195659 -0.004873335 0.05434018 0.05921041 -0.004873335 0.1189561 0.2088482 -0.002641856 0.1170793 0.2098519 -0.002641856 0.1209563 0.2081202 -0.002641856 0.1230393 0.2076826 -0.002641856 0.1066614 0.1948676 -0.007641792 0.1040185 0.1957008 -0.004873335 0.1213881 0.1895074 -0.007641792 0.1236549 0.2098748 -0.01850521 0.1243996 0.207535 -0.01525521 0.1263946 0.2098641 -0.01850521 0.129137 0.2106651 -0.01877653 0.1315674 0.2115735 -0.01850521 0.134659 0.2073087 -0.01100528 0.1337438 0.2131812 -0.01849639 0.1355184 0.2152523 -0.01850998 0.1395264 0.2109686 -0.01026558 0.1373867 0.2155214 -0.0165016 0.1419768 0.2163583 -0.01101946 0.1408162 0.213817 -0.01100528 0.142831 0.2196003 -0.01100528 0.1430782 0.2227284 -0.01100307 0.1378418 0.2229348 -0.01852518 0.1426951 0.2262138 -0.01100528 0.1417207 0.2293893 -0.01100528 0.1401795 0.2323316 -0.01100528 0.1354825 0.2299039 -0.01850521 0.1381236 0.2349407 -0.01100528 0.1339569 0.2316873 -0.01850521 0.1342046 0.2344745 -0.01525521 0.1321291 0.2331616 -0.01850527 0.1356236 0.2371276 -0.01100528 0.1346423 0.2356769 -0.01350528 0.1320328 0.2372273 -0.01350528 0.1312549 0.2395276 -0.01097166 0.1291807 0.2382655 -0.01350528 0.126366 0.2404972 -0.01100528 0.1261851 0.238755 -0.01350528 0.1257475 0.2375526 -0.01525521 0.1230451 0.2404289 -0.01100528 0.1237524 0.2352234 -0.01850521 0.1264922 0.2352129 -0.01850521 0.1197932 0.2397516 -0.01100528 0.1210156 0.2344212 -0.01877617 0.1167212 0.2384884 -0.01100528 0.1185795 0.2335141 -0.01850521 0.1139336 0.2366822 -0.01100528 0.1163855 0.2318732 -0.01850521 0.1115253 0.2343945 -0.01100528 0.1126117 0.2293271 -0.01652592 0.1095784 0.2317032 -0.01100528 0.1081574 0.2286996 -0.01100265 0.1075108 0.226359 -0.01108103 0.1065641 0.2229766 -0.01026362 0.1123804 0.2206259 -0.01844465 0.1079376 0.2170345 -0.01100528 0.110957 0.2156676 -0.0142821 0.1146645 0.2151837 -0.01850521 0.1161901 0.2134003 -0.01850521 0.1127163 0.2094559 -0.01100528 0.1159424 0.2106131 -0.01525521 0.1180177 0.2119261 -0.01850527 0.1376402 0.2067587 -0.00775659 0.1399129 0.2203559 0.01049435 0.1397503 0.219452 -0.01057648 0.1391687 0.2174136 0.01049435 0.1400724 0.222492 -0.01055747 0.1400495 0.2233878 0.01049435 0.1397714 0.2255337 -0.01055532 0.139573 0.2263852 0.01049435 0.1388602 0.2284511 -0.01055824 0.138503 0.2292254 0.01049435 0.1373758 0.2311241 -0.01057392 0.1368831 0.231792 0.01049435 0.1353803 0.2334407 -0.01056247 0.1347797 0.2339798 0.01049435 0.1329546 0.2353063 -0.01000529 0.1322789 0.2356996 0.01049435 0.1302038 0.236639 -0.01000529 0.1294833 0.2368808 0.01049435 0.1272461 0.2373844 -0.01062065 0.126507 0.237475 0.01049435 0.1241998 0.2375164 -0.01099324 0.123472 0.2374579 0.01049435 0.1211796 0.2370277 -0.01092642 0.1205026 0.2368302 0.01049435 0.118318 0.2359355 -0.01055014 0.1177203 0.2356176 0.01049435 0.1157436 0.2342879 -0.010549 0.1152392 0.2338698 0.01049435 0.1135565 0.2321527 -0.01054751 0.1131605 0.2316583 0.01049435 0.1118476 0.2296184 -0.01054608 0.1115696 0.2290737 0.01049435 0.1106881 0.2267904 -0.01054483 0.1105316 0.2262217 0.01049435 0.110125 0.2237821 -0.01000529 0.110089 0.2232192 0.01049435 0.1101843 0.2207325 -0.01060807 0.1102597 0.220189 0.01049435 0.1108611 0.2177498 -0.01052707 0.111037 0.2172551 0.01049435 0.1121281 0.214968 -0.01044517 0.1123889 0.2145379 0.01049435 0.1139328 0.2125009 -0.01044893 0.1142601 0.2121484 0.01049435 0.1165741 0.2101845 0.01049435 0.1192359 0.2087265 0.01049435 0.1221369 0.2078343 0.01049435 0.1251579 0.2075443 0.01049435 0.1271494 0.2076894 -0.01055085 0.1281756 0.2078683 0.01049435 0.1301168 0.2084172 -0.01000529 0.1310663 0.2087932 0.01049435 0.1328716 0.2097326 -0.0109685 0.1337116 0.210281 0.01049435 0.1353081 0.2115792 -0.01051586 0.1360033 0.2122708 0.01049435 0.1373183 0.2138816 -0.01056647 0.1378475 0.2146813 0.01049435 0.138822 0.2165461 -0.01000529 0.1297093 0.2276596 -0.01834952 0.1250689 0.2144797 -0.01844227 0.1266404 0.2194934 -0.01812976 0.1203895 0.2174659 -0.01838594 0.1259099 0.2329682 -0.01844924 0.1345916 0.2229849 -0.01848942 0.1340991 0.2227417 -0.01649922 0.1307207 0.2173668 -0.01648533 0.132356 0.2185439 -0.01650422 0.132315 0.2160205 -0.01604151 0.1341508 0.2162162 -0.01677799 0.134299 0.2206037 -0.01653301 0.1342738 0.2204731 -0.01845872 0.1328967 0.2131563 -0.01398634 0.1347272 0.2297109 -0.0150485 0.1303949 0.2181599 -0.01575523 0.1303559 0.217801 -0.01171594 0.1300426 0.2182883 -0.01110577 0.1307547 0.2172151 -0.01113909 0.1351902 0.2325159 -0.01101291 0.1354897 0.2320487 -0.0122832 0.1325895 0.2151707 -0.0111559 0.1307258 0.2138823 -0.01100194 0.1336135 0.2114909 -0.01102846 0.1323556 0.2138416 -0.01127648 0.1339255 0.2116978 -0.01226592 0.1366356 0.2148258 -0.01281595 0.1373478 0.2155666 -0.01114511 0.116051 0.2223466 -0.01649886 0.1192274 0.2277349 -0.01649677 0.1162135 0.2250686 -0.01652538 0.1175015 0.2296829 -0.0163992 0.1158688 0.2246231 -0.0184558 0.1135062 0.2144947 -0.01214367 0.1151579 0.2133068 -0.0110808 0.1149638 0.2139875 -0.01155549 0.1151404 0.2142648 -0.01344054 0.1115494 0.2186991 -0.01250195 0.1118443 0.2177996 -0.01098316 0.1117189 0.2267449 -0.01235461 0.1125569 0.228967 -0.0112062 0.1163055 0.2336929 -0.01101422 0.1134434 0.230175 -0.01273089 0.1161794 0.2333554 -0.01235461 0.117307 0.2319779 -0.01488196 0.1155531 0.2163296 -0.01614397 0.119752 0.2269277 -0.01575523 0.1196027 0.2259345 -0.01135945 0.120669 0.2273132 -0.01100468 0.11879 0.2283317 -0.01127839 0.1197905 0.2272848 -0.01175528 0.1197253 0.2285222 -0.01100528 0.1174918 0.2302285 -0.01102679 0.117421 0.2320742 -0.01110404 0.1310783 0.2334958 -0.01350528 0.1308662 0.2348678 -0.01103919 0.1289907 0.2356373 -0.01350528 0.1279264 0.2351613 -0.01102727 0.1274483 0.2340597 -0.01350528 0.1275035 0.2335247 -0.01100528 0.1284309 0.2321527 -0.01350528 0.1282495 0.2323412 -0.01100528 0.1302969 0.2324957 -0.01100629 0.1323983 0.2187781 -0.01850503 0.1177487 0.2263096 -0.01850503 0.1380059 0.2277568 -0.01286023 0.1231541 0.2287331 -0.01850521 0.1198822 0.2282974 -0.01850521 0.1179071 0.2308536 -0.01850426 0.1238849 0.2326577 -0.01850503 0.1389853 0.2241107 -0.0124334 0.1269931 0.2163547 -0.01850521 0.1302649 0.2167903 -0.01850521 0.1322399 0.2142342 -0.01850426 0.1262621 0.2124298 -0.01850503 0.1320654 0.2130361 -0.0170049 0.1311869 0.2161639 -0.01700496 0.1286534 0.216965 -0.01700496 0.1260458 0.214836 -0.01700437 0.1269897 0.2117041 -0.01700496 0.1294108 0.2109066 -0.0169931 0.1308195 0.2137022 -0.01700365 0.1303906 0.2150268 -0.0170052 0.1293202 0.2156652 -0.01700323 0.127705 0.2150005 -0.01700365 0.1274731 0.2132692 -0.01700323 0.1292867 0.2121172 -0.01699805 0.1241014 0.2302519 -0.01700437 0.1231575 0.2333832 -0.01700496 0.1196401 0.2340225 -0.01700294 0.1179261 0.230646 -0.01700437 0.1208565 0.2279866 -0.01700437 0.1226739 0.2318186 -0.01700323 0.1224421 0.2300873 -0.01700365 0.1212905 0.2328848 -0.01700323 0.1196753 0.2322199 -0.01700365 0.1194435 0.2304887 -0.01700323 0.1208269 0.2294225 -0.01700323 0.1384255 0.22687 -0.01097315 0.1390858 0.2214597 -0.01099419 0.1230623 0.2184404 -0.01100528 0.1255806 0.2180725 -0.01100528 0.1274517 0.2139862 -0.01100528 0.1282247 0.2125428 -0.0110051 0.1298613 0.2124905 -0.0110051 0.1303132 0.214908 -0.01100522 0.1286588 0.2155932 -0.01102066 0.1278089 0.2188866 -0.01102095 0.1296002 0.2217838 -0.01101964 0.1283826 0.2258599 -0.01100528 0.1245091 0.2270793 -0.01100528 0.12245 0.2302901 -0.01100528 0.1225022 0.2319268 -0.01100528 0.1211109 0.2327902 -0.01100522 0.1196672 0.2320173 -0.01102203 0.1197188 0.2302814 -0.01100522 0.1210064 0.2295171 -0.01100319 0.1216219 0.2255408 -0.01100516 0.1206342 0.2232797 -0.01100528 0.1208335 0.2208362 -0.01100528 0.1024404 0.1906969 -0.004644811 0.1047967 0.1897051 -0.007656395 0.05310696 0.05582213 -0.004873335 0.07303667 0.0485683 -0.004873335 0.1014653 0.2018335 0.005010426 0.1028892 0.2102301 0.003950178 0.1069522 0.2232696 0.01000684 0.107147 0.2179791 0.00762397 0.1088081 0.2130914 0.009676098 0.1087145 0.2171766 0.01049143 0.1054688 0.219125 0.004722833 0.1070836 0.2248114 0.006756961 0.1114008 0.2123798 0.01046323 0.1131696 0.2057105 0.009045064 0.1185187 0.2044432 0.009543538 0.1169858 0.2074744 0.01047539 0.1230409 0.2056609 0.01047402 0.1234074 0.2018761 0.008969306 0.1286503 0.2042598 0.009789288 0.1318593 0.2049625 0.009567141 0.1323223 0.1987174 0.004180192 0.1287267 0.1903812 0.004964053 0.07792091 0.0703963 -5.23039e-5 0.07735437 0.07100474 -4.91907e-4 0.07540673 0.06973952 -4.36983e-4 0.06414932 0.07428395 -4.91678e-4 0.0652303 0.07327377 2.31909e-4 0.07887506 0.07518285 -4.91907e-4 0.0656467 0.08068686 -4.90816e-4 0.06768864 0.08122706 -4.69378e-4 0.07540667 0.06946176 0.007020592 0.07811146 0.07020664 0.00701034 0.06507819 0.07307523 0.007064759 0.0633884 0.07565736 -3.81765e-5 0.06314182 0.07558846 0.00702548 0.06503754 0.08021926 2.31909e-4 0.06497049 0.08072912 0.00702238 0.06768906 0.08151131 0.007160961 0.07785916 0.07768386 -9.80821e-5 0.07801729 0.07789111 0.007020592 0.07970762 0.07531005 -4.49616e-5 0.07995444 0.07537907 0.00702697 0.06823235 0.08553409 -4.91624e-4 0.07906508 0.08102023 -9.53603e-5 0.08200514 0.08167397 -4.90583e-4 0.06933444 0.08454996 2.31909e-4 0.07920831 0.0807203 0.007021725 0.06918239 0.08435148 0.00706464 0.06749272 0.08693355 -4.09693e-5 0.06929236 0.09182846 -4.89449e-4 0.08297926 0.08645898 -4.91907e-4 0.07179337 0.09250307 -4.69052e-4 0.06724601 0.08686465 0.00702548 0.06907469 0.09200531 0.00702238 0.07179319 0.09278756 0.007163226 0.0819633 0.08895999 -9.80928e-5 0.08212149 0.08916723 0.007020592 0.08381199 0.08658641 -3.81799e-5 0.08405846 0.08665531 0.007021129 0.08222758 0.08150857 0.007021248 0.08605408 0.1002286 -4.06982e-4 0.07633674 0.1037777 -9.57249e-5 0.07340717 0.1031318 -4.90594e-4 0.08791571 0.09786248 -5.02541e-5 0.08632308 0.09564614 -4.91907e-4 0.07339054 0.09587186 -4.91691e-4 0.08361655 0.09229141 -4.38199e-4 0.07634818 0.1040385 0.007020592 0.08622795 0.1004487 0.007171869 0.0881626 0.0979315 0.007021129 0.08612895 0.09295487 -8.22511e-5 0.0863341 0.09279084 0.00702238 0.08361506 0.09201413 0.007020592 0.07328653 0.0956276 0.007064759 0.0715968 0.09820973 -3.81635e-5 0.07135039 0.09814071 0.007019639 0.07318323 0.103293 0.007021725 0.09201353 0.1091194 -4.03836e-5 0.09037345 0.1114062 7.91635e-6 0.09006434 0.1111153 -4.2829e-4 0.09118765 0.1090114 -4.91907e-4 0.08976179 0.1041091 -4.90905e-4 0.09037125 0.104577 2.31909e-4 0.07750344 0.1143856 -4.93431e-4 0.07646185 0.1081125 -4.91678e-4 0.08772021 0.1035678 -4.37515e-4 0.09069359 0.1114456 0.007138133 0.09225964 0.109187 0.007023394 0.0904383 0.104067 0.00702238 0.08771926 0.1032903 0.007020592 0.07754284 0.1071023 2.31909e-4 0.07739055 0.1069039 0.007063567 0.07570099 0.1094859 -3.81823e-5 0.07545441 0.1094171 0.007026314 0.07728308 0.1145577 0.00702238 0.07999533 0.1150698 -1.70535e-4 0.08000069 0.1153373 0.007099986 0.09611773 0.1203956 -4.03797e-5 0.09447765 0.1226824 7.91635e-6 0.09416848 0.1223915 -4.28287e-4 0.09529179 0.1202875 -4.91907e-4 0.09386593 0.1153852 -4.90905e-4 0.09447544 0.1158531 2.31909e-4 0.08160758 0.1256617 -4.93432e-4 0.08056604 0.1193886 -4.91678e-4 0.09182441 0.1148439 -4.37514e-4 0.09479159 0.1227214 0.007020592 0.09636378 0.1204631 0.007023394 0.09454262 0.1153429 0.007028758 0.09182226 0.1145628 0.007127285 0.08164703 0.1183784 2.31909e-4 0.0814957 0.1181812 0.007020592 0.07980519 0.1207621 -3.81811e-5 0.07955873 0.1206932 0.007021129 0.08138722 0.1258338 0.00702238 0.08409953 0.1263459 -1.70516e-4 0.08410489 0.1266134 0.007099986 0.1002271 0.1316865 -3.77528e-5 0.09858179 0.1339585 7.91635e-6 0.09827268 0.1336677 -4.28288e-4 0.09939599 0.1315637 -4.91907e-4 0.09797012 0.1266614 -4.90905e-4 0.09857964 0.1271292 2.31909e-4 0.08571177 0.1369379 -4.93432e-4 0.08467024 0.1306648 -4.91678e-4 0.0959286 0.12612 -4.37511e-4 0.09853821 0.1342719 0.007020592 0.1004751 0.13176 0.007020711 0.0986467 0.1266193 0.00702238 0.09592634 0.125837 0.007172644 0.08575117 0.1296546 2.31909e-4 0.08559989 0.1294574 0.007020592 0.08390933 0.1320382 -3.8187e-5 0.08366292 0.1319693 0.007021129 0.08549141 0.13711 0.00702238 0.08820366 0.137622 -1.70538e-4 0.08821094 0.1378954 0.007236838 0.1043261 0.1429479 -4.04003e-5 0.1026861 0.1452347 7.91635e-6 0.1023769 0.1449438 -4.28287e-4 0.1035002 0.1428398 -4.91907e-4 0.1020743 0.1379375 -4.90905e-4 0.1026839 0.1384054 2.31909e-4 0.08981597 0.1482141 -4.93432e-4 0.08877444 0.141941 -4.91678e-4 0.1000328 0.1373962 -4.37509e-4 0.1029999 0.1452737 0.007020592 0.1045722 0.1430155 0.007023394 0.1027506 0.1378954 0.007018983 0.1000306 0.1371151 0.007127285 0.08985537 0.1409307 2.31909e-4 0.08970409 0.1407335 0.007020592 0.08801352 0.1433144 -3.81949e-5 0.08776712 0.1432455 0.007021129 0.08959561 0.1483861 0.00702238 0.09230786 0.1488982 -1.70533e-4 0.09231328 0.1491656 0.007098019 0.1084302 0.154224 -4.04062e-5 0.1067902 0.1565108 7.91635e-6 0.106481 0.15622 -4.28287e-4 0.1076044 0.154116 -4.91907e-4 0.1061785 0.1492137 -4.90905e-4 0.106788 0.1496815 2.31909e-4 0.09392017 0.1594902 -4.93432e-4 0.09287863 0.1532171 -4.91678e-4 0.104137 0.1486724 -4.37515e-4 0.1071042 0.1565499 0.007020592 0.1086763 0.1542916 0.007023394 0.1068551 0.1491717 0.00702238 0.104136 0.148395 0.007020592 0.09395956 0.1522069 2.31909e-4 0.09380745 0.1520084 0.007064759 0.09211772 0.1545906 -3.81729e-5 0.09187132 0.1545215 0.007019639 0.09370005 0.1596624 0.007018923 0.096412 0.1601744 -1.70526e-4 0.0964179 0.1604419 0.00710541 0.1125397 0.165515 -3.76814e-5 0.1108943 0.167787 7.91635e-6 0.1105853 0.1674962 -4.28289e-4 0.1117085 0.1653921 -4.91907e-4 0.1102826 0.1604898 -4.90905e-4 0.1108921 0.1609577 2.31909e-4 0.0980243 0.1707664 -4.93432e-4 0.09698277 0.1644933 -4.91678e-4 0.1082412 0.1599485 -4.37519e-4 0.1108508 0.1681004 0.007020592 0.1127877 0.1655883 0.007021129 0.1109592 0.1604478 0.00702238 0.1082401 0.1596711 0.007020592 0.09806376 0.163483 2.31909e-4 0.09791147 0.1632846 0.007063567 0.09622186 0.1658667 -3.81599e-5 0.09597545 0.1657978 0.007020771 0.097804 0.1709384 0.00702238 0.1005162 0.1714505 -1.70612e-4 0.1005231 0.1717208 0.00716114 0.1166387 0.1767764 -4.03833e-5 0.1149986 0.1790632 7.91635e-6 0.1146894 0.1787723 -4.28289e-4 0.1158128 0.1766684 -4.91907e-4 0.1143869 0.1717661 -4.90905e-4 0.1149964 0.1722338 2.31909e-4 0.1021286 0.1820425 -4.93432e-4 0.101087 0.1757695 -4.91678e-4 0.1123453 0.1712247 -4.375e-4 0.1153125 0.1791023 0.007020592 0.1168848 0.176844 0.007023394 0.1150634 0.1717237 0.007028758 0.1123421 0.1709404 0.00721687 0.1021679 0.1747593 2.31909e-4 0.1020166 0.174562 0.007020592 0.1003261 0.177143 -3.8179e-5 0.1000795 0.1770741 0.00702548 0.1019082 0.1822146 0.00702238 0.1046203 0.1827267 -1.70619e-4 0.1046257 0.1829943 0.007100045 0.1188876 0.1904379 -4.06981e-4 0.1091701 0.1939871 -9.57319e-5 0.1062406 0.1933411 -4.90595e-4 0.1207492 0.1880719 -5.02447e-5 0.1191565 0.1858555 -4.91907e-4 0.106224 0.1860812 -4.91691e-4 0.11645 0.1825007 -4.38193e-4 0.1091817 0.1942479 0.007020592 0.1209961 0.1881408 0.007021129 0.1189624 0.1831642 -8.22665e-5 0.1191676 0.1830002 0.00702238 0.1164485 0.1822234 0.007020592 0.10612 0.1858369 0.0070647 0.1044303 0.188419 -3.81614e-5 0.1041839 0.18835 0.007019639 0.1060155 0.1935026 0.007048547 0.124845 0.1993348 -4.46703e-5 0.1232069 0.2016155 7.91635e-6 0.1228978 0.2013246 -4.28291e-4 0.1240211 0.1992207 -4.91907e-4 0.1225956 0.1943187 -4.90859e-4 0.1232047 0.1947863 2.31909e-4 0.1232683 0.1942759 0.007009565 0.1103494 0.2045984 -4.9344e-4 0.1092954 0.1983217 -4.91678e-4 0.1205543 0.193777 -4.38206e-4 0.1205527 0.1934996 0.007020592 0.1103763 0.1973116 2.31909e-4 0.1102241 0.1971132 0.007063567 0.1085352 0.1996941 -3.96948e-5 0.1082895 0.199625 0.007009863 0.1128175 0.2052781 -1.65378e-4 0.1041727 0.1999261 0.007295072 0.04814779 0.06389999 0.002963781 0.05625265 0.08204656 0.003962278 0.05644869 0.07952535 0.004564821 0.05733901 0.08356666 0.00431317 0.06071192 0.08564865 0.005949556 0.06311541 0.08501732 0.00783044 0.06388539 0.0999822 0.004689157 0.06254464 0.09442305 0.005011558 0.06395202 0.09758222 0.005187034 0.06436502 0.09425306 0.006261885 0.06559467 0.1029311 0.005107522 0.07120263 0.1180617 0.005173981 0.07078927 0.1154508 0.005528509 0.06711137 0.1056827 0.005393624 0.06996023 0.1039838 0.007814824 0.07361996 0.1225979 0.005680501 0.07819688 0.1362691 0.005415618 0.07750952 0.1318141 0.005906879 0.07842653 0.1344217 0.005931496 0.07545977 0.1246793 0.005802869 0.08087182 0.1406726 0.005960524 0.08191996 0.1437447 0.006031453 0.08486616 0.1546006 0.00541377 0.08431667 0.1505532 0.005961596 0.09120726 0.1730473 0.005168378 0.08725512 0.1601784 0.005650341 0.09105789 0.1693425 0.005725502 0.08861458 0.1626022 0.005871236 0.09405368 0.1785411 0.005579948 0.09490346 0.1815626 0.005502045 0.09721463 0.1915908 0.004680216 0.09900963 0.189063 0.006539106 0.05253392 0.06271737 0.006144404 0.1182456 0.2037842 0.008779823 0.1095784 0.2317032 0.009994387 0.1081593 0.2287001 0.009994387 0.1095092 0.229937 0.01049453 0.1115253 0.2343945 0.009994387 0.1148505 0.2365346 0.01049482 0.1139336 0.2366822 0.009994387 0.1207048 0.2400658 0.01000654 0.1222845 0.2395219 0.01049453 0.1275648 0.2404565 0.009988546 0.1320489 0.2385991 0.0104956 0.1381236 0.2349407 0.009994387 0.1402765 0.2308689 0.01049482 0.1426951 0.2262138 0.009994387 0.1423565 0.2197486 0.01049554 0.1410535 0.2142519 0.009992182 0.1370437 0.2100901 0.01049697 0.1297451 0.2059819 0.01049453 0.1078535 0.223023 0.01049411 0.1381649 0.2101736 0.009970664 0.1419877 0.2163875 0.009994387 0.142831 0.2196003 0.009994387 0.1430695 0.2229134 0.009994387 0.1417207 0.2293893 0.009994387 0.1401795 0.2323316 0.009994387 0.1346476 0.2378882 0.009996354 0.1167212 0.2384884 0.009994387 0.1167084 0.2385675 -0.009505212 0.1121485 0.2351269 -0.009480595 0.1214242 0.2401698 -0.009505331 0.1263802 0.2405723 -0.009505212 0.1312298 0.239458 -0.009505331 0.1356613 0.2371942 -0.009505212 0.1391987 0.2337003 -0.009505331 0.1417815 0.2294416 -0.009505212 0.1430767 0.2236912 -0.009476065 0.1430073 0.2240837 -0.003559112 0.1423327 0.2276169 0.00159657 0.1411666 0.23065 0.004577994 0.138184 0.2349899 0.007491171 0.1337854 0.2383109 0.008839726 0.1295051 0.2400619 0.008967041 0.1230309 0.2405053 0.00749135 0.1187035 0.2393876 0.005108714 0.1161409 0.238191 0.002895057 0.1140096 0.2367627 8.86535e-5 0.1123252 0.235251 -0.003559112 0.1113705 0.234215 -0.007356464 0.1398864 0.2117551 0.005560576 0.09333503 0.1794877 -3.37208e-4 0.08770304 0.1627213 -3.37208e-4 0.08180385 0.1460568 -3.37208e-4 0.07563763 0.1294938 -3.37208e-4 0.06920462 0.1130322 -3.37208e-4 0.062505 0.09667217 -3.37208e-4 0.05553889 0.08041346 -3.37208e-4 0.04830694 0.0642569 -3.30659e-4 0.1408162 0.213817 0.003149688 0.1347176 0.2054462 0.00659132 0.136398 0.2081852 0.007854402 0.09374606 0.1779536 -8.38464e-4 0.09608638 0.1820662 -0.001393437 0.0947597 0.1779831 -0.001428127 0.09305423 0.1728245 -0.001422405 0.09152889 0.1682944 -0.001387298 0.08981603 0.1632636 -0.001396417 0.09255754 0.168843 -0.001494944 0.08839362 0.159152 -0.001413226 0.08640265 0.1534826 -0.001410007 0.08500492 0.149567 -0.001392543 0.08029836 0.1392686 -8.70411e-4 0.08313184 0.1442351 -0.001432836 0.08159714 0.1402013 -0.001407027 0.07956606 0.1346005 -0.001415312 0.0780636 0.130612 -0.001419067 0.0759961 0.1252092 -0.001437664 0.07436448 0.1211414 -0.001419007 0.07233101 0.1158297 -0.001435339 0.07076001 0.1118947 -0.001414954 0.06845337 0.1061828 -0.001415133 0.06666982 0.101952 -0.001442849 0.06491261 0.09758126 -0.001426279 0.06328719 0.09371542 -0.001414895 0.06033957 0.08691167 -0.001390039 0.05775564 0.08098691 -0.001374959 0.05738222 0.07957255 -0.001491844 0.05871075 0.08268636 -0.001491844 0.04890918 0.06049674 -0.001519381 0.0478481 0.05967694 -0.001196861 0.04695445 0.05726087 -0.001306772 0.07770568 0.1248241 -0.001495599 0.07796871 0.1311445 0.005162179 0.07897013 0.1305224 -0.001491606 0.08142703 0.1403982 0.005141317 0.07923156 0.1344865 0.005096673 0.08266371 0.1437515 0.005132377 0.08463931 0.1438091 -0.001495778 0.08489888 0.1499384 0.005138576 0.08645063 0.1487712 -0.001493394 0.08611822 0.1534292 0.005641639 0.08821356 0.1593776 0.005506992 0.08944392 0.1628727 0.005018711 0.09045159 0.1624851 -0.001491367 0.09152013 0.1689556 0.004933893 0.09247076 0.1694065 0.006182312 0.09278291 0.1727691 0.005353093 0.09447556 0.1778163 0.00476247 0.09623831 0.1787435 0.006136596 0.09574472 0.1816967 0.004668653 0.09677284 0.1812953 -0.001492679 0.09794431 0.1885489 0.004556894 0.09909814 0.188314 -0.001491785 0.1003028 0.1861292 -0.001491844 0.07957661 0.1291846 -0.001491844 0.07814258 0.1252446 -0.001491844 0.07640963 0.1204833 -0.001491844 0.07439821 0.114957 -0.001491844 0.07266789 0.110203 -0.001491844 0.07123386 0.106263 -0.001491844 0.06950092 0.1015018 -0.001491844 0.0674895 0.09597545 -0.001491844 0.06575924 0.09122151 -0.001491844 0.06421047 0.08696562 -0.001491904 0.0625922 0.08252024 -0.001491844 0.06045889 0.07666254 -0.001491844 0.05068981 0.06098943 -0.001491844 0.05950188 0.07660073 -0.001491844 0.06222832 0.0835604 -0.00149244 0.0607959 0.08600682 -0.001488268 0.06577295 0.0916928 -0.001491844 0.06656169 0.09540152 -0.001492321 0.06429767 0.09386658 -0.001495242 0.07094138 0.1058931 -0.001491844 0.0692228 0.1025487 -0.001490235 0.06905913 0.1053424 -0.001495242 0.0726816 0.1106743 -0.001491844 0.07349491 0.1143876 -0.001492559 0.07175296 0.1120619 -0.001499652 0.07607191 0.1214935 -0.001493394 0.08130693 0.1339386 -0.001491844 0.08331835 0.1394649 -0.001491844 0.08505123 0.1442261 -0.001491844 0.0829935 0.1404503 -0.001496016 0.07959032 0.1296559 -0.001491844 0.08040547 0.133374 -0.001500844 0.08648532 0.1481661 -0.001491844 0.08821564 0.1529201 -0.001491844 0.09022706 0.1584464 -0.001491844 0.0918529 0.1629127 -0.001491844 0.08991217 0.1594488 -0.001492857 0.08739537 0.1523369 -0.001495599 0.09339404 0.1671477 -0.001491844 0.09512436 0.1719017 -0.001491844 0.09713572 0.177428 -0.001491844 0.09875726 0.1818822 -0.001491904 0.09677892 0.1784483 -0.001494944 0.09340775 0.167619 -0.001491844 0.09426116 0.1713081 -0.001495599 0.1090356 0.140702 0.005136668 0.1069677 0.1350606 0.005149126 0.1059249 0.1349946 0.006687581 0.1057116 0.1315798 0.005137443 0.1035813 0.1256004 0.00510478 0.1022354 0.1217591 0.005074441 0.1002857 0.1161252 0.005002021 0.09805065 0.1174083 0.007028043 0.09901434 0.1123285 0.005479753 0.09712839 0.1067267 0.005307912 0.0959776 0.1032613 0.005190253 0.09381836 0.0966084 0.005117058 0.09255623 0.09268271 0.005050599 0.08997064 0.08453392 0.004229068 0.08756965 0.07668185 0.004011571 0.07576096 0.04075706 -0.006052792 0.07236206 0.03566461 -0.02125513 0.07600134 0.0417639 -0.006772816 0.0727685 0.03695869 -0.02125513 0.07576483 0.04284352 -0.007355868 0.0726304 0.03827339 -0.02125513 0.07509076 0.04381644 -0.007705032 0.07197237 0.03937458 -0.02125513 0.08041876 0.04842573 0.005145013 0.07302093 0.03532212 0.005319595 0.04986429 0.05334728 -0.007755339 0.0484789 0.05350232 -0.007705032 0.04733717 0.05319035 -0.007355868 0.04646205 0.05251532 -0.006772816 0.04599899 0.05158954 -0.006052792 0.06420964 0.03505617 -0.02125513 0.06758809 0.03932887 -0.02125513 0.06987768 0.0386849 -0.02125513 0.07064831 0.03643476 -0.02125513 0.07119297 0.03418344 -0.02125513 0.06980216 0.03497684 -0.02125513 0.06967782 0.03328263 -0.02125513 0.06803619 0.03426802 -0.02125513 0.06794399 0.03296333 -0.02125513 0.06648683 0.03493231 -0.02125513 0.06557035 0.03659999 -0.02125513 0.06604307 0.03821802 -0.02125513 0.0715636 0.05261558 -0.002104878 0.1116945 0.2339836 -0.00668019 0.1146278 0.2365981 -0.009572267 0.117016 0.2380783 -0.009505331 0.1193479 0.2390827 -0.00945419 0.1215517 0.2396855 -0.009505331 0.1251296 0.2400821 -0.009503662 0.128741 0.239655 -0.009505331 0.1320669 0.2386373 -0.009504318 0.1362171 0.2360796 -0.009506523 0.1394938 0.2325417 -0.009496033 0.1412312 0.2292646 -0.009505331 0.1420018 0.2269793 -0.009505331 0.1424509 0.2246097 -0.009505331 0.1426623 0.2231177 -0.008559048 0.1425098 0.2240321 -0.003543138 0.1422598 0.2258415 -4.94574e-4 0.1416882 0.2280387 0.002251505 0.1406635 0.2304933 0.004597306 0.1396734 0.23221 0.005948603 0.1374449 0.2349523 0.007620871 0.1343257 0.2374703 0.00873816 0.1302165 0.2392934 0.00899291 0.1323841 0.2390376 -0.003439128 0.1351234 0.236952 -0.00510776 0.1314387 0.2394476 -0.005535662 0.1291115 0.2400901 -0.001178324 0.1282613 0.2397877 -0.00204885 0.1259678 0.2405229 7.75944e-4 0.1255006 0.2405413 0.003506362 0.1243408 0.240565 -0.004223465 0.1286107 0.2397444 0.003660023 0.1271416 0.2404487 -0.005550503 0.1236773 0.2404494 -6.28781e-4 0.121464 0.240178 -0.003850102 0.1228203 0.2399717 0.002050757 0.1367319 0.2358048 -0.005347609 0.1201254 0.2399358 4.73591e-4 0.1239506 0.2400504 -0.004497528 0.126363 0.2400323 -0.002129375 0.1319128 0.2387506 -0.005817294 0.1400817 0.2315715 -0.006077945 0.1366623 0.2357542 -0.004364132 0.1215453 0.2397341 -0.003002524 0.127846 0.2398417 -3.49801e-4 0.1327073 0.2383519 -0.003320336 0.1344792 0.2373914 -0.003503501 0.1326844 0.2387518 -0.001270711 0.1338028 0.2382945 0.001787066 0.1300007 0.2398918 0.001661479 0.1296359 0.2399696 -8.49162e-4 0.1337402 0.2377792 0.002031862 0.1325027 0.2384238 0.002797961 0.1393405 0.2326898 -0.002681016 0.1373718 0.2357648 -0.004337668 0.137858 0.2345526 0.001586616 0.137309 0.2353979 -6.95499e-4 0.1388981 0.2340928 0.001100659 0.136751 0.2362856 0.00172168 0.1357982 0.2368052 -2.25063e-4 0.1399182 0.23261 -0.004646897 0.1140278 0.2361171 -4.94575e-4 0.1158779 0.2374329 0.002251505 0.1182407 0.2386546 0.004597306 0.1227151 0.2399242 0.00732994 0.1268491 0.239974 0.008589982 0.1336377 0.2378882 0.003575921 0.04736024 0.060458 0.005145013 0.04827332 0.06010812 0.006144464 0.05147159 0.06310403 0.006144404 0.07030791 0.03549951 0.006144404 0.06827116 0.03427118 0.006144404 0.07096302 0.03411996 0.00614345 0.06813097 0.03362941 0.006144404 0.06648683 0.03493231 0.006144404 0.04797798 0.040964 0.006144404 0.04995656 0.04124689 0.006144404 0.04876011 0.04123079 0.006144404 0.04768145 0.04176187 0.006438851 0.06579399 0.03590786 0.006144404 0.05100852 0.04181712 0.006144404 0.06567704 0.03758949 0.006144404 0.05187988 0.04350876 0.006144404 0.06692796 0.03902345 0.006144404 0.05136394 0.04511362 0.006144404 0.05474478 0.05440241 0.006144404 0.04978966 0.04618251 0.006144404 0.05306124 0.05448907 0.006144404 0.04751819 0.04547733 0.006144404 0.0515964 0.0563628 0.006144404 0.04538667 0.04551273 0.006144404 0.07058221 0.04906338 0.006144404 0.05579674 0.05497264 0.006144404 0.07046526 0.05074506 0.006144404 0.0566681 0.05666434 0.006144404 0.07171618 0.05217897 0.006144404 0.05615216 0.05826914 0.006144404 0.072874 0.05248093 0.006144404 0.05457788 0.05933809 0.006144404 0.05230635 0.05863285 0.006144404 0.06858325 0.03934222 0.006144404 0.07422918 0.04778987 0.006144404 0.07185488 0.04764872 0.006144404 0.070454 0.03787344 0.006144404 0.07232397 0.03570836 0.006144404 0.07950067 0.04875987 0.006144404 0.07546174 0.04982399 0.006144404 0.07448786 0.0519939 0.006144404 0.07897013 0.0530954 0.006144404 0.04677003 0.04316818 0.006404817 0.04460448 0.0456649 0.005319595 0.0444045 0.04394567 0.005144894 0.04497653 0.04228973 0.005144715 0.04608726 0.04093021 0.005144536 0.07206904 0.03387659 0.005144894 0.06884169 0.03264826 0.005144536 0.07056647 0.03297573 0.005144715 0.05187988 0.04350876 -0.01625519 0.05136394 0.04511362 -0.01625519 0.04978966 0.04618251 -0.01625519 0.04751819 0.04547733 -0.01625519 0.04680818 0.04320734 -0.01625519 0.04769325 0.0417726 -0.01625519 0.04947757 0.04111146 -0.01625519 0.05100852 0.04181712 -0.01625519 0.05072832 0.04432052 -0.01625567 0.05059361 0.04277831 -0.01625561 0.04945629 0.04520922 -0.01625508 0.04806864 0.0445578 -0.01624691 0.04784852 0.04340547 -0.01625519 0.04804384 0.04286915 -0.0162301 0.04919427 0.04214864 -0.01624238 0.07067352 0.03666847 -0.01625519 0.07015752 0.03827327 -0.01625519 0.06858325 0.03934222 -0.01625519 0.06631177 0.03863704 -0.01625519 0.06563383 0.03709363 -0.01625519 0.06610333 0.03524953 -0.01625519 0.06827121 0.03427118 -0.01625519 0.06980216 0.03497684 -0.01625519 0.06949949 0.03746998 -0.01624161 0.06938725 0.03593802 -0.01625561 0.06824994 0.03836894 -0.01625508 0.06686222 0.03771752 -0.01624691 0.06664216 0.03656518 -0.01625519 0.06683748 0.03602886 -0.0162301 0.06798791 0.03530836 -0.01624238 0.07401889 0.04768431 0.001293897 0.07525676 0.04912614 0.001144468 0.07164531 0.04775518 0.001144468 0.07059419 0.04906946 0.001293718 0.07054567 0.05096596 0.001144468 0.07237631 0.05248439 0.001144468 0.07399833 0.05221796 0.001237034 0.07532852 0.05081033 0.001144468 0.05617159 0.05530011 0.001144468 0.05402541 0.05427122 0.001294374 0.05196177 0.05543702 0.001144468 0.05175203 0.05780625 0.001144468 0.05358266 0.05932468 0.001144468 0.05587226 0.05868071 0.001144468 0.05658155 0.05708181 0.001276135 0.05390775 0.05706721 5.71646e-4 0.05138337 0.04214459 0.001144468 0.04995656 0.04124689 0.001144468 0.04806345 0.04143995 0.001144468 0.04677671 0.04344028 0.001144468 0.047692 0.04563558 0.001144468 0.0500186 0.04612934 0.001144468 0.05174666 0.0444951 0.001144468 0.05057346 0.04279249 0.001133918 0.04919189 0.04212427 0.001145064 0.04794412 0.04298359 0.001145184 0.04782718 0.04395163 0.001136422 0.04853743 0.04495435 0.001096606 0.04945003 0.04518455 0.001128494 0.05070585 0.04431027 0.001130878 0.06923431 0.03452235 0.001144468 0.07064831 0.03643476 0.001144468 0.06685709 0.03459966 0.001144468 0.06557035 0.03659999 0.001144468 0.06648558 0.03879523 0.001144468 0.06808578 0.03932541 0.001144468 0.06987768 0.0386849 0.001144468 0.06936711 0.03595221 0.001133918 0.06798547 0.03528398 0.001145064 0.06673777 0.0361433 0.001145184 0.06662076 0.03711134 0.001136422 0.06733107 0.03811407 0.001096606 0.06824368 0.0383442 0.001128494 0.06952196 0.03748023 0.001144945 0.07290756 0.04998117 2.43242e-4 0.06875413 0.03546661 -0.007555305 0.06961369 0.03669542 -0.007555365 0.06897586 0.03805702 -0.007555544 0.06680423 0.03754699 -0.00833553 0.06726676 0.03559154 -0.007552802 0.04996049 0.0423069 -0.007555305 0.05082005 0.04353576 -0.007555365 0.05018228 0.04489731 -0.007555544 0.04801058 0.04438728 -0.00833553 0.04847311 0.04243189 -0.007552802 0.09381836 0.1675599 0.007029771 0.09208494 0.1626809 0.007017612 0.1202474 0.1722856 0.006162822 0.1187795 0.1743629 0.007041513 0.120514 0.1792441 0.007017433 0.1128087 0.1540018 0.006727635 0.1118901 0.1554338 0.007020413 0.1136053 0.1602625 0.007017433 0.0799539 0.1294629 0.007023572 0.07826751 0.1247178 0.007017612 0.07304519 0.1104813 0.007023572 0.07134509 0.1056979 0.007022976 0.06613647 0.0914998 0.007023572 0.06443101 0.08669537 0.007082819 0.09978783 0.1222994 0.007017433 0.08791607 0.08710604 0.006380856 0.08730155 0.08778679 0.007234573 0.08975636 0.09473711 0.007020592 0.08422994 0.07944327 0.007089376 0.08587229 0.08406561 0.007020592 0.09114414 0.09843558 0.007044255 0.09289807 0.103373 0.007049143 0.08284765 0.07575553 0.007020592 0.08332568 0.07621663 0.007050096 0.08417415 0.07586693 0.00619173 0.08637946 0.07261961 0.004400849 0.1050585 0.1367794 0.007020592 0.1067032 0.1412917 0.007018327 0.07418751 0.1213628 0.005474746 0.07203292 0.1158657 0.005331516 0.066504 0.1021608 0.005033552 0.06465238 0.09761261 0.004412293 0.06950396 0.1029819 0.006430089 0.05708777 0.07960146 0.003854334 0.05834764 0.08282005 0.004321932 0.0624541 0.08398163 0.006355285 0.07130235 0.05817872 0.0072214 0.06097477 0.06180042 0.007020592 0.0590378 0.06431305 0.007019996 0.1178179 0.1636568 0.005394876 0.1199313 0.1689832 0.005251407 0.115581 0.1630565 0.006283998 0.1080272 0.1447305 0.00723499 0.1086016 0.1440845 0.00635761 0.1104825 0.1516817 0.007020592 0.1109606 0.1521428 0.007050096 0.112761 0.1503879 0.00561285 0.08517628 0.1436996 0.007018208 0.09075486 0.159233 0.00723505 0.08829963 0.1522818 0.007020592 0.08782655 0.1518054 0.007272541 0.09503865 0.1708298 0.007006108 0.09899365 0.1816625 0.007017612 0.09746778 0.1887615 0.005194246 0.1006801 0.1864076 0.007023572 0.09778666 0.178025 0.007391989 0.08690202 0.1485576 0.007021427 0.1217208 0.182883 0.007385492 0.122636 0.1800042 0.007394194 0.1241785 0.1792498 0.005026459 0.1173398 0.1708391 0.007384955 0.114813 0.1638966 0.007385194 0.1157631 0.1610119 0.006822228 0.1164282 0.1599056 0.005567312 0.1104692 0.1445751 0.005120635 0.08144235 0.1331244 0.007384955 0.08396905 0.1400668 0.007385253 0.07453364 0.114143 0.007384955 0.07341206 0.1138965 0.006269872 0.07706034 0.1210852 0.007385253 0.07069587 0.1126859 0.005360901 0.06790417 0.1057149 0.00489825 0.06881588 0.1049349 0.006459712 0.06767588 0.09529989 0.007384419 0.06997662 0.101937 0.007043123 0.06624704 0.09522575 0.00619173 0.06334429 0.09446156 0.004243075 0.06003159 0.08689528 0.004481375 0.1094363 0.1404885 0.005836367 0.1035224 0.132876 0.007384955 0.1009956 0.1259335 0.007385194 0.09661364 0.1138945 0.007384955 0.09772735 0.1141401 0.006256937 0.09408694 0.106952 0.007385194 0.09079289 0.09526008 0.006807863 0.08936756 0.08083689 0.004805803 0.06071621 0.0761798 0.007384955 0.06324291 0.08312213 0.007385253 0.08100783 0.06802475 0.006730675 0.08044564 0.06915599 0.007020592 0.1295735 0.2225438 -0.01350528 0.1290928 0.2247065 -0.01350528 0.1267278 0.2268006 -0.01350528 0.1235642 0.2268561 -0.01350528 0.1216264 0.2254363 -0.01350528 0.1041468 -0.1944552 0.006491303 0.1042258 -0.1934268 0.001090109 0.1031869 -0.1940096 5.09692e-4 0.1006451 -0.1933764 0.001459956 0.09935021 -0.1891397 5.83547e-4 0.10109 -0.1867828 5.64901e-4 0.1019334 -0.1869198 0.001136183 0.1006637 -0.1935172 0.004816174 0.09915715 -0.1891021 0.004809439 0.1255034 -0.1796486 5.3953e-4 0.1253915 -0.186141 5.66139e-4 0.1272366 -0.1837134 0.00112766 0.1227048 -0.178887 5.99434e-4 0.122181 -0.1795669 0.00109297 0.1244683 -0.1860622 0.001098692 0.1243 -0.1862069 0.007020592 0.1217558 -0.1792034 0.007025659 0.12256 -0.1785387 0.007288932 0.1255701 -0.1794646 0.004494249 0.1269441 -0.1840428 -0.001453518 0.1238098 -0.1799906 -0.001480221 0.1254144 -0.1801216 -0.001409947 0.1228942 -0.180771 -0.001513898 0.1253777 -0.1867834 0.007350742 0.1274322 -0.1837098 0.00506711 0.09603691 -0.1813964 -8.69784e-4 0.09869408 -0.1928955 -3.38637e-4 0.09333509 -0.1760498 -3.37208e-4 0.06645888 -0.100371 -8.67763e-4 0.06920468 -0.1095944 -3.37208e-4 0.06250506 -0.0932343 -3.37208e-4 0.05979257 -0.08453965 -8.54144e-4 0.05553895 -0.07697558 -3.37208e-4 0.05321133 -0.06926965 -9.07959e-4 0.04830658 -0.06081813 -3.37208e-4 0.04786121 -0.05625402 -0.001200377 0.04695445 -0.05382299 -0.001306772 0.1010319 -0.1933162 -0.001485764 0.0877031 -0.1592835 -3.37208e-4 0.09475994 -0.1745488 -0.001397848 0.09305453 -0.1693871 -0.001425027 0.09616208 -0.1788615 -0.00138694 0.09663593 -0.1778325 -0.001494109 0.08839058 -0.1557148 -0.001391768 0.08180391 -0.1426189 -3.37208e-4 0.08640319 -0.1500459 -0.001409292 0.08987987 -0.1600179 -0.001387178 0.09034472 -0.1590632 -0.001492738 0.08321726 -0.1411831 -0.001387298 0.07563769 -0.126056 -3.37208e-4 0.08160263 -0.1367695 -0.001408696 0.08363157 -0.140168 -0.001492083 0.07609021 -0.1221548 -0.001387298 0.07436895 -0.1177055 -0.001419663 0.07653093 -0.1210894 -0.001496553 0.07072573 -0.1084945 -0.001389503 0.06670039 -0.09853178 -0.001426756 0.07231616 -0.1124844 -0.001425266 0.06326991 -0.09035521 -0.001389443 0.06032556 -0.08343493 -0.001395106 0.06489962 -0.09423512 -0.001449346 0.05849653 -0.07919436 -0.00141257 0.05738329 -0.07613325 -0.001491844 0.04891717 -0.05705958 -0.001521766 0.07794821 -0.1270059 -0.001396775 0.07948684 -0.1310832 -0.001411378 0.08491659 -0.1458773 -0.001414179 0.09165406 -0.1652199 -0.001431107 0.09805744 -0.1847802 -0.001395046 0.1065546 -0.1911359 -0.001491844 0.1067081 -0.1915576 -0.001598238 0.1010667 -0.1886619 -0.001506268 0.1013238 -0.1862801 -0.001521587 0.1004151 -0.1829993 -0.001492023 0.09875667 -0.1784511 -0.001491844 0.09713584 -0.1739901 -0.001491844 0.09512442 -0.1684638 -0.001491844 0.0933941 -0.1637098 -0.001491844 0.09336245 -0.1642847 -0.001494348 0.09420901 -0.1679058 -0.001493573 0.09915041 -0.1849024 -0.001487076 0.0967983 -0.175016 -0.001494944 0.09196007 -0.1597697 -0.001491844 0.09022712 -0.1550086 -0.001491844 0.0882157 -0.1494823 -0.001491844 0.08648538 -0.1447283 -0.001491844 0.08649909 -0.1451996 -0.001491844 0.08733814 -0.1489183 -0.001492679 0.08589923 -0.146094 -0.00149101 0.09166759 -0.1593999 -0.001491844 0.08996671 -0.1559916 -0.001496136 0.08505135 -0.1407883 -0.001491844 0.08331841 -0.136027 -0.001491844 0.08130699 -0.1305007 -0.001491844 0.07957667 -0.1257467 -0.001491844 0.07959038 -0.126218 -0.001491844 0.08042043 -0.1299476 -0.00149393 0.07892286 -0.127205 -0.001491904 0.08475887 -0.1404184 -0.001491844 0.08301103 -0.1370201 -0.001492679 0.05708676 -0.05522423 -0.001491844 0.07814258 -0.1218067 -0.001491844 0.07640969 -0.1170455 -0.001491844 0.07785016 -0.1214368 -0.001491844 0.0760855 -0.1180596 -0.001492798 0.07439827 -0.1115191 -0.001491844 0.07266795 -0.1067652 -0.001491844 0.07268166 -0.1072365 -0.001491844 0.07348078 -0.110961 -0.001493573 0.07171446 -0.108684 -0.001491546 0.07123392 -0.1028251 -0.001491844 0.06950098 -0.09806388 -0.001491844 0.0674895 -0.09253758 -0.001491844 0.06587362 -0.08809721 -0.001491904 0.06655901 -0.09196341 -0.00149244 0.06430655 -0.09041815 -0.001491844 0.07094144 -0.1024553 -0.001491844 0.06922286 -0.09911078 -0.001490235 0.06892991 -0.1018843 -0.001494944 0.06432515 -0.08384358 -0.001491844 0.0625922 -0.07908236 -0.001491844 0.06046861 -0.0732569 -0.001491844 0.05068981 -0.05755156 -0.001491844 0.05950188 -0.07316285 -0.001491844 0.06403273 -0.08347368 -0.001491844 0.06253737 -0.07971394 -0.001491844 0.06201845 -0.08007705 -0.001491844 0.06104993 -0.08263558 -0.001491904 0.0715636 -0.0491777 -0.002104878 0.1213601 -0.1859925 -0.001518845 0.1216556 -0.1868044 -0.002104878 0.07181346 -0.04986417 -0.001491844 0.1253858 -0.1889581 -0.004873454 0.1284433 -0.1820937 -3.37857e-4 0.1314045 -0.1890735 -0.006620407 0.07965397 -0.06143319 0.001749455 0.07693922 -0.05362945 0.001749038 0.07603836 -0.05298501 0.002362728 0.07916021 -0.06190168 0.002734303 0.08457201 -0.06325691 0.002328753 0.08328545 -0.06201267 0.001744508 0.08113539 -0.05144995 0.002050757 0.08052188 -0.05237829 0.001744508 0.08151286 -0.05094474 0.00349766 0.08445984 -0.06226408 0.003813564 0.08433514 -0.06337982 0.005031764 0.07975286 -0.06220364 0.007615447 0.07910668 -0.06185179 0.007008969 0.05935102 -0.06092649 -8.97195e-4 0.06107819 -0.06579881 -8.19315e-4 0.06150376 -0.06529271 -0.001395642 0.05995273 -0.05964016 -0.001396715 0.06116247 -0.05858039 -8.06883e-4 0.07260507 -0.05555057 -0.00149101 0.07101601 -0.05501329 -8.01021e-4 0.07380574 -0.05574345 -9.54348e-4 0.07446205 -0.06042808 -0.001491844 0.07553046 -0.0606051 -9.84017e-4 0.07356435 -0.06242585 -0.001388609 0.07398647 -0.06279432 -8.93784e-4 0.06375581 -0.06553 -0.001491844 0.06355428 -0.06650662 -9.04803e-4 0.07427519 -0.06290715 0.007165908 0.07586324 -0.06059098 0.007015883 0.06403565 -0.06677216 0.007020592 0.06093662 -0.06609237 0.007021546 0.05903416 -0.06098097 0.007015824 0.05602395 -0.07364529 0.002210199 0.05110168 -0.06239181 0.001751065 0.05540078 -0.07307982 0.003817677 0.056046 -0.07197213 0.001744508 0.05917245 -0.06925189 0.002465963 0.05836063 -0.06908422 0.001746416 0.05598682 -0.0603913 0.002379953 0.05540466 -0.06130439 0.001747369 0.05926162 -0.06914144 0.00700742 0.05625736 -0.06086689 0.007160663 0.05664664 -0.07297688 0.005267798 0.10561 -0.1974608 -0.003329277 0.103095 -0.1967524 -0.003522098 0.1051835 -0.197961 -0.00390917 0.1086383 -0.2058625 -0.003043234 0.1081295 -0.2058171 -0.003903746 0.1084922 -0.2063118 -0.003331482 0.1067095 -0.2088769 -0.00302726 0.105909 -0.2090446 -0.003796279 0.1023925 -0.1970154 -0.003940165 0.1021699 -0.1976628 -0.003323137 0.1054342 -0.2085953 -0.003341197 0.1023413 -0.1961874 0.006055414 0.1058287 -0.1971212 0.007015407 0.1076688 -0.2020599 0.007020592 0.1091412 -0.2059703 0.008417844 0.1261203 -0.1900947 -0.002793252 0.1267922 -0.1903857 -0.003685891 0.1262534 -0.1896804 -0.003181993 0.1291551 -0.198505 -0.003174602 0.1301256 -0.1982787 -0.003753662 0.1279071 -0.1874744 -0.003744244 0.1331436 -0.1992238 -0.003740131 0.1334334 -0.1984372 -0.002897739 0.1288755 -0.1878981 -0.002790272 0.1325477 -0.1994098 -0.003091216 0.1333444 -0.2000225 0.006464779 0.1288509 -0.1989078 0.009083628 0.1272379 -0.1943259 0.007481813 0.1256795 -0.1899927 0.007001221 0.1065002 -0.2019167 -0.007750809 0.1011217 -0.2008503 -0.007236659 0.1039592 -0.1989628 -0.006587505 0.1068558 -0.2102953 -0.007755398 0.1089994 -0.2067958 -0.007756412 0.1095272 -0.2055878 0.009054422 0.1063832 -0.2098952 0.006115913 0.1052976 -0.2093999 0.005226552 0.1246081 -0.1912552 -0.006389796 0.1272856 -0.1932607 -0.007717192 0.1324479 -0.1915056 -0.007749617 0.1294379 -0.199342 -0.007760882 0.1289301 -0.1873756 0.004519283 0.1323225 -0.1952795 0.004180192 0.1341906 -0.1994553 0.005252599 0.1279873 -0.1867421 0.005776762 0.1245169 -0.1946497 -0.007639586 0.1251125 -0.198924 -0.00774008 0.1319289 -0.200137 -0.007755339 0.1349183 -0.201502 -0.007755339 0.1376414 -0.2033231 -0.007756352 0.1112288 -0.2043575 -0.007760226 0.1096022 -0.1995219 -0.007638037 0.1054972 -0.1960858 -0.004806518 0.1069289 -0.1921644 -0.002104878 0.1210992 -0.2270749 -0.01604115 0.119082 -0.225882 -0.01850515 0.1210721 -0.2273752 -0.01850521 0.1195661 -0.2257367 -0.01648974 0.1181303 -0.2277681 -0.01642209 0.1173023 -0.2292829 -0.01851528 0.1189957 -0.2316399 -0.01274728 0.1196955 -0.2304959 -0.01850217 0.1133422 -0.2268627 -0.01131808 0.1136716 -0.2257239 -0.01797497 0.1129345 -0.2261577 -0.0124967 0.1179839 -0.2256296 -0.01853251 0.1154406 -0.2274748 -0.01849496 0.1143584 -0.2280862 -0.01263475 0.114237 -0.2228407 -0.01608645 0.1161247 -0.2225426 -0.01850515 0.1128928 -0.2228969 -0.01849424 0.1340198 -0.2156715 -0.01850515 0.1372482 -0.2153247 -0.01850515 0.136123 -0.215463 -0.0158137 0.1362613 -0.2180259 -0.01644003 0.1377621 -0.2179644 -0.01850992 0.1343953 -0.2191682 -0.01654577 0.1320819 -0.2126842 -0.01844382 0.1347008 -0.210749 -0.01850521 0.1350711 -0.2105867 -0.01367604 0.1371479 -0.2120835 -0.01252645 0.1364698 -0.2108843 -0.01108974 0.1367391 -0.2109491 -0.01638305 0.1362718 -0.2129131 -0.01850819 0.1296001 -0.2092626 -0.01699054 0.1292347 -0.2103512 -0.01850521 0.1304511 -0.2077186 -0.01850521 0.1320925 -0.2103306 -0.01634663 0.1330131 -0.2091002 -0.01858878 0.1310652 -0.2123299 -0.01850515 0.1305812 -0.2124751 -0.01648974 0.1291825 -0.211405 -0.01572602 0.1173614 -0.2076095 -0.01100564 0.1172966 -0.2076386 -0.01350528 0.1160141 -0.2070413 -0.01350528 0.1161907 -0.2071239 -0.010369 0.1247633 -0.2049181 -0.01100414 0.1236601 -0.2053226 -0.01350528 0.1241796 -0.2042164 -0.01050066 0.1242586 -0.2040405 -0.01350528 0.1221921 -0.1990959 -0.00776273 0.1238879 -0.2041531 -0.004644811 0.1177387 -0.1872586 -0.004644811 0.1179065 -0.1873368 -0.007641792 0.1238447 -0.2029032 -0.01350528 0.1143939 -0.2018415 -0.007643103 0.1156002 -0.205904 -0.01350528 0.1102213 -0.1899947 -0.004644811 0.1101431 -0.1901624 -0.007641792 0.1163704 -0.2068892 -0.004644811 0.120845 -0.220645 -0.01350528 0.1205737 -0.2191059 -0.01350528 0.1210542 -0.2169435 -0.01350528 0.1234192 -0.2148492 -0.01350528 0.1265833 -0.2147938 -0.01350528 0.1285208 -0.2162135 -0.01350528 0.1293022 -0.2175669 -0.01350528 0.05364942 -0.04235219 -0.02125471 0.05508899 -0.04630661 -0.009096741 0.05520796 -0.04743921 -0.008179664 0.05470806 -0.04814273 -0.007764518 0.05288958 -0.04318761 -0.02125513 0.04927426 -0.0445035 -0.02125519 0.04986429 -0.04990941 -0.007755339 0.06702661 -0.03804165 -0.02125483 0.06813877 -0.04260331 -0.008293688 0.06598472 -0.03727865 -0.02125513 0.06869685 -0.04292541 -0.007857441 0.06679779 -0.03557908 -0.02125513 0.06577014 -0.0342428 -0.02125513 0.06868499 -0.03582292 -0.02125513 0.07091164 -0.03662812 -0.02125513 0.07013541 -0.03496384 -0.02125513 0.0726304 -0.03483557 -0.02125513 0.0727685 -0.03352081 -0.02125513 0.07197237 -0.03593671 -0.02125513 0.07060492 -0.03311979 -0.02125513 0.07236206 -0.03222674 -0.02125513 0.06992691 -0.03157639 -0.02125513 0.06967782 -0.02984476 -0.02125513 0.06765544 -0.03087121 -0.02125513 0.06620669 -0.02982729 -0.02125513 0.06549519 -0.03008621 -0.02125513 0.06794399 -0.02952545 -0.02125513 0.07119297 -0.03074556 -0.02125513 0.06578475 -0.03233999 -0.02125513 0.06464713 -0.03068006 -0.02125513 0.06420964 -0.03161829 -0.02125513 0.06429988 -0.03264963 -0.02125513 0.06840407 -0.04392582 0.002358496 0.0649839 -0.03452897 0.002358496 0.06840419 -0.04392457 -0.007641494 0.06429988 -0.03264963 -0.004469811 0.05024176 -0.03592234 -0.02125298 0.05120682 -0.0357964 -0.002547264 0.05105584 -0.03622031 -0.003916561 0.04989016 -0.03589159 -0.002807676 0.04921382 -0.03601217 -0.001641392 0.05339092 -0.03661823 -0.001898109 0.05158132 -0.03681188 -0.00463885 0.05098313 -0.03545159 -0.002010345 0.05532014 -0.03522723 -0.002657115 0.05365657 -0.03652346 0.002358496 0.05252516 -0.03744208 0.002358496 0.05243384 -0.03762567 -0.002125859 0.0524612 -0.03908687 0.002358496 0.05177718 -0.03720748 -0.02125513 0.05588138 -0.04848366 0.002358496 0.05588001 -0.04848235 -0.007641375 0.06242048 -0.03333365 0.002358496 0.06121474 -0.05292749 0.002358496 0.06715589 -0.0508728 0.002363502 0.06406527 -0.03339761 0.002358496 0.0617963 -0.05452531 0.002182126 0.06242048 -0.03333365 -0.001641392 0.06419557 -0.03222072 -0.00463885 0.06387829 -0.03329402 -0.002339601 0.06261181 -0.03255355 -0.002589881 0.06429624 -0.03124117 -0.002696573 0.0647487 -0.03055495 -0.002274513 0.06549519 -0.03008621 -0.001641392 0.06707298 -0.02951198 0.005144417 0.04763603 -0.03658646 0.005144417 0.04850226 -0.03627115 -0.02125513 0.04921382 -0.03601217 -0.02125513 0.06252598 -0.05653005 -0.002373933 0.0682463 -0.05370187 -0.001860976 0.0688281 -0.05530047 -0.002641856 0.06286799 -0.05746978 -0.002641856 0.06222069 -0.0556913 -0.001407861 0.06805223 -0.05316877 0.001639306 0.06213504 -0.05545598 0.001135826 0.06121474 -0.05292749 -0.002641856 0.06717485 -0.05075818 -0.002641856 0.06747913 -0.04917132 -0.004644811 0.06752455 -0.04891359 -0.007641792 0.05996167 -0.05190742 -0.004644811 0.05976122 -0.05173921 -0.007641792 0.0819959 -0.05012995 0.003472268 0.07630342 -0.05264949 0.00772798 0.07609045 -0.05368095 0.00705558 0.07530218 -0.05486303 0.007804274 0.05010825 -0.06233596 0.003634274 0.04916644 -0.06050521 0.003635168 0.04814541 -0.06045627 0.002988815 0.05253392 -0.05927956 0.006144404 0.05525171 -0.06038892 0.007504999 0.05468112 -0.05849802 0.007744431 0.0562517 -0.07860648 0.003962159 0.0547899 -0.07360762 0.004169344 0.05697458 -0.07625901 0.004599332 0.05732351 -0.08009821 0.004310309 0.06388151 -0.0965349 0.004688799 0.06236827 -0.09042602 0.005007445 0.06459957 -0.09417945 0.005227982 0.06408333 -0.0912007 0.006038844 0.06567865 -0.09963089 0.005131185 0.07119476 -0.1146038 0.005173563 0.07077962 -0.1120858 0.005510628 0.06977498 -0.1005206 0.007707238 0.0674588 -0.1026489 0.005390048 0.07819008 -0.132813 0.005415499 0.07344043 -0.1190111 0.005597233 0.07724797 -0.1275048 0.005886852 0.07862883 -0.1311978 0.005928337 0.08046168 -0.1377598 0.005725622 0.08485984 -0.1511446 0.005413889 0.08533191 -0.1501233 0.005915999 0.08575361 -0.1468703 0.00694859 0.08690631 -0.1473139 0.007777333 0.09120088 -0.1695901 0.005168795 0.09056848 -0.1663662 0.005524516 0.09800112 -0.1890476 0.004982531 0.09359347 -0.1757155 0.005282104 0.09721219 -0.1881449 0.004680514 0.1028894 -0.2067923 0.003950178 0.1034224 -0.205752 0.004550099 0.09998214 -0.1943689 0.005012929 0.1044269 -0.1953827 0.007730722 0.09558236 -0.1778978 0.005857646 0.09774768 -0.177038 0.007728815 0.09394401 -0.1662351 0.007818281 0.08745121 -0.1570535 0.005708336 0.08928298 -0.1590608 0.005872905 0.09256857 -0.1587202 0.007744431 0.08978843 -0.1564485 0.007221639 0.08093404 -0.1374574 0.00592935 0.08237797 -0.1401694 0.006103575 0.08461672 -0.1399611 0.007649302 0.08334141 -0.1375308 0.007635891 0.07897394 -0.1278526 0.007336497 0.08029532 -0.1293805 0.007429659 0.07492959 -0.1213617 0.005866587 0.07673799 -0.1194639 0.007747232 0.07210707 -0.1088503 0.007515788 0.07018822 -0.1095962 0.005589902 0.06704819 -0.0904389 0.007733464 0.06606841 -0.08844316 0.007647931 0.06063699 -0.08225536 0.005849719 0.06293964 -0.08143109 0.007728099 0.05906391 -0.07129371 0.007689177 0.05799418 -0.06092613 0.007792174 0.08435285 -0.05950373 0.004055559 0.0790838 -0.06357508 0.007693946 0.05989456 -0.06868058 0.007745206 0.0757606 -0.05082571 0.007744431 0.07059592 -0.05406308 0.007744431 0.06056135 -0.05771332 0.007744431 0.06034523 -0.06670641 0.007743835 0.06232112 -0.07218098 0.007743716 0.06410068 -0.06949615 0.007742762 0.06395602 -0.06734675 0.007742643 0.0625267 -0.07644969 0.007739365 0.06641894 -0.0834403 0.007743716 0.06445044 -0.0780158 0.007744193 0.06537657 -0.08365261 0.007739663 0.06855374 -0.08925855 0.007743656 0.07052403 -0.09472036 0.007743716 0.07230931 -0.0920484 0.007742762 0.0719521 -0.08987379 0.007716238 0.07109266 -0.09939473 0.007747352 0.072658 -0.1005346 0.007743537 0.07462811 -0.1059966 0.007743775 0.07603782 -0.1011729 0.007739007 0.07640731 -0.1033483 0.00774157 0.08691173 -0.09921008 0.007744252 0.0864861 -0.09763944 0.007743835 0.09095561 -0.0998966 0.007744133 0.08684462 -0.08866924 0.007742226 0.08938604 -0.09244531 0.00774759 0.085909 -0.08292007 0.007744431 0.0848847 -0.08319997 0.007743597 0.08293658 -0.0860545 0.007741868 0.07437157 -0.1084092 0.007748007 0.076761 -0.111806 0.007744133 0.07875174 -0.1204922 0.007744789 0.08087706 -0.1230793 0.007741987 0.08127945 -0.1273918 0.007747113 0.08283674 -0.1285489 0.007743597 0.08489197 -0.1254824 0.007744669 0.07869857 -0.1171746 0.007743895 0.08594995 -0.1401968 0.007744133 0.08500206 -0.1344169 0.007744133 0.08690875 -0.1397327 0.007743656 0.08837819 -0.1469218 0.007745623 0.08905208 -0.1455873 0.007743716 0.09104502 -0.1511012 0.007743716 0.09283024 -0.1484292 0.007742762 0.09217494 -0.1464488 0.007743299 0.09153652 -0.1555233 0.00774455 0.09315627 -0.1568634 0.007743716 0.09514921 -0.1623774 0.007743656 0.09693449 -0.1597053 0.007742762 0.09627878 -0.1577222 0.007743418 0.09509772 -0.1653538 0.007748007 0.09726232 -0.1681421 0.007743835 0.09905713 -0.1762082 0.007744431 0.1013872 -0.1794679 0.007743656 0.1016403 -0.1833645 0.007746458 0.1033576 -0.1849296 0.007743597 0.1051428 -0.1822578 0.007742762 0.1047855 -0.1800831 0.007716238 0.09712117 -0.175518 0.007457137 0.09921956 -0.1735554 0.007743895 0.1052905 -0.1941995 0.007722675 0.1054914 -0.1907441 0.007743775 0.1074452 -0.1962422 0.007743895 0.1080492 -0.2016509 0.007700979 0.1101191 -0.2013777 0.007486462 0.1092404 -0.1935571 0.007742166 0.109183 -0.1908243 0.007369458 0.1193194 -0.1878488 0.007743835 0.1197453 -0.1894195 0.007744252 0.1244125 -0.1900817 0.00780344 0.1218549 -0.1847792 0.007743835 0.1237055 -0.1867516 0.007743954 0.1206575 -0.1783701 0.007745325 0.1196779 -0.1788789 0.007741928 0.1177183 -0.1734094 0.007743597 0.11577 -0.1762639 0.007741868 0.1251091 -0.1958211 0.007598459 0.1205875 -0.1759199 0.00729531 0.1181474 -0.1714948 0.007744252 0.1136142 -0.1621332 0.007743775 0.1137671 -0.1595301 0.007746398 0.1103988 -0.15018 0.007745862 0.1114885 -0.1563521 0.007743239 0.1095419 -0.1509493 0.007743597 0.1123906 -0.1510097 0.007608354 0.1115428 -0.1487678 0.007519841 0.1181818 -0.1677685 0.007672309 0.1190062 -0.1695042 0.007733225 0.1155724 -0.1675332 0.007744252 0.1158338 -0.1596063 0.007366061 0.1155872 -0.1574879 0.007348001 0.1073654 -0.14505 0.007742226 0.106859 -0.1405487 0.007745862 0.1054056 -0.1395807 0.007743597 0.1033899 -0.1425918 0.007744252 0.1089139 -0.1406282 0.007381021 0.1083763 -0.1384277 0.007480919 0.1032478 -0.1337407 0.007742941 0.10433 -0.1335317 0.007744133 0.1040957 -0.1298634 0.007652044 0.1055532 -0.1320157 0.007606267 0.105144 -0.1292187 0.007024884 0.1013016 -0.1283047 0.007743775 0.09929746 -0.1311554 0.007743775 0.08942526 -0.1367039 0.007743179 0.09972643 -0.1208832 0.007744431 0.09914362 -0.1224646 0.007742822 0.09719735 -0.1170285 0.007743656 0.09518164 -0.1200392 0.007744252 0.08481293 -0.1238573 0.007744431 0.09520435 -0.1219387 0.007707953 0.1016281 -0.1215918 0.007617235 0.101579 -0.1194574 0.007325351 0.09669101 -0.1125437 0.007744312 0.09309333 -0.1057524 0.007743775 0.09283488 -0.1019487 0.007744252 0.08900898 -0.09454882 0.007742583 0.09869313 -0.1129677 0.007602334 0.09777009 -0.1107726 0.007469713 0.09503942 -0.1111884 0.007742881 0.09107744 -0.108763 0.007744252 0.08071309 -0.1124187 0.00774306 0.08122271 -0.1141495 0.00774306 0.09474831 -0.1018812 0.007533848 0.09332382 -0.100107 0.007649898 0.09214586 -0.09336704 0.007175445 0.09080606 -0.09187608 0.007427155 0.08742606 -0.08391314 0.00768572 0.08640235 -0.08112138 0.007627308 0.08273893 -0.07732397 0.007744252 0.08287358 -0.07458055 0.007744252 0.08078074 -0.07192385 0.007743775 0.07669907 -0.06072801 0.007741689 0.08094865 -0.06460696 0.00753653 0.0786373 -0.0660513 0.007743537 0.07861125 -0.07671976 0.007744014 0.07884645 -0.07476609 0.007742285 0.06844538 -0.08062618 0.00774753 0.0678479 -0.07859766 0.007716238 0.07450401 -0.06544494 0.007744193 0.08290851 -0.08789157 0.007744431 0.1034294 -0.1442724 0.007744431 0.1114138 -0.1669188 0.007743954 0.1115984 -0.165144 0.007744252 0.101745 -0.170572 0.007739663 0.1003834 -0.1690011 0.007743239 0.1075336 -0.1555485 0.007744431 0.107003 -0.1540907 0.007744431 0.115742 -0.178101 0.007744431 0.1230625 -0.20554 -0.01657223 0.1234443 -0.2051275 -0.0165053 0.1228276 -0.2056255 -0.01719421 0.1181291 -0.2073356 -0.01719421 0.1171321 -0.2072645 -0.01634263 0.1178942 -0.2074212 -0.01657223 0.1273657 -0.2327129 -0.0170052 0.1271219 -0.2320432 -0.01800519 0.1183269 -0.2078788 -0.01800519 0.1199953 -0.2126121 -0.01678508 0.1271633 -0.2330531 -0.01654672 0.1328385 -0.2309345 -0.01650398 0.1272165 -0.2173801 -0.01669633 0.1322627 -0.2311661 -0.01666045 0.1318152 -0.2303248 -0.01802444 0.1230253 -0.2061687 -0.01800519 0.06806713 -0.05078691 -0.004644811 0.06814539 -0.05061918 -0.007641792 0.0715655 -0.06001603 -0.007641792 0.0714873 -0.0601837 -0.004644811 0.07002431 -0.05578154 -0.007641792 0.06985658 -0.05570334 -0.004644811 0.07498568 -0.06941282 -0.007641792 0.07490748 -0.06958055 -0.004644811 0.07344442 -0.06517833 -0.007641792 0.07327675 -0.06510013 -0.004644811 0.07840585 -0.07880961 -0.007641792 0.07832759 -0.07897734 -0.004644811 0.0768646 -0.07457512 -0.007641792 0.07669687 -0.07449692 -0.004644811 0.08182597 -0.08820647 -0.007641792 0.08174777 -0.08837413 -0.004644811 0.08028477 -0.08397197 -0.007641792 0.08011704 -0.08389377 -0.004644811 0.08524614 -0.09760326 -0.007641792 0.08516794 -0.09777092 -0.004644811 0.08370494 -0.09336876 -0.007641792 0.08353722 -0.09329056 -0.004644811 0.08866631 -0.1070001 -0.007641792 0.08858811 -0.1071678 -0.004644811 0.08712506 -0.1027655 -0.007641792 0.08695739 -0.1026873 -0.004644811 0.09208649 -0.1163969 -0.007641792 0.09200823 -0.1165646 -0.004644811 0.09054523 -0.1121624 -0.007641792 0.0903775 -0.1120841 -0.004644811 0.0955066 -0.1257936 -0.007641792 0.0954284 -0.1259613 -0.004644811 0.09396541 -0.1215592 -0.007641792 0.09379768 -0.121481 -0.004644811 0.09892678 -0.1351904 -0.007641792 0.09884858 -0.1353582 -0.004644811 0.09738558 -0.1309559 -0.007641792 0.09721785 -0.1308778 -0.004644811 0.102347 -0.1445873 -0.007641792 0.1022688 -0.144755 -0.004644811 0.1008056 -0.1403527 -0.007641792 0.100638 -0.1402745 -0.004644811 0.1057671 -0.1539841 -0.007641792 0.1056889 -0.1541517 -0.004644811 0.1042258 -0.1497496 -0.007641792 0.1040582 -0.1496714 -0.004644811 0.1091299 -0.163392 -0.007653355 0.1091091 -0.1635485 -0.004644811 0.107646 -0.1591464 -0.007641792 0.1074783 -0.1590682 -0.004644811 0.1126074 -0.1727777 -0.007641792 0.1125292 -0.1729454 -0.004644811 0.1110661 -0.1685432 -0.007641792 0.1108984 -0.168465 -0.004644811 0.06054973 -0.05352306 -0.004644811 0.060382 -0.05344486 -0.007641792 0.06380218 -0.06284165 -0.007641792 0.06226092 -0.05860716 -0.007641792 0.06396985 -0.06291985 -0.004644811 0.06233912 -0.05843943 -0.004644811 0.06722229 -0.07223844 -0.007641792 0.06568109 -0.06800401 -0.007641792 0.06739002 -0.07231664 -0.004644811 0.0657593 -0.06783628 -0.004644811 0.07064247 -0.08163529 -0.007641792 0.06910127 -0.0774008 -0.007641792 0.07081019 -0.08171349 -0.004644811 0.06917947 -0.07723307 -0.004644811 0.07406264 -0.09103208 -0.007641792 0.07252138 -0.08679759 -0.007641792 0.07423037 -0.09111028 -0.004644811 0.07259958 -0.08662986 -0.004644811 0.07748281 -0.1004289 -0.007641792 0.07594156 -0.09619438 -0.007641792 0.07765048 -0.1005071 -0.004644811 0.07601976 -0.09602671 -0.004644811 0.08090293 -0.1098257 -0.007641792 0.07936173 -0.1055912 -0.007641792 0.08107066 -0.1099038 -0.004644811 0.07943993 -0.1054235 -0.004644811 0.0843231 -0.1192225 -0.007641792 0.08278185 -0.114988 -0.007641792 0.08449083 -0.1193007 -0.004644811 0.08286011 -0.1148203 -0.004644811 0.08774328 -0.1286193 -0.007641792 0.08620202 -0.1243848 -0.007641792 0.08791095 -0.1286975 -0.004644811 0.08628022 -0.124217 -0.004644811 0.09116339 -0.1380161 -0.007641792 0.08962219 -0.1337816 -0.007641792 0.09133112 -0.1380943 -0.004644811 0.0897004 -0.133614 -0.004644811 0.09458357 -0.1474128 -0.007641792 0.09304237 -0.1431784 -0.007641792 0.09475129 -0.147491 -0.004644811 0.09312057 -0.1430107 -0.004644811 0.09800374 -0.1568098 -0.007641792 0.09646254 -0.1525752 -0.007641792 0.09817147 -0.156888 -0.004644811 0.09654074 -0.1524075 -0.004644811 0.1014747 -0.1661829 -0.007660925 0.09988266 -0.161972 -0.007641792 0.1015916 -0.1662847 -0.004644811 0.09996086 -0.1618043 -0.004644811 0.104844 -0.1756033 -0.007641792 0.1033028 -0.1713688 -0.007641792 0.1050117 -0.1756815 -0.004644811 0.103381 -0.1712011 -0.004644811 0.1143186 -0.1778618 -0.004644811 0.1144863 -0.17794 -0.007641792 0.1159494 -0.1823422 -0.004644811 0.1160276 -0.1821745 -0.007641792 0.1082642 -0.1850001 -0.007641792 0.106723 -0.1807656 -0.007641792 0.1084319 -0.1850783 -0.004644811 0.1068012 -0.1805979 -0.004644811 0.1024405 -0.187259 -0.004644811 0.1042299 -0.1921754 -0.004644811 0.1047825 -0.1862674 -0.007641792 0.1032413 -0.1820328 -0.007641792 0.1005985 -0.1828661 -0.004873335 0.117968 -0.1766728 -0.007641792 0.1205281 -0.1756123 -0.004873335 0.09902036 -0.1778622 -0.004644811 0.1185206 -0.1707646 -0.004644811 0.1013624 -0.1768705 -0.007641792 0.1160891 -0.1715105 -0.007641792 0.09982115 -0.172636 -0.007641792 0.1145478 -0.167276 -0.007641792 0.09717833 -0.1734693 -0.004873335 0.1171079 -0.1662155 -0.004873335 0.09560018 -0.1684654 -0.004644811 0.1151005 -0.1613678 -0.004644811 0.09794223 -0.1674737 -0.007641792 0.112867 -0.1620202 -0.007625401 0.09640103 -0.1632393 -0.007641792 0.1111276 -0.1578792 -0.007641792 0.09375816 -0.1640725 -0.004873335 0.1136878 -0.1568188 -0.004873335 0.09218001 -0.1590686 -0.004644811 0.1116803 -0.1519711 -0.004644811 0.09452205 -0.1580769 -0.007641792 0.1092488 -0.1527169 -0.007641792 0.09298086 -0.1538425 -0.007641792 0.1077075 -0.1484823 -0.007641792 0.09033799 -0.1546757 -0.004873335 0.1102676 -0.147422 -0.004873335 0.08875989 -0.1496718 -0.004644811 0.1082602 -0.1425743 -0.004644811 0.09110194 -0.1486802 -0.007641792 0.1058286 -0.14332 -0.007641792 0.08956068 -0.1444456 -0.007641792 0.1042873 -0.1390855 -0.007641792 0.08691787 -0.1452789 -0.004873335 0.1068475 -0.1380251 -0.004873335 0.08533972 -0.140275 -0.004644811 0.10484 -0.1331775 -0.004644811 0.08768177 -0.1392832 -0.007641792 0.1024085 -0.1339232 -0.007641792 0.08614051 -0.1350488 -0.007641792 0.1008672 -0.1296888 -0.007641792 0.0834977 -0.1358821 -0.004873335 0.1034274 -0.1286283 -0.004873335 0.08191955 -0.1308782 -0.004644811 0.1014199 -0.1237807 -0.004644811 0.08426159 -0.1298865 -0.007641792 0.09898829 -0.1245265 -0.007641792 0.08272039 -0.125652 -0.007641792 0.09744703 -0.1202919 -0.007641792 0.08007752 -0.1264854 -0.004873335 0.1000072 -0.1192315 -0.004873335 0.07849943 -0.1214814 -0.004644811 0.09799969 -0.1143839 -0.004644811 0.08084148 -0.1204897 -0.007641792 0.09556812 -0.1151297 -0.007641792 0.07930022 -0.1162553 -0.007641792 0.09402692 -0.1108951 -0.007641792 0.07665735 -0.1170886 -0.004873335 0.09658706 -0.1098346 -0.004873335 0.07507926 -0.1120846 -0.004644811 0.09457951 -0.1049871 -0.004644811 0.0774213 -0.1110929 -0.007641792 0.09214794 -0.1057328 -0.007641792 0.07588005 -0.1068584 -0.007641792 0.09060674 -0.1014984 -0.007641792 0.07323724 -0.1076917 -0.004873335 0.09316688 -0.1004379 -0.004873335 0.07165908 -0.1026877 -0.004644811 0.09115934 -0.09559023 -0.004644811 0.07400113 -0.1016961 -0.007641792 0.08872783 -0.096336 -0.007641792 0.07245993 -0.09746164 -0.007641792 0.08718657 -0.09210151 -0.007641792 0.06981706 -0.09829491 -0.004873335 0.08974677 -0.09104108 -0.004873335 0.06823897 -0.09329098 -0.004644811 0.08773916 -0.08619344 -0.004644811 0.07058095 -0.09229928 -0.007641792 0.08530765 -0.08693921 -0.007641792 0.06903976 -0.08806478 -0.007641792 0.0837664 -0.08270472 -0.007641792 0.06639689 -0.08889812 -0.004873335 0.08632659 -0.08164429 -0.004873335 0.06481879 -0.08389413 -0.004644811 0.08431905 -0.07679665 -0.004644811 0.06716084 -0.08290249 -0.007641792 0.08188748 -0.07754242 -0.007641792 0.06561958 -0.07866799 -0.007641792 0.08034628 -0.07330793 -0.007641792 0.06297671 -0.07950127 -0.004873335 0.08290642 -0.0722475 -0.004873335 0.06139862 -0.07449734 -0.004644811 0.08089888 -0.06739985 -0.004644811 0.06374067 -0.07350569 -0.007641792 0.0784673 -0.06814563 -0.007641792 0.06219941 -0.0692712 -0.007641792 0.07692611 -0.06391113 -0.007641792 0.0595566 -0.07010447 -0.004873335 0.07948625 -0.06285071 -0.004873335 0.05797845 -0.06510055 -0.004644811 0.0774787 -0.058003 -0.004644811 0.06032049 -0.0641089 -0.007641792 0.07504719 -0.05874878 -0.007641792 0.05877929 -0.05987435 -0.007641792 0.07350593 -0.05451434 -0.007641792 0.05690032 -0.05471205 -0.007641792 0.07162702 -0.04935199 -0.007641792 0.06930667 -0.04297697 -0.007641792 0.05613642 -0.06070768 -0.004873335 0.07606613 -0.05345386 -0.004873335 0.05434018 -0.05577254 -0.004873335 0.07426989 -0.04851871 -0.004873335 0.1209564 -0.2046822 -0.002641856 0.1230394 -0.2042447 -0.002641856 0.1189562 -0.2054102 -0.002641856 0.1170793 -0.206414 -0.002641856 0.1213881 -0.1860696 -0.007641792 0.1239483 -0.1850092 -0.004873335 0.1066491 -0.1914473 -0.007651984 0.1180168 -0.208489 -0.01850521 0.1159425 -0.2071753 -0.01525521 0.1159113 -0.2102419 -0.01850521 0.1143254 -0.2126182 -0.01877653 0.1090975 -0.210814 -0.01100528 0.1130474 -0.2148765 -0.01850521 0.1079377 -0.2135966 -0.01100528 0.1124136 -0.217507 -0.01849639 0.1123854 -0.2202342 -0.01850998 0.1065616 -0.2195287 -0.01026529 0.1111272 -0.2216411 -0.0165016 0.1081529 -0.225247 -0.01101702 0.1074045 -0.2225401 -0.01100528 0.1095786 -0.2282654 -0.01100528 0.1115254 -0.2309567 -0.01100528 0.1139337 -0.2332444 -0.01100528 0.118002 -0.2313789 -0.01649665 0.1167213 -0.2350505 -0.01100528 0.1197933 -0.2363138 -0.01100528 0.1218308 -0.2314349 -0.01850521 0.1230452 -0.2369911 -0.01100528 0.1241459 -0.2318205 -0.01850521 0.1257476 -0.2341147 -0.01525521 0.1264938 -0.2317749 -0.01850527 0.1267294 -0.2331575 -0.01650524 0.126366 -0.2370592 -0.01100528 0.1261852 -0.2353171 -0.01350528 0.1291808 -0.2348276 -0.01350528 0.1312549 -0.2360898 -0.0109716 0.132033 -0.2337895 -0.01350528 0.1356237 -0.2336897 -0.01100528 0.1346424 -0.232239 -0.01350528 0.1342048 -0.2310366 -0.01525521 0.1381238 -0.2315028 -0.01100528 0.1342359 -0.2279699 -0.01850521 0.1321304 -0.2297229 -0.01850521 0.1401796 -0.2288938 -0.01100528 0.1358167 -0.2255961 -0.01877623 0.1417208 -0.2259514 -0.01100528 0.1370998 -0.2233355 -0.01850521 0.1426953 -0.222776 -0.01100528 0.1377258 -0.2206681 -0.01850521 0.1430696 -0.2194755 -0.01100528 0.1389802 -0.216292 -0.01652586 0.142831 -0.2161625 -0.01100528 0.1419889 -0.212948 -0.01100265 0.1409797 -0.2107393 -0.01108098 0.1395309 -0.2075399 -0.0102638 0.1283164 -0.206777 -0.01850521 0.1314676 -0.2047644 -0.01428204 0.1260014 -0.2063915 -0.01850521 0.1261271 -0.2011371 -0.01100528 0.1243996 -0.2040971 -0.01525521 0.1236538 -0.206437 -0.01850527 0.1330336 -0.2064644 -0.01544493 0.1053004 -0.2150916 -0.00775659 0.1122996 -0.2269685 0.01049435 0.1118431 -0.2261715 -0.01057648 0.1109784 -0.2242361 0.01049435 0.1135505 -0.2287074 -0.01055747 0.1141439 -0.2293789 0.01049435 0.1157362 -0.230844 -0.01055526 0.1164356 -0.2313688 0.01049435 0.1183094 -0.2324931 -0.0105583 0.1190809 -0.2328566 0.01049435 0.1211648 -0.2335866 -0.01057404 0.1219715 -0.2337814 0.01049435 0.1241823 -0.2340784 -0.01056247 0.1249892 -0.2341055 0.01049435 0.12724 -0.2339484 -0.01000529 0.1280103 -0.2338154 0.01049435 0.1302038 -0.2332012 -0.01000529 0.1309112 -0.2329232 0.01049435 0.1329485 -0.2318711 -0.01062065 0.1335731 -0.2314653 0.01049435 0.135367 -0.2300139 -0.01099324 0.135887 -0.2295014 0.01049435 0.1373668 -0.2276981 -0.01092642 0.1377582 -0.2271118 0.01049435 0.1388567 -0.2250222 -0.01055014 0.1391102 -0.2243946 0.01049435 0.1397698 -0.2221053 -0.01054894 0.1398874 -0.2214608 0.01049435 0.1400727 -0.2190638 -0.01054745 0.1400582 -0.2184305 0.01049435 0.1397528 -0.216024 -0.01054614 0.1396155 -0.215428 0.01049435 0.1388232 -0.2131122 -0.01054483 0.1385775 -0.212576 0.01049435 0.1373208 -0.2104457 -0.01000529 0.1369866 -0.2099915 0.01049435 0.1353152 -0.2081478 -0.01060813 0.134908 -0.2077799 0.01049435 0.1328796 -0.2062981 -0.01052713 0.1324267 -0.2060321 0.01049435 0.1301208 -0.2049814 -0.01044511 0.1296445 -0.2048195 0.01049435 0.1271523 -0.2042515 -0.01044893 0.1266751 -0.2041919 0.01049435 0.1236402 -0.2041748 0.01049435 0.1206639 -0.204769 0.01049435 0.1178681 -0.2059501 0.01049435 0.1153674 -0.2076699 0.01049435 0.1139352 -0.2090612 -0.01055079 0.113264 -0.2098578 0.01049435 0.1121311 -0.2115257 -0.01061451 0.1116442 -0.2124244 0.01049435 0.110862 -0.2143075 -0.01000529 0.1105741 -0.2152645 0.01049435 0.1101855 -0.2172853 -0.01051586 0.1100975 -0.218262 0.01049435 0.1101256 -0.2203411 -0.01056653 0.1102343 -0.2212938 0.01049435 0.1106864 -0.2233489 -0.01000529 0.1248111 -0.2260055 -0.01834946 0.1203563 -0.2139676 -0.01837778 0.1253977 -0.2122049 -0.018386 0.1311336 -0.2276293 -0.01844924 0.1182869 -0.2250591 -0.01649922 0.1174713 -0.2187806 -0.01647526 0.1169238 -0.2207229 -0.01650422 0.1152052 -0.218735 -0.01623249 0.1140527 -0.2200934 -0.01677793 0.1167591 -0.2235497 -0.01653301 0.1166949 -0.2234336 -0.01845872 0.1130467 -0.2169435 -0.01398652 0.1222657 -0.2307466 -0.0151354 0.1181793 -0.2191682 -0.01575523 0.1179785 -0.2188681 -0.01171594 0.1185317 -0.21904 -0.01110577 0.1172965 -0.2186756 -0.01113909 0.1237337 -0.2332479 -0.01101291 0.1232041 -0.2330824 -0.01228326 0.1148443 -0.215336 -0.01099658 0.1118237 -0.2161954 -0.01102423 0.1150491 -0.2185962 -0.01116162 0.1113209 -0.2164874 -0.01226592 0.1112554 -0.2206256 -0.01281595 0.111186 -0.2216507 -0.01114511 0.1318585 -0.2131552 -0.01649886 0.1326772 -0.2194607 -0.01647341 0.1334836 -0.215345 -0.01652538 0.1332231 -0.2149045 -0.01848071 0.1280646 -0.2053119 -0.01210981 0.1267321 -0.2056563 -0.0110808 0.1273182 -0.206053 -0.01155549 0.1273583 -0.2063804 -0.01343798 0.1316475 -0.2067748 -0.0126295 0.1321583 -0.2069681 -0.01098322 0.1329625 -0.2074676 -0.01250195 0.1387906 -0.2159808 -0.01120626 0.1389567 -0.2220107 -0.01101422 0.1388881 -0.2174761 -0.01273083 0.1388365 -0.221671 -0.01235461 0.127936 -0.2076411 -0.01529788 0.1370599 -0.2213478 -0.01492059 0.131968 -0.2190436 -0.01575523 0.1314439 -0.2181866 -0.01135945 0.1315133 -0.2199283 -0.01100468 0.1336076 -0.2195007 -0.01127845 0.1321681 -0.2193419 -0.01175528 0.135612 -0.2199367 -0.01106321 0.1353045 -0.2228874 -0.0110194 0.1370788 -0.2214885 -0.01110738 0.1272772 -0.2307063 -0.01100528 0.1294079 -0.2321987 -0.01104414 0.1297024 -0.2323337 -0.01350528 0.1309985 -0.2306054 -0.01102727 0.1306567 -0.2294542 -0.01350528 0.1293648 -0.2285647 -0.01100528 0.1286782 -0.2286248 -0.01350528 0.1274331 -0.2304465 -0.01350528 0.1170419 -0.2209295 -0.01850503 0.1331053 -0.2172824 -0.01850503 0.1172116 -0.2297505 -0.0135625 0.1306049 -0.2233768 -0.01850521 0.1321093 -0.220333 -0.01850521 0.1359049 -0.2208651 -0.01850426 0.1324853 -0.2260896 -0.01850503 0.1195423 -0.2148351 -0.01850521 0.1180379 -0.2178789 -0.01850521 0.1142425 -0.2173469 -0.01850426 0.1176618 -0.2121222 -0.01850503 0.113606 -0.2163169 -0.0170049 0.1162896 -0.2181482 -0.01700496 0.1187452 -0.2171335 -0.01700496 0.1193742 -0.2138262 -0.01700437 0.1166379 -0.2120341 -0.01700496 0.1142708 -0.2129792 -0.0169931 0.1151996 -0.2164108 -0.01699906 0.117399 -0.2165663 -0.01700329 0.118209 -0.2150188 -0.01700365 0.1172738 -0.2135437 -0.01700323 0.1151441 -0.2138269 -0.01699805 0.130773 -0.2243857 -0.01700437 0.133509 -0.2261779 -0.01700496 0.1358765 -0.2252327 -0.0169931 0.1365412 -0.2218949 -0.0170049 0.1338579 -0.2200637 -0.01700496 0.1314021 -0.2210783 -0.01700496 0.1328734 -0.2246683 -0.01700323 0.1319382 -0.223193 -0.01700365 0.1350031 -0.224385 -0.01699805 0.1349476 -0.221801 -0.01699906 0.1327481 -0.2216455 -0.01700323 0.117626 -0.2310022 -0.01097321 0.1239767 -0.2146697 -0.01100528 0.1218111 -0.2160066 -0.01100528 0.1174589 -0.213696 -0.01100516 0.1154519 -0.2138038 -0.01100516 0.1158548 -0.2166112 -0.01101088 0.1178593 -0.216086 -0.01102066 0.1206274 -0.2180626 -0.01102095 0.1211174 -0.2214332 -0.0110197 0.1246702 -0.2237733 -0.01100528 0.1284213 -0.2222176 -0.01100528 0.1330746 -0.2246407 -0.01100528 0.1346952 -0.2244082 -0.01100522 0.1326715 -0.2218334 -0.01100319 0.1320626 -0.2233534 -0.01100528 0.1296442 -0.219183 -0.01100516 0.1342925 -0.2216008 -0.01100349 0.1289474 -0.2168161 -0.01100528 0.127224 -0.2150725 -0.01100528 0.1219419 -0.180164 -0.004645645 0.1195092 -0.1809072 -0.007641792 0.07303667 -0.04513043 -0.004873335 0.05310696 -0.05238425 -0.004873335 0.1296593 -0.1870815 0.004911422 0.1328098 -0.1950556 0.004662334 0.1319748 -0.2006026 0.008157908 0.1341527 -0.1954133 0.003950178 0.1381563 -0.2044709 0.004883885 0.1361635 -0.2039614 0.00694406 0.1403563 -0.2093826 0.007144451 0.1322926 -0.2020393 0.009815335 0.1366859 -0.2054321 0.009806573 0.13975 -0.2085257 0.01000332 0.1233723 -0.1985593 0.009045064 0.1184602 -0.2010267 0.009543597 0.1215825 -0.2023634 0.01047539 0.1130718 -0.2022407 0.009011745 0.1131556 -0.2054321 0.009950876 0.1087837 -0.2084637 0.009373247 0.1042053 -0.2055133 0.004180192 0.1016014 -0.1968162 0.004963994 0.1045192 -0.1934066 0.007020592 0.06339609 -0.07224506 -5.22973e-5 0.0642212 -0.07234692 -4.91907e-4 0.06489998 -0.07012581 -4.36983e-4 0.07735437 -0.06756687 -4.91907e-4 0.07496851 -0.06630402 -9.80913e-5 0.06574189 -0.07652503 -4.91907e-4 0.07941335 -0.07223832 -4.90816e-4 0.0781964 -0.07396471 -4.69378e-4 0.0647214 -0.06991302 0.007020592 0.06312823 -0.07222223 0.00701034 0.07495617 -0.06604206 0.007064759 0.07791042 -0.06693398 -3.81686e-5 0.07805502 -0.06672269 0.00702548 0.07957941 -0.07148861 2.31909e-4 0.07995855 -0.07183611 0.00702238 0.07837879 -0.07418274 0.007160961 0.06812775 -0.07778793 -9.80817e-5 0.06813985 -0.07804834 0.007020592 0.0651859 -0.07715767 -4.49495e-5 0.06504118 -0.07736915 0.00702697 0.07922524 -0.07797908 -4.82309e-4 0.06934857 -0.08111888 -9.5352e-5 0.06751656 -0.0835095 -4.90583e-4 0.07907152 -0.07756811 2.31909e-4 0.06904608 -0.08098119 0.007021725 0.07906043 -0.07731831 0.00706464 0.0820145 -0.07821023 -4.09675e-5 0.08221894 -0.08093208 -4.91907e-4 0.08379888 -0.08311831 -1.1445e-4 0.07216697 -0.08907204 -4.91688e-4 0.08230006 -0.08524107 -4.69052e-4 0.08215922 -0.07799887 0.00702548 0.08406269 -0.08311223 0.00702238 0.08248305 -0.08545893 0.007163226 0.07224404 -0.08932447 0.007020592 0.0692901 -0.0884341 -3.81818e-5 0.06914556 -0.08864527 0.007021129 0.06723982 -0.08352583 0.007021188 0.07634156 -0.1003258 -4.06991e-4 0.08606678 -0.09679836 -9.57303e-5 0.08789581 -0.09442055 -4.90594e-4 0.07339459 -0.09970986 -5.02601e-5 0.07395029 -0.0990774 -4.91907e-4 0.08556276 -0.09011918 -4.91907e-4 0.07210212 -0.0937016 -4.91953e-4 0.08622568 -0.09700554 0.007020592 0.07634902 -0.1006044 0.007125616 0.07324975 -0.09992146 0.007021129 0.07160878 -0.0948019 -8.22547e-5 0.07134616 -0.09480816 0.00702238 0.0730955 -0.09267282 -1.8812e-4 0.07292979 -0.0924654 0.007020592 0.08317691 -0.08885633 -9.80786e-5 0.08316457 -0.08859437 0.007064759 0.08611881 -0.0894863 -3.81665e-5 0.08626317 -0.08927506 0.007019639 0.088171 -0.09440004 0.007021725 0.07749122 -0.1109672 -4.03923e-5 0.08021759 -0.1116648 7.91635e-6 0.08026748 -0.1112433 -4.28287e-4 0.07805448 -0.1103535 -4.91907e-4 0.07599562 -0.1056816 -4.90905e-4 0.07582944 -0.1064318 2.31909e-4 0.09199166 -0.1056744 -4.93432e-4 0.08966696 -0.1013954 -4.91907e-4 0.07721155 -0.1039547 -4.37511e-4 0.07999765 -0.1119008 0.007138192 0.07734614 -0.1111772 0.007023394 0.07545036 -0.1060843 0.00702238 0.07703399 -0.1037415 0.007020592 0.0872811 -0.1001325 -9.80477e-5 0.087269 -0.09987056 0.007063567 0.09022301 -0.1007625 -3.81645e-5 0.09036767 -0.1005512 0.007026314 0.09227108 -0.1056646 0.00702238 0.09052258 -0.1078003 -1.70614e-4 0.09069037 -0.1080086 0.007100045 0.08160096 -0.1222581 -3.76492e-5 0.08432179 -0.122941 7.91635e-6 0.08437156 -0.1225194 -4.28288e-4 0.08215868 -0.1216297 -4.91907e-4 0.08009982 -0.1169579 -4.90905e-4 0.07993364 -0.117708 2.31909e-4 0.09609586 -0.1169505 -4.93432e-4 0.09377115 -0.1126715 -4.91907e-4 0.08131575 -0.1152309 -4.37513e-4 0.08455657 -0.123153 0.007020592 0.08145827 -0.1224738 0.007019639 0.07955461 -0.1173602 0.007018923 0.08113819 -0.1150177 0.007020592 0.0913853 -0.1114087 -9.81463e-5 0.09137058 -0.1111384 0.007282495 0.09432715 -0.1120386 -3.81828e-5 0.09447169 -0.1118274 0.007021129 0.09637528 -0.1169407 0.00702238 0.09462678 -0.1190764 -1.70626e-4 0.09479689 -0.1192905 0.007236838 0.08569967 -0.1335196 -4.03719e-5 0.08842599 -0.1342172 7.91635e-6 0.0884757 -0.1337956 -4.28291e-4 0.08626288 -0.1329059 -4.91907e-4 0.08420401 -0.128234 -4.90905e-4 0.08403784 -0.1289841 2.31909e-4 0.1002001 -0.1282267 -4.93432e-4 0.09787535 -0.1239477 -4.91907e-4 0.08541995 -0.126507 -4.37513e-4 0.08821052 -0.1344488 0.007020592 0.08555454 -0.1337295 0.007023394 0.08365875 -0.1286367 0.00702238 0.08523976 -0.1262888 0.007172703 0.0954895 -0.1226848 -9.81414e-5 0.0954774 -0.1224244 0.007020592 0.09843134 -0.1233148 -3.81856e-5 0.09857589 -0.1231036 0.007021129 0.1004795 -0.1282169 0.00702238 0.09873092 -0.1303525 -1.70568e-4 0.09889876 -0.130561 0.007100045 0.08980381 -0.1447957 -4.03607e-5 0.09253013 -0.1454933 7.91635e-6 0.09257996 -0.1450718 -4.28292e-4 0.09036707 -0.144182 -4.91907e-4 0.08830821 -0.1395102 -4.90905e-4 0.08814203 -0.1402602 2.31909e-4 0.1043042 -0.1395028 -4.93432e-4 0.1019796 -0.1352238 -4.91907e-4 0.08952414 -0.1377832 -4.37516e-4 0.09231472 -0.145725 0.007020592 0.08965873 -0.1450056 0.007023394 0.08776301 -0.1399126 0.007018923 0.08934658 -0.13757 0.007020592 0.09959363 -0.133961 -9.81523e-5 0.09957897 -0.1336907 0.007282495 0.1025356 -0.1345909 -3.81988e-5 0.10268 -0.1343798 0.007021129 0.1045836 -0.139493 0.00702238 0.1028352 -0.1416287 -1.70562e-4 0.1030029 -0.1418371 0.007098019 0.09390807 -0.1560719 -4.04346e-5 0.09663432 -0.1567695 7.91635e-6 0.09668415 -0.1563479 -4.2829e-4 0.09447121 -0.1554582 -4.91907e-4 0.09241241 -0.1507863 -4.90905e-4 0.09224623 -0.1515364 2.31909e-4 0.1084085 -0.150779 -4.93432e-4 0.1060837 -0.1465 -4.91907e-4 0.09362834 -0.1490594 -4.37507e-4 0.09641891 -0.1570011 0.007020592 0.09376293 -0.1562818 0.007023394 0.09186708 -0.151189 0.00702238 0.09345078 -0.1488462 0.007020592 0.1036978 -0.1452372 -9.81143e-5 0.1036856 -0.1449753 0.007064759 0.1066396 -0.1458671 -3.81974e-5 0.1067841 -0.1456558 0.007019639 0.1086878 -0.1507694 0.007018923 0.1069393 -0.1529048 -1.70577e-4 0.1071059 -0.1531147 0.007125258 0.0980122 -0.167348 -4.04189e-5 0.1007386 -0.1680456 7.91635e-6 0.1007884 -0.1676241 -4.28292e-4 0.09857541 -0.1667344 -4.91907e-4 0.0965166 -0.1620625 -4.90905e-4 0.09635037 -0.1628127 2.31909e-4 0.1125126 -0.1620552 -4.93432e-4 0.1101878 -0.1577762 -4.91907e-4 0.09773248 -0.1603356 -4.3751e-4 0.1005231 -0.1682773 0.007020592 0.09786713 -0.167558 0.007023394 0.09597128 -0.1624652 0.00702238 0.09755492 -0.1601224 0.007020592 0.107802 -0.1565133 -9.80525e-5 0.1077899 -0.1562514 0.007063567 0.1107439 -0.1571433 -3.82068e-5 0.1108884 -0.1569321 0.007020771 0.112792 -0.1620454 0.00702238 0.1110436 -0.1641811 -1.70503e-4 0.1112112 -0.1643895 0.007098019 0.1021218 -0.1786388 -3.77137e-5 0.1048427 -0.1793217 7.91635e-6 0.1048925 -0.1789003 -4.28292e-4 0.1026796 -0.1780105 -4.91907e-4 0.1006208 -0.1733386 -4.90905e-4 0.1004546 -0.1740888 2.31909e-4 0.1166168 -0.1733313 -4.93432e-4 0.1142921 -0.1690524 -4.91907e-4 0.1018368 -0.1716117 -4.37512e-4 0.1050775 -0.1795338 0.007020592 0.1019791 -0.1788546 0.007021129 0.1000756 -0.1737411 0.007018923 0.1016592 -0.1713985 0.007020592 0.1119062 -0.1677895 -9.80622e-5 0.1118932 -0.1675268 0.007087647 0.1148481 -0.1684194 -3.815e-5 0.1149928 -0.1682083 0.00702548 0.1168962 -0.1733217 0.00702238 0.1151477 -0.1754572 -1.70505e-4 0.1153162 -0.1756688 0.007163405 0.1091751 -0.1905351 -4.06993e-4 0.1189003 -0.1870077 -9.56628e-5 0.1207293 -0.1846299 -4.90594e-4 0.1062281 -0.1899192 -5.02792e-5 0.1067838 -0.1892867 -4.91907e-4 0.1183962 -0.1803286 -4.91907e-4 0.1049357 -0.1839109 -4.91953e-4 0.1190592 -0.1872149 0.007020592 0.1060832 -0.1901307 0.007021129 0.1044422 -0.1850113 -8.22476e-5 0.1041797 -0.1850174 0.00702238 0.105929 -0.1828821 -1.88149e-4 0.1057633 -0.1826747 0.007020592 0.1160104 -0.1790656 -9.8036e-5 0.1159981 -0.1788037 0.007064759 0.1189524 -0.1796957 -3.81801e-5 0.1190967 -0.1794844 0.007019639 0.1210056 -0.1846088 0.007048487 0.1103288 -0.2011761 -4.60372e-5 0.1130511 -0.2018741 7.91635e-6 0.113101 -0.2014526 -4.28286e-4 0.1101276 -0.1984738 -4.91907e-4 0.1085494 -0.1962849 -1.11837e-4 0.1100447 -0.1941643 -4.38204e-4 0.1248179 -0.1958947 -4.9344e-4 0.1225005 -0.1916047 -4.91907e-4 0.1082863 -0.1962911 0.007009565 0.1098675 -0.1939508 0.007020592 0.1201146 -0.1903418 -9.80649e-5 0.1201025 -0.1900799 0.007063508 0.1230552 -0.1909716 -3.97083e-5 0.123199 -0.1907606 0.007009804 0.1233641 -0.1980016 -1.6544e-4 0.1264337 -0.1885054 0.007326126 0.08203077 -0.04814124 0.002919375 0.08748358 -0.06724154 0.003962278 0.08590811 -0.06556051 0.004429876 0.08762854 -0.06910431 0.00431317 0.08135914 -0.06423729 0.007145881 0.08661448 -0.0725665 0.005738794 0.084136 -0.07392859 0.00783044 0.09316539 -0.08588731 0.004689157 0.09111219 -0.08077889 0.004816412 0.09157407 -0.08408915 0.005188584 0.08913189 -0.08181017 0.006235957 0.09918129 -0.1044404 0.005173981 0.09476095 -0.09233224 0.005182445 0.09801751 -0.1021101 0.00539726 0.1002453 -0.1094691 0.005680501 0.1055269 -0.1228839 0.005415618 0.102752 -0.1177627 0.0058766 0.1041822 -0.1216684 0.005927264 0.1006146 -0.1116831 0.005838036 0.1063083 -0.1279766 0.005960524 0.1074801 -0.1310037 0.006031453 0.1122012 -0.1412137 0.00541377 0.1100205 -0.1377599 0.005961596 0.119201 -0.1594206 0.005168378 0.1139565 -0.147022 0.005650341 0.1170316 -0.1566748 0.005742549 0.1144731 -0.1497527 0.005871236 0.1205518 -0.1654587 0.005579948 0.121843 -0.1683196 0.005502045 0.1252146 -0.1754969 0.005061089 0.1265186 -0.1774871 0.004680216 0.1262243 -0.1790552 0.00517106 0.123517 -0.1767002 0.006546497 0.0779078 -0.05004417 0.006144404 0.1182457 -0.2003463 0.008779823 0.1022199 -0.2045303 -0.007755339 0.142831 -0.2161625 0.009994387 0.1419879 -0.2129496 0.009994387 0.1417488 -0.214765 0.01049453 0.1430696 -0.2194755 0.009994387 0.141582 -0.2249172 0.01049548 0.1426953 -0.222776 0.009994387 0.1396831 -0.2297204 0.01000654 0.1358284 -0.232344 0.01049435 0.1346794 -0.2344291 0.009988546 0.1268124 -0.236525 0.01049566 0.1197933 -0.2363138 0.009994387 0.117363 -0.2344903 0.01049447 0.1139337 -0.2332444 0.009994387 0.1100374 -0.2280741 0.01049554 0.1075022 -0.2230253 0.009992182 0.1073099 -0.2187742 0.01041281 0.1082022 -0.214096 0.01044321 0.1140193 -0.2057566 0.01049482 0.1278601 -0.2021276 0.01049453 0.1341538 -0.2044485 0.01049363 0.1385728 -0.2084041 0.01049411 0.1081594 -0.2252622 0.009994387 0.1095786 -0.2282654 0.009994387 0.1115254 -0.2309567 0.009994387 0.1167213 -0.2350505 0.009994387 0.1230452 -0.2369911 0.009994387 0.1276032 -0.2370144 0.009996354 0.1417208 -0.2259514 0.009994387 0.1417813 -0.2260043 -0.009505212 0.1430457 -0.2205608 -0.009489059 0.1391988 -0.2302625 -0.009505331 0.1356616 -0.2337561 -0.009505271 0.1312299 -0.2360202 -0.009505331 0.1263802 -0.2371345 -0.009505152 0.1214243 -0.2367319 -0.009505331 0.1167085 -0.2351297 -0.009505212 0.1120198 -0.231557 -0.009476065 0.1113706 -0.2307771 -0.007356286 0.1123253 -0.2318131 -0.003559112 0.1140055 -0.2333214 1.25899e-4 0.1161427 -0.2347539 0.0029217 0.1187034 -0.2359496 0.005108654 0.1230307 -0.2370674 0.00749129 0.1295052 -0.2366241 0.008967041 0.1337853 -0.2348731 0.008839786 0.1381837 -0.2315524 0.007491409 0.1407802 -0.2279146 0.005108773 0.1419742 -0.2253505 0.002894997 0.1426888 -0.2228865 8.87216e-5 0.1430074 -0.2206458 -0.003559112 0.1430729 -0.2192385 -0.007356464 0.1069995 -0.2207841 0.006773769 0.1414526 -0.2116414 0.003033339 0.1217107 -0.1657219 -3.37208e-4 0.115248 -0.149258 -3.37208e-4 0.1090553 -0.1327003 -3.37208e-4 0.1031323 -0.1160486 -3.37208e-4 0.09747904 -0.09930336 -3.37208e-4 0.09209519 -0.08246433 -3.37208e-4 0.08698058 -0.06553173 -3.37208e-4 0.08213537 -0.04850649 -3.3066e-4 0.104997 -0.2140418 0.004522323 0.1074045 -0.2225401 0.003149688 0.1071065 -0.2135564 0.00713092 0.1204098 -0.1648108 -8.38464e-4 0.1236445 -0.1754239 -0.001414954 0.1212602 -0.1694648 -0.00139296 0.1196523 -0.165485 -0.001428127 0.1176428 -0.160437 -0.001422405 0.1158995 -0.1559864 -0.001387298 0.1139777 -0.1510314 -0.001396417 0.1154521 -0.1570629 -0.001496136 0.1124246 -0.1469676 -0.001413226 0.1103056 -0.1413448 -0.001410007 0.1088594 -0.1374468 -0.001392543 0.1058451 -0.1265325 -8.70411e-4 0.1068669 -0.1321584 -0.001432836 0.1054498 -0.1280817 -0.001407027 0.1034055 -0.1224858 -0.001415312 0.1019928 -0.1184647 -0.001419067 0.1001037 -0.1129969 -0.001437664 0.09873884 -0.1088321 -0.001419007 0.09688234 -0.103456 -0.001435339 0.09555631 -0.09943175 -0.001414954 0.09365183 -0.09357345 -0.001415133 0.09229856 -0.08918601 -0.001442849 0.09083521 -0.08470833 -0.001426279 0.08959543 -0.08070212 -0.001414895 0.08748006 -0.07359546 -0.001390039 0.08614736 -0.06912589 -0.001420378 0.08502614 -0.06607204 -0.001491844 0.07931852 -0.04583519 -0.001490235 0.07954299 -0.04470312 -0.001196861 0.07867449 -0.04227787 -0.001306772 0.1001565 -0.1123231 0.004985213 0.0985465 -0.1138008 -0.001495599 0.1023334 -0.1185948 0.00515908 0.1012406 -0.1189787 -0.001491606 0.1055835 -0.1277814 0.005137026 0.1035884 -0.1221835 0.005096673 0.1069147 -0.1314871 0.005132436 0.1054385 -0.1328009 -0.001495778 0.1091794 -0.1376633 0.005138576 0.1072402 -0.1377664 -0.001493394 0.1104891 -0.141121 0.005641698 0.1127076 -0.1470247 0.005506992 0.1139388 -0.1503065 0.005022764 0.1129988 -0.1508458 -0.001491904 0.1163312 -0.1564872 0.004933893 0.1178151 -0.1602203 0.005353093 0.1197627 -0.1651746 0.00476247 0.1190213 -0.1670355 0.006518125 0.1212848 -0.1689631 0.004668653 0.1202623 -0.1692879 -0.001491606 0.1201508 -0.1689347 0.006315886 0.1240043 -0.175626 0.004556834 0.1231971 -0.1762402 -0.001472651 0.1207596 -0.1756023 -0.001491844 0.09991616 -0.1183437 -0.001491844 0.09848207 -0.1144037 -0.001491844 0.09674912 -0.1096425 -0.001491844 0.0947377 -0.1041161 -0.001491844 0.09300744 -0.09936219 -0.001491844 0.09157335 -0.09542214 -0.001491844 0.08984041 -0.09066092 -0.001491844 0.08782899 -0.08513456 -0.001491844 0.08609873 -0.08038067 -0.001491844 0.08454948 -0.07612496 -0.001491904 0.08293169 -0.07167941 -0.001491844 0.08080065 -0.06582087 -0.001491844 0.07856285 -0.04739654 -0.001491844 0.08149403 -0.06515842 -0.001491844 0.08387905 -0.07224231 -0.00149244 0.08638423 -0.0734235 -0.001491963 0.08639115 -0.08075052 -0.001491844 0.08817082 -0.08409857 -0.001492321 0.08891856 -0.0814675 -0.001495242 0.09155964 -0.09495085 -0.001491844 0.09072637 -0.09128415 -0.001490235 0.09264868 -0.09332817 -0.001495361 0.09329986 -0.0997321 -0.001491844 0.0950638 -0.1030994 -0.001492559 0.0949546 -0.1002156 -0.00149846 0.09765714 -0.1101992 -0.001493334 0.1016464 -0.1230977 -0.001491844 0.1036579 -0.128624 -0.001491844 0.1053908 -0.1333853 -0.001491844 0.1045401 -0.1291701 -0.001496016 0.1002086 -0.1187136 -0.001491844 0.1019741 -0.1220859 -0.001500844 0.1068249 -0.1373253 -0.001491844 0.1085551 -0.1420792 -0.001491844 0.1105666 -0.1476055 -0.001491844 0.1121938 -0.152077 -0.001491904 0.1114521 -0.148171 -0.001492857 0.1088086 -0.1411052 -0.001495599 0.1137336 -0.1563068 -0.001491844 0.1154639 -0.1610608 -0.001491844 0.1174753 -0.1665871 -0.001491844 0.1190963 -0.1710416 -0.001491904 0.1184064 -0.1671377 -0.001496791 0.114026 -0.1566767 -0.001491844 0.1157435 -0.1600512 -0.001495599 0.08475261 -0.1461025 0.005136668 0.08281195 -0.1407353 0.005137264 0.08143532 -0.136978 0.005137562 0.07922363 -0.1310281 0.00510478 0.07778549 -0.1272203 0.005074441 0.07565766 -0.1216511 0.005002021 0.07819461 -0.1211975 0.007028043 0.07419133 -0.1179267 0.005493342 0.07203596 -0.1124233 0.005285203 0.07069826 -0.1090058 0.004768848 0.06808483 -0.1025286 0.004685163 0.06869465 -0.1015533 0.005950331 0.06651037 -0.09872555 0.005051314 0.06325083 -0.09081363 0.004219889 0.05994319 -0.08305352 0.004280209 0.04599905 -0.04815167 -0.006052792 0.04532939 -0.04206585 -0.02125513 0.04646205 -0.04907745 -0.006772816 0.04586416 -0.04334199 -0.02124732 0.04733717 -0.04975247 -0.007355868 0.04680067 -0.04423677 -0.02125513 0.0484789 -0.05006444 -0.007705032 0.04801261 -0.04465734 -0.02125513 0.04736024 -0.05702012 0.005145013 0.04460448 -0.04222702 0.005319595 0.0739299 -0.04115027 -0.007755339 0.07509076 -0.04037857 -0.007705032 0.07576483 -0.03940564 -0.007355868 0.07600134 -0.03832602 -0.006772816 0.07576096 -0.03731918 -0.006052792 0.0511834 -0.03635948 -0.02125513 0.05165117 -0.04114592 -0.02125513 0.05037844 -0.04256051 -0.02125513 0.0486949 -0.04264718 -0.02125513 0.0471372 -0.04155421 -0.02125513 0.04527288 -0.04017966 -0.02125513 0.0469911 -0.03918033 -0.02125513 0.0458545 -0.03851574 -0.02125513 0.04697746 -0.03715664 -0.02125513 0.04819375 -0.03799909 -0.02125513 0.05008453 -0.03778415 -0.02125513 0.05176806 -0.03946423 -0.02125513 0.0568369 -0.05453777 -0.002104878 0.1427122 -0.2189492 -0.007540345 0.1420831 -0.2232576 -0.009495615 0.1412314 -0.2258267 -0.009505331 0.1401539 -0.2279844 -0.009505331 0.13879 -0.2299735 -0.009505331 0.1363043 -0.2325768 -0.009503662 0.1332629 -0.2345713 -0.009505331 0.1300603 -0.2359297 -0.009504377 0.1252372 -0.2366378 -0.009506523 0.120453 -0.2360339 -0.009496092 0.1170161 -0.2346403 -0.009505331 0.1149568 -0.233385 -0.009505331 0.1130897 -0.2318584 -0.009505331 0.1119687 -0.2308515 -0.008559167 0.1126732 -0.2314538 -0.003543138 0.1140289 -0.23268 -4.7984e-4 0.1158781 -0.233995 0.002251505 0.1182408 -0.2352166 0.004597306 0.1201025 -0.2358952 0.005948483 0.1235727 -0.2365636 0.00762093 0.1275807 -0.2364875 0.008738219 0.1319014 -0.2352423 0.00899285 0.1300762 -0.2364398 -0.00343877 0.1275726 -0.2365334 -0.00527656 0.1320475 -0.2357898 -0.005152881 0.1332632 -0.2351408 -0.001175343 0.1359453 -0.2334536 7.75831e-4 0.1363149 -0.2331675 0.003506422 0.1371771 -0.232466 -0.003906071 0.1333078 -0.2346093 0.003663897 0.1349983 -0.2341512 -0.005550503 0.1379321 -0.2317146 2.58798e-4 0.1390789 -0.2304105 -0.003684163 0.13994 -0.2293429 0.00113821 0.1379387 -0.2310863 0.002140402 0.1241604 -0.2366583 -0.005469322 0.1371868 -0.231795 -0.004497468 0.1348477 -0.2336217 -0.005578458 0.1354889 -0.2332363 -2.14745e-4 0.1323375 -0.2350411 -0.004820525 0.1194837 -0.2357115 -0.006096243 0.1254728 -0.2370025 -0.004302442 0.138826 -0.2300065 -0.003002524 0.1406636 -0.2270554 0.004597306 0.1342312 -0.2340288 -2.55892e-4 0.1293871 -0.2361224 -0.003320276 0.1274123 -0.2365258 -0.003503501 0.1296616 -0.2364141 -0.00127083 0.1285109 -0.2367827 0.001787066 0.1320159 -0.2354021 0.00177282 0.1327797 -0.2353874 -8.49186e-4 0.1282284 -0.2363484 0.002032339 0.1234866 -0.2370815 -0.001467347 0.1231825 -0.2365096 -9.93563e-4 0.1219069 -0.2368392 0.001100778 0.1232918 -0.2365478 0.001679539 0.1249609 -0.2371389 0.00172162 0.126025 -0.2369244 -2.25133e-4 0.1209059 -0.2361188 -0.002855181 0.1205857 -0.2364684 -0.005141079 0.1229937 -0.2366495 -0.004591643 0.1422598 -0.2224036 -4.94575e-4 0.1416884 -0.2246009 0.002251505 0.1380523 -0.2309039 0.007329761 0.1349173 -0.2335996 0.008589923 0.1286595 -0.2363185 0.003373861 0.07950067 -0.045322 0.006144404 0.08041876 -0.04498785 0.005145013 0.07897013 -0.04965752 0.006144404 0.04726237 -0.03778707 0.006144404 0.04686069 -0.03939586 0.006433427 0.04819375 -0.03799909 0.006144404 0.04935932 -0.03772836 0.006144404 0.06741505 -0.03045165 0.006144404 0.06608116 -0.03194016 0.006144404 0.06698739 -0.03115874 0.006144404 0.06815505 -0.03087222 0.006438851 0.07209169 -0.03043425 0.005770266 0.06975311 -0.0314182 0.006144404 0.05051714 -0.03803026 0.006144404 0.06559044 -0.03377866 0.006144404 0.05168765 -0.03924334 0.006144404 0.06700444 -0.03569108 0.006144404 0.05165117 -0.04114592 0.006144404 0.07086938 -0.04509568 0.006144404 0.06938159 -0.03561377 0.006144404 0.07221472 -0.04407989 0.006144404 0.07066839 -0.03361344 0.006144404 0.07454133 -0.04457372 0.006144404 0.07232397 -0.03227049 0.006144404 0.05530536 -0.05118578 0.006144404 0.07043009 -0.04620867 0.006144404 0.05647587 -0.05239886 0.006144404 0.07084995 -0.0480647 0.006144404 0.05643939 -0.05430144 0.006144404 0.07227677 -0.04896235 0.006144404 0.05574649 -0.05527693 0.006144404 0.07416987 -0.04876929 0.006144404 0.07545661 -0.04676896 0.006144404 0.04940891 -0.0427857 0.006144404 0.05342113 -0.05092018 0.006144404 0.05095827 -0.04212141 0.006144404 0.05169308 -0.05255442 0.006144404 0.04538667 -0.04207485 0.006144404 0.04826885 -0.05665522 0.006144523 0.05205637 -0.05490499 0.006144404 0.05419719 -0.05594122 0.006144404 0.05147159 -0.05966615 0.006144404 0.04726815 -0.04174947 0.006144404 0.07317 -0.03180527 0.005145013 0.07056647 -0.02953785 0.005144715 0.06884169 -0.02921038 0.005144536 0.0444045 -0.04050779 0.005144894 0.04608726 -0.03749233 0.005144536 0.04497653 -0.03885185 0.005144715 0.06606173 -0.03490912 -0.01625519 0.06820255 -0.03594541 -0.01625519 0.07027149 -0.03477221 -0.01625519 0.0704813 -0.03240305 -0.01625519 0.06865066 -0.03088456 -0.01625519 0.06698739 -0.03115874 -0.01625519 0.06569844 -0.03255861 -0.01625519 0.06746566 -0.03479075 -0.01625567 0.06660211 -0.03352069 -0.0162447 0.06901133 -0.0346539 -0.01625508 0.06965565 -0.0332629 -0.01624691 0.06908351 -0.03223872 -0.01625519 0.06858921 -0.03195339 -0.0162301 0.06724476 -0.03214091 -0.01624238 0.04726815 -0.04174947 -0.01625519 0.0486949 -0.04264718 -0.01625519 0.05058801 -0.04245412 -0.01625519 0.05165117 -0.04114592 -0.01625519 0.05168765 -0.03924334 -0.01625519 0.04985707 -0.03772485 -0.01625519 0.04819375 -0.03799909 -0.01625519 0.0469048 -0.03939896 -0.01625519 0.04868268 -0.04160875 -0.01624161 0.04780852 -0.04036098 -0.0162447 0.05021774 -0.04149425 -0.01625508 0.05086201 -0.04010325 -0.01624691 0.05028992 -0.03907901 -0.01625519 0.04979556 -0.03879374 -0.0162301 0.04845112 -0.03898125 -0.01624238 0.0515598 -0.05354082 0.001144468 0.05254364 -0.0513736 0.001288414 0.05414754 -0.05088388 0.001144468 0.05592155 -0.05157226 0.001144468 0.0566315 -0.05384224 0.001144468 0.05516666 -0.05571603 0.001144468 0.05279368 -0.05556666 0.001302421 0.05442988 -0.05343931 5.71645e-4 0.07057988 -0.04549813 0.001293897 0.07055836 -0.04739832 0.001144468 0.07244372 -0.04402673 0.001144468 0.07409369 -0.04435783 0.001293718 0.07534992 -0.0457794 0.001144468 0.07492363 -0.04811936 0.001144468 0.07350981 -0.04895788 0.001237034 0.07158601 -0.0487346 0.001144468 0.06556522 -0.03354495 0.001144468 0.0665391 -0.03137505 0.001144468 0.06887811 -0.03094387 0.001144468 0.07019567 -0.03199541 0.001144468 0.07063692 -0.03384637 0.001144468 0.06917202 -0.03572022 0.001144468 0.06679779 -0.03557908 0.001144468 0.06657755 -0.03352278 0.001144886 0.06723099 -0.0321207 0.001145064 0.06873911 -0.03197699 0.001145184 0.06945097 -0.03264337 0.001136422 0.0695514 -0.03386807 0.001096606 0.0690003 -0.03463095 0.001128554 0.06747627 -0.03476846 0.001130878 0.04684829 -0.03989344 0.001144468 0.0471372 -0.04155421 0.001144468 0.04774552 -0.03821533 0.001144468 0.05008453 -0.03778415 0.001144468 0.05176806 -0.03946423 0.001144468 0.05165117 -0.04114592 0.001144468 0.05037844 -0.04256051 0.001144468 0.0486949 -0.04264718 0.001144468 0.04778397 -0.04036307 0.001144886 0.04843735 -0.03896105 0.001145064 0.04994547 -0.03881728 0.001145184 0.05065739 -0.03948366 0.001136422 0.05075782 -0.04070836 0.001096606 0.05020666 -0.0414713 0.001128494 0.04867208 -0.0416311 0.001144945 0.07290756 -0.0465433 2.43242e-4 0.04796588 -0.039595 -0.007555305 0.04809731 -0.04108887 -0.007555365 0.04946112 -0.04172194 -0.007555544 0.05079686 -0.03993529 -0.00833553 0.04918563 -0.03873467 -0.007552802 0.06675952 -0.03275471 -0.007555305 0.06689095 -0.03424853 -0.007555365 0.06825476 -0.03488165 -0.007555544 0.0695905 -0.03309494 -0.00833553 0.06797927 -0.03189438 -0.007552802 0.1136584 -0.156854 0.007020413 0.1118685 -0.1520526 0.007017433 0.09646505 -0.1775038 0.006162703 0.09892511 -0.1781515 0.007041513 0.1007338 -0.1830055 0.007017433 0.09041118 -0.158716 0.006727814 0.09203523 -0.1592226 0.007020413 0.09382516 -0.164024 0.007017433 0.09984111 -0.1188912 0.007020175 0.09804785 -0.1140806 0.007017612 0.09523886 -0.1005661 0.006267488 0.09289729 -0.09981793 0.007023572 0.09114229 -0.09510791 0.007017433 0.08598858 -0.08083635 0.007023572 0.08420681 -0.07605969 0.007082879 0.08000773 -0.1260609 0.007017433 0.06648015 -0.09147018 0.006380856 0.06738853 -0.09159672 0.007234573 0.06997561 -0.09849882 0.007020592 0.06437838 -0.08323073 0.007089376 0.06609147 -0.08782738 0.007020592 0.07128983 -0.1022241 0.007044255 0.07311999 -0.1071338 0.007049143 0.06306689 -0.0795173 0.007020592 0.0629971 -0.08017778 0.007050096 0.06212234 -0.0804553 0.00619173 0.05834561 -0.07938528 0.004400849 0.07338076 -0.1104898 0.006285071 0.08527773 -0.1405411 0.007020592 0.08691829 -0.1450551 0.007018327 0.09901666 -0.1088878 0.005474746 0.09713375 -0.1032919 0.005331516 0.09255975 -0.08923929 0.005033552 0.09105467 -0.0845651 0.004412233 0.08535689 -0.06593054 0.003797829 0.08637344 -0.06918621 0.004342138 0.08397686 -0.07271009 0.006355285 0.06060963 -0.05863356 0.007218539 0.07085227 -0.05476742 0.007020592 0.07395118 -0.05544716 0.007019996 0.1009191 -0.1863505 0.00736463 0.09277993 -0.1693319 0.005394816 0.0945847 -0.1747708 0.005251407 0.0941075 -0.1674345 0.006283879 0.08811438 -0.1485403 0.00723499 0.08725917 -0.1484147 0.00635761 0.09070175 -0.1554434 0.007020592 0.09063196 -0.1561039 0.007050096 0.08812469 -0.1559171 0.005612909 0.1049566 -0.1330623 0.007017612 0.1106679 -0.1485474 0.00723493 0.1080805 -0.1416443 0.007020592 0.1081367 -0.1409752 0.007272541 0.1148405 -0.1601846 0.007006108 0.118774 -0.1710255 0.007018208 0.1245061 -0.1754826 0.005194246 0.1173604 -0.1674628 0.007391989 0.1067573 -0.1378929 0.007021427 0.1021485 -0.186569 0.007385492 0.1002263 -0.1840226 0.007644176 0.09791767 -0.1853452 0.005118966 0.09915864 -0.1854619 0.006323516 0.09776288 -0.1745266 0.007384955 0.09523594 -0.1675843 0.007385194 0.0926541 -0.1659851 0.006822407 0.09143322 -0.1655651 0.005567312 0.08614385 -0.149991 0.005120635 0.1010194 -0.122561 0.007384955 0.1034715 -0.1292996 0.007384419 0.09411072 -0.1035796 0.007384955 0.09481161 -0.1026699 0.006269812 0.09663754 -0.1105218 0.007385253 0.09603768 -0.09999448 0.005247652 0.09380626 -0.09290373 0.005169808 0.08725202 -0.08473694 0.007384419 0.08975577 -0.09130018 0.007043123 0.08829891 -0.08376169 0.00619173 0.09045743 -0.08076405 0.004922151 0.0900315 -0.08131003 0.00424993 0.0877102 -0.07338082 0.00455445 0.08430832 -0.1461966 0.005836367 0.08394539 -0.1365635 0.007384955 0.08141851 -0.1296212 0.007385194 0.07703667 -0.117582 0.007384955 0.07634162 -0.1184861 0.006257116 0.07450973 -0.1106396 0.007385194 0.06951773 -0.09956574 0.006807863 0.08029323 -0.06561654 0.007384955 0.08282017 -0.07255876 0.007385253 0.05950701 -0.07241255 0.006730675 0.06066483 -0.07291775 0.007020592 0.1216265 -0.2219985 -0.01350528 0.1233848 -0.2233462 -0.01350528 0.1265425 -0.2234302 -0.01350528 0.1290018 -0.221439 -0.01350528 0.1295736 -0.2191059 -0.01350528 0.04222112 1.21383e-4 0.007731914 0.04249459 1.70517e-4 0.006144821 0.04224377 0.002541303 0.007731914 0.03685981 1.85808e-4 0.006144404 0.03685981 1.38043e-4 0.007731914 0.03604292 0.001573503 0.006144404 0.03604292 0.001573503 0.007731914 0.03604292 -0.002329111 0.006144404 0.03604292 -0.002329111 0.007731914 0.03685981 -9.18454e-4 0.006144404 0.03685981 -9.44941e-4 0.007731914 0.04411166 -9.04237e-4 0.006144464 0.04421776 -9.02409e-4 0.007731854 0.03587436 0.005780935 0.007731914 0.03650236 0.003898978 0.006144523 0.03695774 0.008196711 0.006144642 0.03699791 0.008369386 0.007731258 0.04299658 0.003280937 0.006144404 0.03785282 0.003266096 0.007732152 0.04406654 0.007420599 0.007731914 0.04375076 0.007796704 0.006144464 0.0492146 -0.003813683 0.006144404 0.0492146 -0.002692162 0.006144404 0.0492146 -0.003813683 0.007731914 0.0492146 -0.002692162 0.007731914 0.05721449 -0.001116812 0.006144404 0.05721449 -0.001116812 0.007731914 0.05721449 1.92695e-4 0.006144404 0.05721449 1.92695e-4 0.007731914 0.04936844 0.002837717 0.006144404 0.04936844 0.002837717 0.007731914 0.05721449 0.005482733 0.006144404 0.05721449 0.005482733 0.007731914 0.05721449 0.006792247 0.006144404 0.05721449 0.006792247 0.007731914 0.0492146 0.009489119 0.006144404 0.0492146 0.009489119 0.007731914 0.05145114 0.001087307 0.006144404 0.0492146 0.001813411 0.006144404 0.05145114 0.001087307 0.007731914 0.0492146 0.001813411 0.007731914 0.05145114 -0.001966059 0.006144404 0.05145114 -0.001966059 0.007731914 0.0492146 0.003907382 0.006144404 0.0492146 0.003907382 0.007731914 0.0492146 0.008412957 0.006144404 0.0492146 0.008412957 0.007731914 0.05145114 0.007686913 0.006144404 0.05145114 0.007686913 0.007731914 0.05145114 0.004633426 0.006144404 0.05145114 0.004633426 0.007731914 0.04337215 0.01092964 0.006146132 0.04373168 0.01404011 0.006144404 0.04259067 0.01398181 0.007731914 0.0421403 0.01008802 0.007732927 0.03717744 0.01420867 0.006144404 0.03717744 0.01420867 0.007731914 0.03604292 0.01420867 0.006144404 0.03604292 0.01420867 0.007731914 0.03604292 0.009275197 0.006144404 0.03604292 0.009275197 0.007731914 0.03697001 0.01318854 0.007328987 0.04043054 0.009920597 0.007731676 0.04080796 0.009518861 0.006144523 0.04440069 0.01019257 0.007731735 0.04425263 0.01121789 0.006144464 0.04373168 0.01404011 0.007731914 0.03997981 -0.007404625 0.006144523 0.03969901 -0.007937431 0.007731974 0.03685581 -0.006880283 0.006144583 0.0369898 -0.004014611 0.007729887 0.03747117 -0.004187285 0.006144464 0.0359376 -0.005414962 0.007731914 0.03665882 -0.007943332 0.007731914 0.03665882 -0.007943332 0.006144404 0.03608506 -0.0071038 0.007731914 0.04309874 -0.008700609 0.007731616 0.04310286 -0.008604586 0.006144404 0.03751456 -0.00846517 0.007731914 0.04135203 -0.005631148 0.007732331 0.04060423 -0.008105993 0.006144344 0.04307687 -0.005249798 0.006144583 0.04310286 -0.0052464 0.007731914 0.04404282 -0.008604586 0.006144404 0.04404282 -0.008604586 0.007731914 0.04404282 -0.004215657 0.006144404 0.04404282 -0.004215657 0.007731914 0.03991973 -0.004215657 0.007731914 0.06764638 -0.03507012 0.007732927 0.05068707 -0.03924924 0.007695198 0.05097287 -0.04081863 0.007726848 0.06664717 -0.03423774 0.007731914 0.06643754 -0.03315716 0.007724821 0.0673694 -0.03208875 0.007631897 0.04932576 -0.03872811 0.007631897 0.06811934 -0.03188776 0.007631897 0.09544879 -0.01996755 0.007731914 0.09653621 -0.01132702 0.007731914 0.097081 -0.002635359 0.007731914 0.097081 0.006073236 0.007731914 0.06896936 -0.03191554 0.007731914 0.09382295 -0.02852314 0.007731914 0.08253884 -0.0341981 0.007731914 0.08605808 -0.0369603 0.007731914 0.09166514 -0.0369603 0.007731914 0.06959158 -0.03253775 0.007731914 0.08007419 -0.0352267 0.007731914 0.06979376 -0.03389286 0.007731854 0.07904553 -0.03769135 0.007731914 0.06896936 -0.03486001 0.007731914 0.07294315 -0.04487192 0.007731854 0.07215756 -0.04524427 0.007631897 0.08170396 -0.04139137 0.007728159 0.07407253 -0.04555356 0.007629156 0.08180767 -0.04702836 0.007731914 0.07438355 -0.04695552 0.007621228 0.07375752 -0.04801553 0.007731914 0.07290756 -0.04824328 0.007731914 0.0518375 -0.05793702 0.007730782 0.05519711 -0.05446791 0.007629096 0.05370402 -0.05509769 0.007732927 0.0490334 -0.0553385 0.007730782 0.05254149 -0.05401819 0.007698595 0.05304718 -0.05225712 0.007634162 0.04197323 -0.05314165 0.00773108 0.04883086 -0.04190641 0.007735729 0.029729 -0.05047893 0.007731914 0.05411398 -0.05188363 0.007631897 0.05017572 -0.0417003 0.007731914 0.07120758 -0.0465433 0.007731914 0.07143533 -0.04569333 0.007731914 0.05496394 -0.05191141 0.007731914 0.07166492 -0.04778283 0.007739782 0.05558621 -0.05253362 0.007731914 0.05561393 -0.05338358 0.007631897 0.04785352 -0.04107809 0.007731914 0.0478124 -0.04022806 0.007681906 0.02480959 -0.04975908 0.007731914 0.04785352 -0.0393781 0.007731914 0.01479864 -0.04889172 0.007731914 0.04857575 -0.03892904 0.007631897 0.06726938 0.03535342 0.007731914 0.06811934 0.03512567 0.007731914 0.03091996 0.03357261 0.007731914 0.03230786 0.03496044 0.007731914 0.06664717 0.03597563 0.007731914 0.0493257 0.04196602 0.007731914 0.04803955 0.0424934 0.007731854 0.03196012 0.03686779 0.007731914 0.06641942 0.03682565 0.007731914 0.0504983 0.04237979 0.007731854 0.06693989 0.03810989 0.007731854 0.05102568 0.04366594 0.007731914 0.06811934 0.03852564 0.007731914 0.0720576 0.04850894 0.007731914 0.07361555 0.04845392 0.00763607 0.05079793 0.04451596 0.007731914 0.07143533 0.04913121 0.007731914 0.05017572 0.04513818 0.007731914 0.07120758 0.04998117 0.007731914 0.05411392 0.05512154 0.007731914 0.05516177 0.05570083 0.007628023 0.04890072 0.04525208 0.007731914 0.05245196 0.05604416 0.007731914 0.03691703 0.05536317 0.007731914 0.04785346 0.04451596 0.007731914 0.02348423 0.05310457 0.007731914 0.02902412 0.03685629 0.007731914 0.03041201 0.03750044 0.007731914 0.01214832 0.05225253 0.007731914 0.02838003 0.03546845 0.007731914 -0.004867553 0.05275797 0.007731914 -0.03116655 0.04224145 0.007731914 -0.03188878 0.04179239 0.007631897 0.02902412 0.03408056 0.007731914 -0.04866003 0.03234159 0.007631897 -0.03263878 0.04139143 0.007731914 -0.04845517 0.03343355 0.00763148 -0.03391474 0.04189592 0.007728219 -0.04958409 0.03449106 0.007631897 -0.05610901 0.04374355 0.007731914 -0.057657 0.04373061 0.007723212 -0.05089819 0.03447055 0.00768429 -0.0641095 0.04542416 0.007731914 -0.05165904 0.03309154 0.007731914 -0.0994302 0.02738952 0.007731914 -0.05143129 0.03224158 0.007731914 -0.09908437 0.02519994 0.007731914 -0.05080908 0.03161936 0.007731914 -0.09929829 0.01771873 0.007731914 -0.09929829 0.01371872 0.007731914 -0.04995906 0.03159159 0.007631897 -0.04995906 -0.02795374 0.007731914 -0.09929829 -0.0102809 0.007731914 -0.1097981 -0.0102809 0.007731914 -0.1097981 0.01371872 0.007731914 -0.1106736 -0.02193075 0.007731914 -0.1097981 -0.01428085 0.007731914 -0.1045489 -0.01936459 0.007731914 -0.09929829 -0.01428085 0.007731914 -0.1004371 -0.01927071 0.007731914 -0.09908437 -0.02176207 0.007731914 -0.05070906 -0.0283547 0.007631897 0.07883721 0.04003912 0.007749259 0.08167052 0.04473453 0.007733166 0.07437634 0.04955148 0.007632791 0.08180767 0.05046623 0.007731914 0.0740391 0.05102914 0.007632315 0.06982129 0.03720498 0.007731795 0.06896936 0.03829789 0.007731914 0.06959158 0.03597563 0.007731914 0.08253884 0.03763598 0.007731914 0.06896936 0.03535342 0.007731914 0.09382295 0.03196102 0.007731914 0.09544879 0.02340543 0.007731914 0.08605808 0.04039818 0.007731914 0.09166514 0.04039818 0.007731914 0.09653621 0.0147649 0.007731914 -0.03348875 -0.04112577 0.007731914 -0.03963869 -0.05007779 0.007731914 -0.03231161 -0.04112172 0.00763309 -0.05589729 -0.04284894 0.007631003 -0.03411102 -0.04050356 0.007731914 -0.05525898 -0.0417779 0.007731914 -0.03433877 -0.03965359 0.007731914 -0.05548673 -0.04092794 0.007731914 -0.03394937 -0.03889685 0.007681906 -0.05620896 -0.04047888 0.007631897 -0.04960691 -0.0311172 0.007632493 -0.05717301 -0.04026597 0.007626593 -0.05115753 -0.03094613 0.00771892 -0.0641095 -0.04198634 0.007731914 -0.05165904 -0.02965372 0.007731914 -0.0994302 -0.02395164 0.007731914 -0.1022742 -0.0290808 0.007731914 -0.1022478 -0.02627116 0.007731914 -0.03303688 -0.03817331 0.007636845 -0.0483154 -0.03027021 0.007739484 -0.04848688 -0.0288037 0.007731914 -0.03188878 -0.03835451 0.007631897 -0.04920911 -0.0283547 0.007631897 -0.0491091 0.03161936 0.007731914 -0.03114646 -0.03935587 0.00763154 0.00435394 -0.04878729 0.007731914 -0.006483078 -0.04947018 0.007731914 -0.01213628 -0.05011397 0.007731914 -0.03116655 -0.04050356 0.007731914 -0.01796919 -0.05096131 0.007732033 -0.0287835 -0.05311924 0.007721722 -0.03853958 -0.05073338 0.007635235 -0.03793871 -0.05177778 0.007731914 -0.03506779 -0.05464452 0.007731914 -0.03888165 -0.05329835 0.007628977 -0.03816992 -0.05666059 0.007731914 -0.04085135 -0.05305594 0.007731974 -0.06169325 -0.04307943 0.007731914 -0.05695897 -0.04347789 0.007731914 -0.04133868 -0.05177778 0.007731914 -0.04060375 -0.05059045 0.007632255 -0.05858319 -0.04261988 0.007729172 -0.0584312 -0.04092794 0.007731914 -0.04048866 0.05374342 0.007731914 -0.05548679 0.04606574 0.007731914 -0.03963869 0.05371564 0.007631897 -0.05610901 0.04668796 0.007731914 -0.04120689 0.05455595 0.007713913 -0.05731862 0.04669225 0.007635831 -0.04059076 0.05660122 0.007693946 -0.06198817 0.0463469 0.007731676 -0.03816998 0.06009846 0.007731914 -0.03824281 0.05647015 0.007676005 -0.03183579 0.05726599 0.007731914 -0.03506779 0.0580824 0.007731914 -0.03842931 0.05393242 0.007732152 -0.02550357 0.05584794 0.007731914 -0.03263878 0.0447914 0.007731914 -0.03150713 0.04411458 0.007630765 -0.010535 0.05335581 0.007731914 -0.03113883 0.04309141 0.007631897 -0.03348881 0.04456365 0.007731914 -0.0343132 0.04359656 0.007731914 -0.05528461 0.04471063 0.007731914 -0.05876111 0.04515504 0.007732748 -0.05143129 -0.0288037 0.007731914 0.04762572 0.04366594 0.007731914 0.04873555 0.05863189 0.007731974 0.05344885 0.05828756 0.007633745 0.05486392 0.05812048 0.007631897 0.05183726 0.06137496 0.00773257 0.07290756 0.05148118 0.007631897 0.05558615 0.05767148 0.007731914 0.05561393 0.05682146 0.007631897 0.07191967 0.05115723 0.007649362 -0.1054875 0.02339184 0.007731914 -0.1097981 0.01771867 0.007731914 -0.1007878 0.0224772 0.007731914 -0.1106736 0.02536857 0.007731914 -0.1064907 0.02536863 0.007731914 -0.1064907 -0.02193075 0.007731914 -0.1022742 0.03251868 0.007731914 -0.1021877 0.02977287 0.007731914 -0.1122981 0.02784866 0.006144404 -0.1097981 -0.0102809 0.006144404 -0.112298 -0.02371913 0.006144404 -0.1097981 0.01371872 0.006144404 -0.1098076 0.01772117 0.006144464 -0.1026632 0.02461194 0.006144404 -0.1040218 0.02733862 0.006144404 -0.1119458 0.02956223 0.006145179 -0.1107512 0.03104633 0.006144225 -0.1095796 0.03163784 0.006144404 -0.1019243 0.02734082 0.006144404 -0.1011881 0.02629357 0.006144404 -0.05713784 0.04365277 0.006144404 -0.05110782 0.0344448 0.006144583 -0.05112022 0.03193044 0.006144404 -0.09929829 0.01771873 0.006144404 -0.09929829 0.01371872 0.006144404 -0.05878096 0.04578787 0.00614506 -0.05653399 0.04680186 0.006144404 -0.04122477 0.05564063 0.006144404 -0.04097682 0.05408656 0.006144464 -0.05537289 0.04479074 0.006144404 -0.03422492 0.04351645 0.006144404 -0.0322138 0.04467755 0.006144404 -0.03364306 0.04183572 0.006144404 -0.04953408 0.03467768 0.006144404 -0.03948831 0.05701404 0.006144344 -0.03823125 0.05488121 0.006144404 -0.02179229 0.05663621 0.006144404 -0.0310527 0.04351645 0.006144404 -0.01134568 0.05497515 0.006144404 -0.001464426 0.05400186 0.006144404 -0.03147768 0.04193031 0.006144404 0.004074931 0.05373853 0.006144404 0.02902412 0.03685629 0.006144404 0.009620368 0.05368411 0.006144404 0.02353388 0.05455666 0.006144404 0.03041201 0.03750044 0.006144404 0.04773962 0.04409098 0.006144404 0.03181135 0.03701657 0.006144404 0.04803055 0.04249525 0.006144404 0.03230786 0.03496044 0.006144404 0.02838003 0.03546845 0.006144404 0.02902412 0.03408056 0.006144404 0.03091996 0.03357261 0.006144404 0.03579127 0.05661785 0.006144404 0.04890072 0.04525208 0.006144404 0.05295282 0.05566036 0.006144404 0.05075627 0.04424649 0.006144404 0.07171738 0.05125898 0.006144464 0.05565959 0.05585944 0.006144404 0.07333254 0.05156725 0.006144404 0.05527502 0.05798262 0.006144404 0.05287355 0.05825346 0.006144523 0.08597773 0.05054479 0.006144404 0.07449626 0.04974693 0.006144464 0.08214038 0.04285842 0.006144344 0.07333254 0.04839509 0.006144404 0.08075582 0.04119211 0.006144583 0.06854438 0.03841173 0.006144404 0.07174646 0.04882007 0.006144404 0.06694865 0.03812086 0.006144404 0.04991108 0.04216837 0.006144404 0.06653326 0.03640067 0.006144404 0.06726938 0.03535342 0.006144404 0.08768039 0.04976671 0.006144106 0.08977711 0.04806721 0.006144404 0.09107631 0.04642814 0.006143033 0.08400255 0.04206031 0.006229996 0.09209114 0.04416596 0.006144404 0.08396732 0.04022634 0.006145179 0.09444022 0.03586959 0.006144404 0.0822283 0.03964501 0.006244719 0.06854438 0.03523957 0.006144404 0.06994313 0.03676837 0.006152272 0.09759312 0.01892346 0.006144404 0.09627652 0.02744489 0.006144404 0.09838503 0.01033741 0.006144404 0.09864938 0.001718878 0.006144404 0.09838503 -0.006899535 0.006144404 0.09759312 -0.01548558 0.006144404 0.0692805 -0.03222668 0.006144404 0.09627652 -0.02400702 0.006144404 0.09444022 -0.03243172 0.006144404 0.0820291 -0.03604799 0.006144404 0.08373278 -0.03642135 0.006144464 0.06978082 -0.03392404 0.006144404 0.08085387 -0.03733676 0.006144523 0.08138233 -0.0389989 0.006144404 0.06854438 -0.03497385 0.006144404 0.07406866 -0.0453822 0.006144404 0.08308607 -0.03937226 0.006144404 0.08597773 -0.04710692 0.006144404 0.07458001 -0.04701989 0.006144344 0.09209114 -0.04072809 0.006144404 0.08426123 -0.03808349 0.006144642 0.09049415 -0.04391968 0.006144106 0.08857685 -0.04578465 0.006143331 0.07333254 -0.04812937 0.006144404 0.05527508 -0.05454474 0.006144404 0.05266356 -0.05465209 0.006144642 0.05295288 -0.05222249 0.006144404 0.03752559 -0.05360579 0.006144404 0.04890078 -0.0418142 0.006144404 0.05411398 -0.05168366 0.006144404 0.05048686 -0.04138916 0.006144404 0.07174646 -0.0453822 0.006144404 0.05572628 -0.05253702 0.006144464 0.07161235 -0.04771405 0.006144404 0.02901732 -0.05187493 0.006144404 0.04773962 -0.0406531 0.006144404 0.02406752 -0.05117571 0.006144404 0.01904344 -0.0506705 0.006144404 0.04874521 -0.03879755 0.006144404 0.01393228 -0.05035871 0.006144404 0.06695824 -0.03222668 0.006144404 0.004740476 -0.05028909 0.006144404 -0.03178876 -0.03818136 0.006144404 -0.03105264 -0.04007858 0.006144404 -0.04953408 -0.02806758 0.006144404 -0.04848688 -0.0288037 0.006144404 -0.03302019 -0.03794831 0.006144464 -0.04831343 -0.0302506 0.006144464 -0.04953408 -0.0312398 0.006144404 -0.03422486 -0.03922855 0.006144404 -0.05598455 -0.04051667 0.006144404 -0.05145668 -0.03023904 0.006144404 -0.05780893 -0.04030567 0.006144404 -0.1011881 -0.02285569 0.006144404 -0.05112022 -0.02849256 0.006144404 -0.09929829 -0.01428085 0.006144404 -0.09929829 -0.0102809 0.006144404 -0.00343585 -0.05073875 0.006144404 -0.01625198 -0.05223429 0.006144404 -0.0322138 -0.04123967 0.006144404 -0.02221775 -0.05327963 0.006144404 -0.03847759 -0.05061668 0.006144404 -0.03379988 -0.04081469 0.006144404 -0.05537289 -0.04220288 0.006144404 -0.03838062 -0.05320805 0.006144464 -0.04106926 -0.05235832 0.006144404 -0.05653399 -0.04336398 0.006144404 -0.04085642 -0.05053728 0.006144404 -0.05885607 -0.04207384 0.006145179 -0.1095796 -0.02819997 0.006144404 -0.1033105 -0.02409219 0.006144404 -0.1108123 -0.02759689 0.006142854 -0.1120502 -0.02589464 0.006144464 -0.1043639 -0.02218896 0.006144404 -0.1098158 -0.01428234 0.006144464 -0.1023392 -0.0210523 0.006144404 -0.04953408 0.03150546 0.006144404 -0.04848688 0.03224158 0.006144404 -0.04825383 0.03347301 0.006144464 0.06644475 -0.03412836 0.006144464 0.05063492 -0.03904062 0.006144464 -0.1011209 -0.02165859 0.007128059 -0.1016195 -0.02373713 0.00713092 -0.1038201 -0.02392613 0.007128775 -0.1031211 -0.02072197 0.007131278 -0.1044275 -0.02187669 0.007130742 -0.1106736 -0.02193075 0.007131934 -0.1064907 -0.02193075 0.007131934 -0.1059948 -0.02050977 0.007131934 -0.1049802 -0.01939821 0.007131934 -0.1036102 -0.01877516 0.007131934 -0.1021056 -0.01874089 0.007131934 -0.1007087 -0.01930093 0.007131934 -0.09964448 -0.02036517 0.007131934 -0.09908437 -0.02176207 0.007131934 -0.09911864 -0.02326667 0.007131934 -0.09974175 -0.02463662 0.007131934 -0.1008533 -0.02565133 0.007131934 -0.1022742 -0.02614718 0.007131934 -0.1096653 -0.02657902 0.007135629 -0.1032742 -0.02874267 0.007131934 -0.1098704 -0.02646023 0.007731914 -0.1032574 -0.02833169 0.007731914 -0.1032742 -0.02614718 0.007131934 -0.1044376 -0.02579158 0.007131934 -0.106881 -0.02297878 0.007731914 -0.1054259 -0.02508234 0.007131934 -0.1061351 -0.02409404 0.007131934 -0.1064907 -0.02293074 0.007131934 -0.1106641 -0.02291679 0.007197022 -0.1022742 -0.0290808 0.007131934 -0.1107941 -0.02483886 0.007188498 -0.0641095 -0.04198634 0.007131934 -0.06459718 -0.04341089 0.007131934 -0.1101691 -0.02800041 0.007131874 -0.1120516 -0.02605259 0.007135331 -0.1122909 -0.02466064 0.007131934 -0.104483 0.02552157 0.007130742 -0.1033282 0.02421528 0.007131278 -0.101121 0.02664077 0.007128059 -0.1016195 0.02456218 0.00713092 -0.1035465 0.02752196 0.007128775 -0.1064907 0.02536863 0.007131934 -0.1106736 0.02536857 0.007131934 -0.1022742 0.02958506 0.007131934 -0.1008533 0.02908915 0.007131934 -0.09974175 0.0280745 0.007131934 -0.09911864 0.02670454 0.007131934 -0.09908437 0.02519994 0.007131934 -0.09964448 0.02380299 0.007131934 -0.1007087 0.02273881 0.007131934 -0.1021056 0.0221787 0.007131934 -0.1036102 0.02221298 0.007131934 -0.1049802 0.02283608 0.007131934 -0.1059948 0.02394765 0.007131934 -0.1032742 0.03218048 0.007131934 -0.1093395 0.03012853 0.007134377 -0.1032742 0.03218048 0.007731914 -0.1097349 0.02991789 0.007731914 -0.1032742 0.02958506 0.007131934 -0.1032932 0.0297324 0.007731914 -0.1064907 0.02636861 0.007131934 -0.1061351 0.02753192 0.007131934 -0.1067758 0.02642798 0.007731914 -0.1054259 0.02852022 0.007131934 -0.1044376 0.02922946 0.007131934 -0.1106076 0.02628463 0.007519841 -0.1022742 0.03251868 0.007131934 -0.1106604 0.02856427 0.007141113 -0.1122981 0.02784866 0.007131934 -0.1115812 0.03043168 0.007131576 -0.1095796 0.03163784 0.007131934 -0.06459718 0.04684877 0.007131934 0.08125507 0.03998768 0.007130742 0.08089846 0.04168903 0.007130622 0.08220094 0.04285597 0.007131397 0.0838623 0.04230439 0.007131397 0.0842114 0.04059624 0.007131457 0.08290964 0.03943973 0.007131636 0.08201235 -0.03936755 0.007131397 0.08084958 -0.03806668 0.007131099 0.08177298 -0.0360614 0.007129609 0.08420628 -0.03692555 0.007128834 0.08372032 -0.039011 0.00713104 0.08605808 -0.0369603 0.007131934 0.08551007 -0.03568565 0.007131934 0.08451861 -0.03471505 0.007131934 0.08323258 -0.0341944 0.007131934 0.08184516 -0.0342018 0.007131934 0.07958364 -0.03571718 0.007131934 0.07904177 -0.03838503 0.007131934 0.08180767 -0.04121065 0.007131934 0.08053302 -0.04066264 0.007131934 0.08056473 -0.03473615 0.007131934 0.07904922 -0.03699761 0.007131934 0.07956248 -0.03967112 0.007131934 -0.06297761 -0.04241663 0.007131814 -0.06169325 -0.04307943 0.007131934 -0.03816992 -0.05666059 0.007131934 -0.03505605 -0.05463677 0.007134377 -0.02242457 -0.05182546 0.007131934 -0.01501095 -0.05052804 0.007131934 -0.009267508 -0.04976701 0.007132112 0.002623438 -0.04881483 0.007131934 0.01814764 -0.04901105 0.007131934 0.029729 -0.05047893 0.007131934 0.03825807 -0.05219286 0.007132291 0.0443027 -0.05383956 0.007131993 0.04906189 -0.05536341 0.007131934 0.05182468 -0.05794119 0.007131934 0.08180767 -0.04702836 0.007131934 0.09166514 -0.0369603 0.007131934 0.09382295 -0.02852314 0.007131934 0.09544879 -0.01996755 0.007131934 0.09653621 -0.01132702 0.007131934 0.097081 -0.002635359 0.007131934 0.097081 0.006073236 0.007131934 0.09653621 0.0147649 0.007131934 0.09544879 0.02340543 0.007131934 0.09382295 0.03196102 0.007131934 0.09166514 0.04039818 0.007131934 0.08605808 0.04039818 0.007131934 0.08551007 0.03912353 0.007131934 0.08451861 0.03815293 0.007131934 0.08323258 0.03763228 0.007131934 0.08184516 0.03763967 0.007131934 0.08056473 0.03817403 0.007131934 0.07958364 0.03915506 0.007131934 0.07904922 0.04043549 0.007131934 0.07904177 0.04182291 0.007131934 0.07956248 0.04310899 0.007131934 0.08053302 0.04410052 0.007131934 0.08180767 0.04464852 0.007131934 0.08180767 0.05046623 0.007131934 0.05182582 0.06137853 0.007131934 0.04892253 0.0587331 0.007133722 0.04288619 0.05685538 0.007132053 0.03208273 0.05435812 0.007131934 0.02270418 0.05292665 0.007131934 0.01208788 0.05219578 0.007131934 0.003322184 0.05225652 0.007132112 -0.01164197 0.05342298 0.007131934 -0.02465671 0.05566591 0.007131934 -0.03496646 0.05802184 0.007131814 -0.03816998 0.06009846 0.007131934 -0.06169325 0.04651725 0.007131934 -0.06327152 0.04572111 0.007134139 -0.0641095 0.04542416 0.007131934 0.09209114 -0.04072809 0.007131934 0.09444022 -0.03243172 0.007131934 0.09627652 -0.02400702 0.007131934 0.09759312 -0.01548558 0.007131934 0.09838503 -0.006899535 0.007131934 0.09864938 0.001718878 0.007131934 0.09838503 0.01033741 0.007131934 0.09759312 0.01892346 0.007131934 0.09627652 0.02744489 0.007131934 0.09444022 0.03586959 0.007131934 0.09185028 0.04503786 0.007133603 0.08597773 -0.04710692 0.007131934 0.08758479 -0.04641592 0.007134675 0.09072571 -0.04364651 0.007134079 0.05147409 -0.05966722 0.007131934 0.04827696 -0.05668538 0.00713253 0.03790831 -0.05363065 0.007131934 0.03379195 -0.05271345 0.007132351 0.026537 -0.05149894 0.007131993 0.01943784 -0.05068451 0.007131278 0.01299464 -0.05029255 0.007131934 0.001075446 -0.0503692 0.007131934 -0.00805521 -0.05113571 0.00713706 -0.01555621 -0.05209767 0.007132112 -0.0268321 -0.05425846 0.007131934 -0.03446453 -0.0560438 0.007131934 -0.03804314 -0.05836737 0.007131934 -0.06244122 -0.0443862 0.007131934 -0.06343507 -0.04387247 0.007131934 -0.06344133 0.04730749 0.007131934 -0.06244122 0.04782408 0.007131934 -0.03834086 0.06168168 0.007131934 -0.03761297 0.06152784 0.007131934 -0.03445494 0.05947542 0.007132649 -0.02076357 0.05641168 0.007131934 -0.01280647 0.05516302 0.007131934 -5.75892e-4 0.05381399 0.007131934 0.01205313 0.05373138 0.007131993 0.01723521 0.05397516 0.007132291 0.03306889 0.05590343 0.007131934 0.04827684 0.06012314 0.007132649 0.05147111 0.06310415 0.007131934 0.08597773 0.05054479 0.007131934 0.08837753 0.04943084 0.007134675 0.08333283 0.04989862 0.007130742 0.0873475 0.04825145 0.007147133 0.09033894 0.0444802 0.007132887 0.09111744 0.04189813 0.007131934 0.08605802 0.04189813 0.007131934 0.0833075 0.04466259 0.007131874 0.09111744 -0.03846025 0.007131934 0.08972185 -0.04235899 0.007136642 0.08689111 -0.04507112 0.007145941 0.08330762 -0.04637604 0.007131934 0.08330756 -0.04122936 0.007131814 0.08605802 -0.03846025 0.007131934 0.08330768 0.04981642 0.007731914 0.08337682 0.04510629 0.007731914 0.08605802 0.04189813 0.007731914 0.0911448 0.0418989 0.007731914 0.08843845 0.04741823 0.007731914 0.09127485 -0.03847038 0.007731914 0.08605802 -0.03846025 0.007731914 0.08339095 -0.04154539 0.007731914 0.08330762 -0.04637604 0.007731914 0.08731299 -0.04482859 0.007731914 0.004409074 0.04695206 -0.02125585 0.006418704 0.04467576 -0.02124994 0.00876373 0.04975396 -0.02125513 0.01111543 0.0466668 -0.02125513 0.0112378 0.04018145 -0.0212531 0.005778193 0.04159921 -0.02130156 0.003544211 0.04035294 -0.02137547 0.01362764 0.0381577 -0.02125513 -0.006298243 0.03848183 -0.0212714 -0.008602917 0.03785324 -0.02125513 -0.008602857 -0.03441542 -0.02125513 -0.03418713 0.03158861 -0.02125513 -0.02412432 0.03785586 -0.02125513 -0.03410071 0.0342198 -0.02125513 -0.03161382 0.041579 -0.02125513 -0.03379988 0.04193025 -0.02125513 -0.03705531 0.03311604 -0.02125513 -0.04879796 0.03425264 -0.02125513 -0.05160349 0.03676086 -0.02125513 -0.05142909 0.03433907 -0.02125513 8.49601e-4 0.04159396 -0.02125489 -0.004645943 0.04096311 -0.02125513 4.09992e-4 0.04559016 -0.02125662 -0.002043843 0.0497415 -0.02125513 -0.004576504 0.04673802 -0.02125513 0.00420773 -0.03735613 -0.02137178 0.01120144 -0.03752529 -0.02125513 0.01232999 -0.03558701 -0.02125513 0.006200551 -0.03913956 -0.0212571 0.006329357 -0.04197788 -0.02129346 0.01113325 -0.04328852 -0.02126514 0.003733098 -0.0439397 -0.02133601 0.008571445 -0.04630738 -0.02125066 -0.002187788 -0.04631805 -0.02125006 8.96474e-4 -0.04268097 -0.02125084 -0.004559934 -0.04322892 -0.02125513 1.25785e-4 -0.04028427 -0.02125549 0.001313805 -0.03775942 -0.02125173 -0.004629373 -0.03745406 -0.02125513 -0.006440758 -0.03498315 -0.02126711 0.0136277 -0.03471988 -0.02125513 0.03238081 0.03127753 -0.02125513 0.01515835 0.03785324 -0.02125513 0.0803979 0.004642248 -0.02125513 0.0824514 0.004863917 -0.02129095 0.08691662 0.009384453 -0.02125513 0.06889206 0.004228889 -0.02125567 0.08597081 0.01800096 -0.02125513 0.06669962 0.004918873 -0.02125513 0.0692805 0.03566455 -0.02125513 0.08422344 0.02585369 -0.02125543 0.08276116 0.03507769 -0.02125513 0.08464103 0.003219664 -0.02125656 0.0872029 0.001718938 -0.02125513 0.085195 -2.50266e-4 -0.02133572 0.08700788 -0.004135966 -0.02125501 0.08293682 -0.001274824 -0.02124553 0.08132517 -0.001665353 -0.02138215 0.08666253 -0.009297847 -0.02125573 0.06722825 -0.00164473 -0.02138215 0.08609461 -0.01390731 -0.02125513 0.07957929 -7.77799e-4 -0.02125293 0.06839168 -9.62097e-4 -0.02125328 0.06960076 1.60209e-5 -0.02136915 0.07886636 -1.6976e-4 -0.02138215 0.06984478 0.002235472 -0.02123236 0.0785523 0.002644896 -0.02123945 0.06604593 -0.001622676 -0.02138215 0.08538889 -0.01796442 -0.02125513 0.06726938 -0.03191554 -0.02125513 0.08432018 -0.0221073 -0.02125513 0.06481879 -8.69886e-4 -0.02125513 0.0340808 -0.02800714 -0.02125513 0.03323084 -0.0277794 -0.02125513 0.06388622 -1.65555e-4 -0.02138197 0.06351721 0.001384437 -0.02125513 0.06438505 0.003564715 -0.02125513 0.03365576 0.03116369 -0.02125513 0.06539809 0.004642188 -0.02125513 0.06695824 0.03566455 -0.02125513 0.03481686 0.03232479 -0.02125513 0.04214441 0.03824877 -0.02125513 0.04102098 0.03785324 -0.02125513 0.03440153 0.03404498 -0.02125513 0.01515841 -0.03441542 -0.02125513 0.0314086 -0.02961081 -0.02125513 0.03388011 -0.03129482 -0.02125513 0.04102098 -0.03441542 -0.02125513 0.03481692 -0.02905434 -0.02125513 -0.03660398 -0.03048366 -0.02125513 -0.03379982 -0.0384925 -0.02125513 -0.0338782 -0.03072696 -0.02125513 -0.0487979 -0.03081488 -0.02125513 -0.04844665 -0.02862882 -0.02125513 -0.03664338 -0.02830862 -0.02125513 -0.049959 -0.0279538 -0.02125513 -0.03534823 -0.0277794 -0.02125513 -0.03534829 0.03104978 -0.02125513 -0.04995906 0.03139156 -0.02125513 -0.03651899 0.03145456 -0.02125513 -0.04831522 0.03229421 -0.02125513 -0.03418713 -0.02831828 -0.02125513 -0.02405422 -0.03441745 -0.02125513 -0.03184145 -0.03800982 -0.02125513 -0.0314809 -0.04130983 -0.02125513 -0.02962976 -0.04279655 -0.02125513 0.03140854 0.03261834 -0.02125513 0.0328058 0.03433585 -0.02125513 -0.03422486 -0.04007858 -0.02125513 -0.05038404 -0.03123986 -0.02125513 0.06660705 -0.03441274 -0.02125513 0.06958943 -0.03463536 -0.02125513 0.04990631 -0.03879755 -0.02125513 0.0509119 -0.0406531 -0.02125513 0.04898041 -0.04212498 -0.02125513 0.04768198 -0.03943085 -0.02125513 0.04290038 -0.03573137 -0.02125513 0.06929016 -0.03209263 -0.02125513 0.08273535 -0.03154039 -0.02125513 0.07852852 -0.03339451 -0.02125513 0.07680851 -0.03599047 -0.02125513 -0.05905795 0.031201 -0.02125513 -0.05905777 -0.02901887 -0.02125513 -0.05185592 -0.02930837 -0.02125513 -0.05112981 0.03179633 -0.02125513 -0.05860519 0.03260529 -0.02125513 -0.03410881 0.04433894 -0.02125513 -0.03112643 0.04411631 -0.02125513 -0.02705037 0.04275679 -0.02125513 0.04781335 0.04264104 -0.02125513 0.04290032 0.03916919 -0.02125513 0.05048686 0.04250484 -0.02125513 0.04867643 0.04548138 -0.02125513 0.05091184 0.04409092 -0.02125513 0.06653326 0.03725063 -0.02125513 0.06798791 0.03864789 -0.02125513 0.06978082 0.03736191 -0.02125513 0.07666295 0.03949439 -0.02125555 0.07877284 0.03649389 -0.02125513 0.07677268 -0.03600943 -0.02284264 0.07832229 -0.03359669 -0.02284264 0.08273833 -0.03145503 -0.02284264 0.07676321 0.03941935 -0.02284264 0.07846957 0.0368734 -0.02284264 0.08275538 0.03497254 -0.02284264 0.07067978 -0.03671574 -0.02284252 0.04931807 -0.04448735 -0.02284264 0.0708248 0.04025644 -0.02284264 0.06821036 0.04104918 -0.02284264 0.04929226 0.04793459 -0.02284264 0.0832926 -0.02667933 -0.02284264 0.08418768 -0.02252483 -0.02284264 0.08609461 -0.01390731 -0.02284264 0.08691668 -0.005946576 -0.02284264 0.0872029 0.001718938 -0.02284264 0.0832926 0.03011721 -0.02284264 0.08418768 0.02596271 -0.02284264 0.08630526 0.01591092 -0.02284264 0.08678346 0.01108402 -0.02284264 0.08588391 0.01877951 -0.02284264 0.005361199 0.04629051 -0.02284312 0.002571046 0.04700666 -0.02284216 0.006560087 0.04387474 -0.0228393 0.005845129 0.04173004 -0.02283978 0.003407776 0.04047214 -0.02284258 3.95036e-4 0.04199987 -0.02284187 2.20808e-4 0.04487848 -0.02284169 0.005372941 -0.0378881 -0.02284026 0.003288865 -0.03712594 -0.02284222 0.006551921 -0.04012638 -0.02284169 0.005192279 -0.04192394 -0.02284306 0.004661202 -0.04335254 -0.02283924 0.001869261 -0.04339289 -0.02284151 -1.79192e-4 -0.04036772 -0.02283966 0.001277148 -0.03779339 -0.02284222 0.01515835 0.03785324 -0.02284264 0.01362764 0.0381577 -0.02284264 0.01127249 0.04030197 -0.02284264 0.011132 0.04673808 -0.02284264 -0.004629373 0.04089182 -0.02284264 -0.006468832 0.03839313 -0.02284264 -0.008602917 0.03785324 -0.02284264 -0.0240767 0.0378549 -0.02284264 0.01118487 -0.037454 -0.02284264 0.01232999 -0.03558701 -0.02284264 0.0136277 -0.03471988 -0.02284264 0.01515841 -0.03441542 -0.02284264 0.04102098 -0.03441542 -0.02284264 0.00876379 -0.04631614 -0.02284264 0.01111549 -0.04322898 -0.02284264 -0.002043783 -0.04630368 -0.02284264 -0.004576504 -0.04330021 -0.02284264 0.06979167 -0.03287714 -0.02284258 0.06896936 -0.03191554 -0.02284264 0.06939768 -0.0345807 -0.02284306 0.06772541 -0.03509134 -0.02284228 0.06644719 -0.03389835 -0.02284264 0.05051887 -0.0389499 -0.02284264 0.06664717 -0.03253775 -0.02284264 0.04932576 -0.03852814 -0.02284264 0.04214441 -0.03481096 -0.02284264 0.06726938 -0.03191554 -0.02284264 0.03481692 -0.02905434 -0.02284264 0.03357619 -0.03137624 -0.02284264 0.0314086 -0.02934789 -0.02284264 0.05102926 -0.04062211 -0.02284264 0.04983615 -0.04190045 -0.02284204 0.04570972 -0.04340451 -0.02284282 0.04813283 -0.04150635 -0.0228433 0.04762578 -0.04022806 -0.02284264 0.04290038 -0.03573137 -0.02284264 0.04804748 -0.03903514 -0.0228424 0.03238081 -0.02800714 -0.02284264 0.03238081 0.03127753 -0.02284264 -0.008602857 -0.03441542 -0.02284264 -0.006222844 -0.03511971 -0.02284264 -0.004645884 -0.03752529 -0.02284264 -0.02412432 -0.0344181 -0.02284264 -0.03418713 -0.02831828 -0.02284264 -0.03410071 -0.03094941 -0.02284264 -0.03224486 -0.03795009 -0.02284264 -0.03391706 -0.03846073 -0.02284264 -0.03705525 -0.02984565 -0.02284264 -0.0486809 -0.03084695 -0.02284264 -0.03433871 -0.03965359 -0.02284264 -0.05035299 -0.03135722 -0.02284264 -0.03383165 -0.04093194 -0.02284264 -0.03212815 -0.04132586 -0.02284312 -0.03335696 -0.04385739 -0.02284264 -0.02916902 -0.04259657 -0.02284288 -0.03116649 -0.04050362 -0.02284264 -0.03096652 -0.03914302 -0.0228433 -0.05905783 -0.0290184 -0.02284264 -0.05163133 -0.03016436 -0.02284252 -0.05123591 -0.02845966 -0.0228455 -0.049959 -0.0279538 -0.02284264 -0.05905795 0.031201 -0.02284264 -0.04995906 0.03139156 -0.02284264 -0.03534829 0.03104978 -0.02284264 -0.03664344 0.03157901 -0.02284264 -0.03534823 -0.0277794 -0.02284264 -0.03418713 0.03158861 -0.02284264 -0.05867213 0.0325669 -0.02284264 -0.05115336 0.0318163 -0.02284282 -0.0516358 0.03352266 -0.02284276 -0.05160349 0.03676086 -0.02284264 -0.05048328 0.03477984 -0.02286714 -0.04874175 0.03432166 -0.02284264 -0.03383165 0.04181307 -0.02284264 -0.0338782 0.03399729 -0.02284264 -0.03212815 0.04141914 -0.02284264 -0.03338938 0.04727619 -0.02284258 -0.03434228 0.04348528 -0.02284264 -0.03314936 0.04476362 -0.02284312 -0.0293383 0.0461421 -0.0228427 -0.03144592 0.04436969 -0.02284294 -0.03093528 0.04269748 -0.0228433 0.008599281 0.0497415 -0.02284264 -0.004559993 0.0466668 -0.02284264 -0.002208292 0.04975396 -0.02284264 0.03140854 0.0328812 -0.02284264 0.03388011 0.03456521 -0.02284264 0.04102098 0.03785324 -0.02284264 0.03481686 0.03232479 -0.02284264 0.06726938 0.03535342 -0.02284264 0.03365576 0.03116369 -0.02284264 0.06539809 0.004642188 -0.02284264 0.06432163 0.003860116 -0.02284264 0.06365633 0.002707719 -0.02284264 0.06351721 0.001384437 -0.02284264 0.03365582 -0.02789324 -0.02284264 0.06437361 -3.75466e-4 -0.02284264 0.06669962 -0.00141108 -0.02284264 0.06664717 0.03597563 -0.02284264 0.04290032 0.03916919 -0.02284264 0.04893183 0.04196244 -0.02284264 0.04765349 0.04315537 -0.0228427 0.05060404 0.04247307 -0.02284264 0.06641584 0.03721958 -0.02284264 0.06726938 0.03829789 -0.02284264 0.06851327 0.03852915 -0.02284312 0.04568272 0.04678893 -0.02284246 0.04804742 0.04485881 -0.02284336 0.04971963 0.04536944 -0.02284324 0.05099797 0.04417657 -0.02284264 0.06979161 0.03733628 -0.0228427 0.06939768 0.03563272 -0.02284264 0.06811934 0.03512567 -0.02284264 0.06735038 0.00478053 -0.02284264 0.08301013 0.004803776 -0.02284234 0.07993692 0.004566013 -0.02284258 0.06962668 0.003252029 -0.02284216 0.07836335 0.001245975 -0.02284067 0.06928455 -3.09429e-4 -0.02284169 0.06991052 0.001191496 -0.02284187 0.07940816 -6.2163e-4 -0.02283984 0.08103412 -0.00141108 -0.02284264 0.0681194 -0.03168779 -0.02284264 0.08496934 0.001975774 -0.0228343 0.08402675 -7.07483e-4 -0.02284187 -0.03651899 -0.02818423 -0.02284264 -0.04910904 -0.02818155 -0.02284264 -0.04828584 -0.02914565 -0.02284181 -0.03660398 0.03375399 -0.02284264 -0.04830473 0.03259974 -0.02284246 -0.04910904 0.03161931 -0.02284264 0.04608231 -0.01980459 0.00414443 0.06179314 -0.01980459 0.00414443 0.04608231 -0.01980459 -0.02125513 0.06179314 -0.01980459 -0.02125513 0.04608231 -0.03582686 0.00414443 0.04608231 -0.03582686 -0.02125513 0.06586098 -0.02862799 0.00414443 0.06586098 -0.02862799 -0.02125513 0.0837208 -0.02862799 0.00414443 0.0837208 -0.02862799 -0.02125513 0.0837208 0.03206586 -0.02125513 0.0837208 0.03206586 0.00414443 0.08500581 0.0282725 -0.02125513 0.08500581 0.0282725 0.00414443 0.08611947 0.02447915 0.00414443 0.08649265 0.02305787 -0.008555352 0.08706188 0.02068579 0.00414443 0.08743929 0.01893347 -0.008555352 0.08783286 0.01689237 0.00414443 0.08814746 0.01503783 -0.008555352 0.08843255 0.01309901 0.00414443 0.08866691 0.01121288 -0.008555352 0.08886086 0.009305655 0.00414443 0.08901071 0.007410705 -0.008555352 0.08911788 0.005512297 0.00414443 0.08918213 0.003616333 -0.008555352 0.08920353 0.001718878 0.00414443 0.08918213 -1.77185e-4 -0.008555352 0.08911788 -0.00207442 0.00414443 0.08901083 -0.003970324 -0.008555352 0.08886086 -0.005867779 0.00414443 0.08866828 -0.00776273 -0.008555352 0.08843255 -0.009661138 0.00414443 0.08815491 -0.01155287 -0.008555352 0.08783286 -0.01345455 0.00414443 0.08747196 -0.01533567 -0.008555352 0.08706188 -0.01724791 0.00414443 0.08662462 -0.0190941 -0.008555352 0.08611947 -0.02104127 0.00414443 0.08563268 -0.02277183 -0.008555352 0.08500581 -0.02483463 0.00414443 0.0845701 -0.02617871 -0.008555352 0.08500581 -0.02483463 -0.02125513 0.08611947 0.02447915 -0.02125513 0.08706188 0.02068579 -0.02125513 0.08783286 0.01689237 -0.02125513 0.08843255 0.01309901 -0.02125513 0.08886086 0.009305655 -0.02125513 0.08911788 0.005512297 -0.02125513 0.08920353 0.001718878 -0.02125513 0.08911788 -0.00207442 -0.02125513 0.08886086 -0.005867779 -0.02125513 0.08843255 -0.009661138 -0.02125513 0.08783286 -0.01345455 -0.02125513 0.08706188 -0.01724791 -0.02125513 0.08611947 -0.02104127 -0.02125513 0.06586098 0.03206586 0.00414443 0.06586098 0.03206586 -0.02125513 0.04608231 0.03926473 0.00414443 0.04608231 0.03926473 -0.02125513 0.04608231 0.02324247 0.00414443 0.04608231 0.02324247 -0.02125513 0.06179314 0.02324247 0.00414443 0.06179314 0.02324247 -0.02125513 0.01094949 -0.04318332 -0.02804225 0.01087665 -0.04324686 -0.03024172 0.01092904 -0.03740322 -0.02804255 0.01078283 -0.03747695 -0.03359508 0.02290594 -0.0431866 -0.02804231 0.02299344 -0.04262036 -0.0306521 0.02146553 -0.04329383 -0.0319885 0.01243734 -0.04329222 -0.03197252 0.0241273 -0.04371821 -0.02802473 0.009727537 -0.04369091 -0.02804249 0.02410525 -0.035492 -0.02804231 0.02292603 -0.03740328 -0.02804255 0.02220934 -0.03669059 -0.02804255 0.01054745 -0.03549051 -0.02804249 0.01164609 -0.03669041 -0.02804255 0.009728908 -0.03623187 -0.02804249 0.02307188 -0.03759199 -0.0335344 0.009607672 -0.03590893 -0.03275561 0.01059937 -0.03536236 -0.03292739 0.0232557 -0.03536236 -0.03292739 0.02423781 -0.03597038 -0.03266125 0.02418988 -0.04014086 -0.0304284 0.0122925 -0.04443001 -0.03167748 0.02355891 -0.04452025 -0.02928948 0.02159416 -0.04443794 -0.03164613 0.02084338 -0.04479408 -0.02717059 0.01174575 -0.04458838 -0.02733707 0.02091193 -0.04472553 -0.02913415 0.01167756 -0.04452025 -0.02928948 0.01156169 -0.04514014 -0.02688491 0.01157677 -0.04800516 -0.02635496 0.01175612 -0.04524171 -0.02300626 0.01186937 -0.0482403 -0.02299809 0.0206415 -0.04524683 -0.02300089 0.02055418 -0.04874414 -0.0230062 0.02080142 -0.04837912 -0.02596849 0.01149493 -0.03653383 -0.03403925 0.02235972 -0.03653347 -0.03404057 0.01053881 -0.04680222 -0.02179265 0.01053881 -0.04527348 -0.02179265 0.010302 -0.04652786 -0.02566361 0.01022732 -0.04514014 -0.02688491 0.01559054 -0.04697471 -0.02179217 0.0218563 -0.04527348 -0.02179265 0.0218563 -0.04745358 -0.02179265 0.02205097 -0.04724949 -0.02497553 0.02216774 -0.04514014 -0.02688491 -0.02645337 -0.05217874 -0.02133238 -0.02883517 -0.05331104 -0.01284611 -0.0327152 -0.05377626 -0.01897376 -0.02348995 -0.05217999 -0.01277446 -0.02122855 -0.0510329 -0.02281123 -0.01793086 -0.05111992 -0.01343107 -0.02031898 -0.05223578 -0.003551304 -0.01453953 -0.05126214 -0.00390464 -0.01137739 -0.05153489 0.006144404 -0.02664273 -0.05347675 -0.00375247 -0.01589292 -0.05004763 -0.02396154 -0.01216727 -0.05021136 -0.0140872 -0.008649289 -0.05046778 -0.004351139 -0.006127119 -0.05094361 0.006144404 -0.01049697 -0.04922151 -0.02511465 -0.005943179 -0.04945725 -0.01476585 -0.002322137 -0.04985368 -0.004840433 -9.46923e-4 -0.05053132 0.006144404 -0.004972755 -0.04859656 -0.02576512 0.001177489 -0.0488857 -0.0156719 0.004629969 -0.04957568 -0.00400573 0.004163324 -0.05029815 0.006144404 4.95976e-4 -0.04818546 -0.02616077 0.006018996 -0.04798364 -0.02636653 0.008540749 -0.04880934 -0.01432776 0.01607877 -0.04909116 -0.01347571 0.02350735 -0.04967737 -0.01419836 0.02499127 -0.04907429 -0.02528488 0.02810883 -0.04956418 -0.02448892 0.03052723 -0.05071169 -0.01383054 0.03170728 -0.0502153 -0.02376973 0.03524309 -0.05097752 -0.02287352 0.03679758 -0.0520029 -0.01334542 0.03869652 -0.05184638 -0.02177077 0.04203701 -0.05281245 -0.0204252 0.04146343 -0.05363959 -0.006848037 0.04522144 -0.05385917 -0.0187937 0.04819393 -0.05494385 -0.01705849 0.04818481 -0.05581307 -0.004860162 0.04686528 -0.05554914 -0.00285542 0.04252523 -0.05487918 0.006144404 0.04700547 -0.05625766 0.006144404 0.03797501 -0.05367982 0.006144404 0.03386837 -0.05207616 -0.003485381 0.01203149 -0.04956465 -0.004266321 0.01946073 -0.05002534 -0.003539741 0.009203553 -0.05024403 0.006144404 0.02670413 -0.05078917 -0.004241228 0.03335475 -0.05265951 0.006144404 -0.02754819 -0.05438327 0.006144404 -0.03279989 -0.05497258 -0.00285542 -0.03413546 -0.05515378 -0.004862308 -0.03307843 -0.05569088 0.006144404 -0.03345483 -0.05198591 -0.02182304 0.03384184 -0.05096346 -0.02315747 0.008247554 -0.04342287 -0.02805459 0.002797365 -0.03497421 -0.03310149 0.01918578 -0.03378677 -0.03361117 -0.01088362 -0.03266352 -0.03406286 -0.03182536 -0.0347898 -0.03318291 -0.0311129 -0.03530019 -0.03287422 -0.02984499 -0.03556889 -0.03283309 -0.002082347 -0.03818136 -0.03153878 -0.02852112 -0.03841722 -0.03142011 -0.002696037 -0.04003173 -0.03050011 -0.02337706 -0.04056066 -0.03017055 -0.02422726 -0.04057842 -0.03012943 -0.02342498 -0.04278832 -0.02870184 -0.002309441 -0.04294162 -0.02859103 0.007674634 -0.03724712 -0.03199613 0.05256825 -0.03468555 -0.03322857 0.02535098 -0.0319361 -0.03434056 0.0463854 -0.03160595 -0.03446292 0.04013502 -0.02872949 -0.03543853 0.007840156 -0.03019207 -0.03496211 -0.003089308 -0.02767795 -0.03575766 0.03388804 -0.02584242 -0.03627097 -0.005838692 -0.02490174 -0.0365138 -0.04576289 -0.02768653 -0.03576678 -0.05086106 -0.0250439 -0.03648662 -0.0455181 -0.03064179 -0.03481131 -0.04489338 -0.03195208 -0.03433459 0.04847347 -0.03588783 -0.03268814 0.05202126 -0.03670179 -0.03227561 0.05341839 -0.03889155 -0.0311442 0.05741888 -0.03769046 -0.03180068 0.05713367 -0.04147601 -0.02965748 0.05236601 -0.04457491 -0.02738761 0.05883979 -0.04394489 -0.02789378 0.05911582 -0.04667806 -0.02550619 0.04680359 -0.03663152 -0.03233152 0.04555964 -0.03809237 -0.03159928 0.03327894 -0.03839868 -0.03142195 0.03743153 -0.04304456 -0.02851372 0.03860396 -0.04353892 -0.02814275 0.04554075 -0.04195398 -0.02928191 0.03862047 -0.04056596 -0.03016358 0.04213201 -0.0461651 -0.02601879 0.05458199 -0.05115175 -0.02040833 0.03861218 -0.05028456 -0.02156907 0.04205679 -0.05127233 -0.0202375 0.04480034 -0.05215138 -0.01891934 0.05544275 -0.05247336 -0.01834797 0.04887849 -0.05361306 -0.01642441 0.05401021 -0.05356854 -0.01638156 -0.04083889 -0.04422807 -0.02760797 -0.03303778 -0.04514461 -0.02689498 -0.03876328 -0.04050844 -0.03030079 -0.04111933 -0.04294145 -0.02861857 -0.03559273 -0.03641504 -0.03243893 -0.04674971 -0.03589475 -0.03266787 -0.04583215 -0.03342866 -0.03375601 0.001147866 -0.0366038 -0.03234541 -0.02909672 -0.04185152 -0.0292955 -0.02442562 -0.04517382 -0.02690589 -0.0371049 -0.04726064 -0.02497553 -0.02422547 -0.04813361 -0.02407383 -0.02924966 -0.009742021 -0.03893917 -0.0311129 -0.007906734 -0.03908216 -0.04764288 -0.008792221 -0.0390129 -0.02924966 -0.00656706 -0.03916645 -0.04605877 -0.005358278 -0.03923243 -0.01387751 -0.003603816 -0.03930771 0.008655846 -0.00656706 -0.03916645 0.0167036 -0.002638757 -0.03934025 0.004586279 -7.12556e-4 -0.03939098 0.01561003 0.001718878 -0.03941494 0.004608094 0.003619909 -0.0394032 0.01051968 -0.007901132 -0.0390864 0.01958328 -0.01315462 -0.0386101 0.008655846 -0.009742021 -0.03893917 -0.00762248 -0.01184314 -0.03874301 -0.02780109 -0.01342284 -0.03856974 -0.004218101 -0.0144242 -0.03844785 -0.02924966 -0.0164836 -0.03816616 0.01212769 -0.0164836 -0.03816616 0.01386064 -0.01748985 -0.03802007 -0.01252818 -0.02223265 -0.03713399 0.01212769 -0.01965856 -0.03764384 -0.02924966 -0.01965856 -0.03764384 -0.05141437 -0.02233344 -0.03711235 -0.0498048 -0.01913404 -0.03773796 -0.05426502 -0.02795535 -0.03572607 -0.03077149 -0.0179491 -0.03793787 -0.04845947 -0.0158087 -0.0382632 -0.04845774 -0.01240342 -0.03868323 0.02779299 -0.02259081 -0.03705638 0.03080552 -0.02429479 -0.03666353 0.006808817 -0.0465154 -0.02571606 0.03727942 -0.04553419 -0.02655082 0.02600443 -0.04774713 -0.02447742 0.03777486 -0.04779225 -0.02442544 0.02989548 -0.04837155 -0.0238226 0.03365278 -0.04910778 -0.02300369 0.03728055 -0.04993593 -0.02201461 0.05600953 -0.04909455 -0.0230543 0.03857815 -0.04823654 -0.02396452 0.0511015 -0.05603826 -0.01088535 -0.006464123 1.31453e-4 -0.03940254 0.002635657 -4.71566e-4 -0.03940725 -0.004506587 0.001718819 -0.03941744 -0.02924966 1.31452e-4 -0.03940254 -0.04574102 -0.001814424 -0.03936553 -0.0456236 0.001723229 -0.03941494 -0.03096586 0.002056002 -0.03941535 -0.04849284 -0.0338298 -0.03323662 -0.05146735 -0.03383022 -0.03348815 -0.05325907 -0.03724002 -0.03200012 -0.04850465 -0.03858298 -0.03132921 -0.03430563 -0.04968583 -0.02235281 -0.03237992 -0.05214428 -0.01896095 -0.0246157 -0.05022692 -0.02164518 -0.02334123 -0.04528838 -0.02676522 -0.005957543 -0.04722809 -0.02502191 -3.00039e-4 -0.0457825 -0.02634513 -0.02341222 -0.04776251 -0.0244584 -1.79927e-4 -0.04676693 -0.02543997 -0.02298998 -0.04987633 -0.02208846 -0.01730459 -0.04879003 -0.0233637 -0.01165479 -0.04790729 -0.02431273 0.05930626 -0.04154008 -0.03133672 0.05246049 -0.03976917 -0.03238397 0.05640327 -0.03741836 -0.03361773 0.05006831 -0.03707468 -0.03378403 0.05157041 -0.03439003 -0.03498482 -0.004069387 -0.03458589 -0.03490298 0.002812743 -0.03653794 -0.03403717 0.006743669 -0.03919631 -0.03273075 0.04621881 -0.03939092 -0.03260874 0.0307163 -0.04014962 -0.03216296 0.04618251 -0.04173558 -0.03120774 0.05058962 -0.04336524 -0.03013134 0.04458916 -0.04464083 -0.02919846 0.05845725 -0.04579162 -0.02829259 0.05785548 -0.04764103 -0.02667677 0.0340349 -0.04700064 -0.0272606 0.05702465 -0.0492981 -0.02502739 0.0597943 -0.04429239 -0.02944707 0.005976736 -0.04314255 -0.0302847 0.003317534 -0.04434311 -0.0294218 -0.01346713 -0.04486107 -0.02903044 -0.01380747 -0.04614466 -0.02800017 -0.04180836 -0.04422038 -0.02951139 -0.03756046 -0.04733878 -0.02695572 0.001039505 -0.04346138 -0.03006535 -0.03199017 -0.04271483 -0.03056764 -0.04726266 -0.04028904 -0.03211766 -0.03517848 -0.04173499 -0.0312165 -0.03575009 -0.03894603 -0.03283417 -0.0374639 -0.03816121 -0.03327989 -0.03588044 -0.04889363 -0.02545028 -0.03554219 -0.05035978 -0.02384608 -0.05843883 -0.03516423 -0.0346561 -0.03263157 -0.03620022 -0.03419375 -0.05789142 -0.02983975 -0.03670674 -0.05287146 -0.0309602 -0.03632539 -0.0526337 -0.02784556 -0.03728669 -0.05249887 -0.0245347 -0.0381487 -0.005486249 -0.02708405 -0.03748792 -0.01400059 -0.02389454 -0.03830003 0.03325986 -0.02569168 -0.03786063 0.03937274 -0.02856409 -0.03705859 -0.002054154 -0.02983915 -0.03665941 0.0455026 -0.0313943 -0.03613328 -0.006344556 -0.03221184 -0.03583824 -0.04747813 -0.03155732 -0.03607779 -0.04685962 -0.02953416 -0.03675818 -0.04663723 -0.02855801 -0.03706037 -0.04998683 -0.01629978 -0.0397064 -0.03114682 -0.01863586 -0.03934365 -0.05031323 -0.02049434 -0.03901427 -0.02924966 -0.01598864 -0.0397526 -0.02964776 -0.0138731 -0.0400269 -0.04794067 -0.01184105 -0.04025024 0.01815438 -0.012214 -0.04021263 0.01981955 -0.01534217 -0.03984105 0.01212769 -0.01598864 -0.0397526 0.01430898 -0.01799416 -0.03945749 0.02453196 -0.02043324 -0.03902578 -0.04631817 -0.007339179 -0.04062157 -0.02924966 -0.01024019 -0.04040187 -0.03132218 -0.008057832 -0.04057341 -0.02924966 -0.006067872 -0.04069727 -0.04712641 -0.002867698 -0.04083448 -0.01483196 -0.003433167 -0.04081654 0.008655846 -0.006067872 -0.04069727 0.01689088 -0.003261923 -0.04081743 0.01043891 -0.007281005 -0.04062479 -0.0456236 0.001718878 -0.04091489 -0.02924966 -3.68491e-4 -0.04089552 -0.03110367 0.001123726 -0.04091602 -0.006464123 -3.6849e-4 -0.04089552 0.002506673 -9.43747e-4 -0.04089742 0.004905879 0.001418352 -0.04092198 0.01574969 0.001718878 -0.04091489 -0.004522502 0.001414537 -0.0409156 0.01775443 -0.008940696 -0.040506 0.008655846 -0.01024019 -0.04040187 0.01212769 -0.02015048 -0.03907859 -4.21808e-4 -0.0216816 -0.03878134 0.02878767 -0.0232762 -0.03843605 -0.02924966 -0.02015048 -0.03907859 0.02282971 -0.03332114 -0.0354163 -0.03004837 -0.03733378 -0.03365647 -1.01479e-4 -0.03846871 -0.03307694 -0.02924662 -0.03908622 -0.03274941 -7.2086e-4 -0.04054248 -0.03193461 -0.02938687 -0.04092299 -0.03170841 -4.26354e-4 -0.04192227 -0.03108924 0.0447812 -0.0498321 -0.02444827 0.05318349 -0.05318152 -0.02010983 0.05375146 -0.05530703 -0.0163905 0.05126702 -0.05736058 -0.01161104 0.05605316 -0.05082488 -0.02329784 -0.0494759 -0.03301614 -0.03553479 -0.02980411 -0.03416913 -0.03507608 0.005702316 -0.0476765 -0.009331881 0.0156297 -0.0489344 0.006144404 0.009587287 -0.04874336 0.006143748 0.019189 -0.0481972 -0.007775902 0.02162081 -0.04939335 0.006144404 0.02435731 -0.0486924 -0.008106291 0.003462076 -0.04664033 -0.02494192 -8.0778e-4 -0.04786747 -0.01025259 0.002597272 -0.04884612 0.006144404 -0.003698885 -0.04922026 0.006144404 -0.00722438 -0.04846042 -0.009234786 -0.01306843 -0.04918289 -0.008881032 -0.01846188 -0.05004459 -0.008348762 -0.02297759 -0.05115574 -0.004236042 -0.02035909 -0.05140405 0.006144404 -0.0249691 -0.05229431 0.006144404 -0.02447587 -0.05151557 -0.003356099 -0.02900743 -0.05317002 0.006144404 -0.02904373 -0.05211126 -0.008735895 -0.03211539 -0.0531845 -0.003852367 -0.03241127 -0.05397039 0.006144404 -0.009663999 -0.04980909 0.006144404 -0.01523745 -0.0505563 0.006144404 -0.03464555 -0.05328905 -0.0111528 -0.03594166 -0.05447393 -0.004870414 0.02712047 -0.05006337 0.006144404 0.02943664 -0.04930597 -0.009576201 0.03211188 -0.05088794 0.006144404 0.03403574 -0.05025947 -0.007920145 0.03657871 -0.05180883 0.006144404 0.04199171 -0.05315709 0.006144404 0.03880387 -0.05167108 -0.003067255 0.04667085 -0.05456691 0.006144404 0.0465247 -0.05378496 -0.003866672 0.04880249 -0.05446267 -0.004866719 0.03746592 -0.05122923 -0.004627645 -0.05871886 0.04456025 -0.004849195 -0.05631464 0.04429125 -0.01115667 -0.05586379 0.04467248 -0.01110053 -0.05525982 0.04577171 -0.008093953 -0.0558325 0.0405994 -0.03089404 -0.05580121 0.04331511 -0.0177161 -0.05651861 0.03982239 -0.03156286 -0.05461186 0.04076009 -0.0319848 -0.04724073 0.04382503 -0.02964287 -0.04859596 0.04333186 -0.0295031 -0.04622149 0.04457932 -0.02881348 -0.053658 0.04141497 -0.03050303 -0.05504298 0.0436002 -0.01757085 -0.0546512 -0.03740906 -0.03159832 -0.05621898 -0.03783684 -0.02634274 -0.0558325 -0.03716152 -0.03089404 -0.05580103 -0.03987723 -0.01771622 -0.05651915 -0.04061287 -0.01095539 -0.05525982 -0.04233384 -0.008093953 -0.05585998 -0.04117256 -0.01137775 -0.05629056 -0.04189467 -0.007116496 -0.04859596 -0.03989404 -0.0295031 -0.04735231 -0.04044836 -0.02921825 -0.04622149 -0.04114145 -0.02881348 -0.05884307 -0.04107868 -0.004855394 -0.05891138 -0.0420556 -0.004855394 -0.05651861 0.04381966 -0.01208239 -0.05648958 -0.03634166 -0.03181958 -0.05495423 -0.04016155 -0.01772093 -0.053658 -0.03797709 -0.03050303 -0.06160598 0.0377866 -0.03310036 -0.06090366 0.03820085 -0.03223884 -0.06182497 0.04350823 -0.004855394 -0.0598793 0.03863579 -0.03180724 -0.0587722 0.03898984 -0.03190648 -0.05757999 0.03922027 -0.0327444 -0.06182497 0.04450821 -0.004855394 -0.05891138 0.04549348 -0.004855394 -0.05699378 0.04577767 -0.00663048 -0.05699378 0.04141837 -0.02787542 -0.06182515 0.03978461 -0.02787542 -0.06182497 0.03960335 -0.03306746 -0.05698114 0.04125767 -0.03263127 -0.05699378 0.04685032 -0.007208406 -0.05699378 0.04577964 -0.01159578 -0.05699378 0.04173648 -0.03129988 -0.05617731 0.04706037 -0.008012175 -0.06186014 0.03927785 -0.03368532 -0.06182539 0.0348438 -0.03590583 -0.06181699 0.02298992 -0.03380364 -0.06182843 0.02298849 -0.03593832 -0.06090366 -0.03476303 -0.03223884 -0.06160598 -0.03434872 -0.03310036 -0.06182497 -0.04007035 -0.004855394 -0.0598793 -0.03519797 -0.03180724 -0.0587722 -0.03555196 -0.03190648 -0.05757647 -0.03578299 -0.03275042 -0.06182497 -0.04107034 -0.004855394 -0.06182515 -0.03634673 -0.02787542 -0.06182169 -0.03614848 -0.03349256 -0.06181216 -0.01955324 -0.03358215 -0.06182539 -0.03140592 -0.03590583 -0.06182527 -0.01955014 -0.03593826 -0.06126374 -0.02553015 -0.03257417 -0.06031429 -0.02553069 -0.03191947 -0.05916905 -0.0254758 -0.03180778 -0.05810785 -0.02553069 -0.03226822 -0.05734562 -0.01955121 -0.03334313 -0.05776143 -0.01952105 -0.03259545 -0.05710184 -0.03132969 -0.03458869 -0.05810785 -0.0195508 -0.03226822 -0.06126403 -0.0195508 -0.03257459 -0.0525459 -0.03332918 -0.03378635 -0.05699378 -0.04341244 -0.007208406 -0.05699378 -0.0423398 -0.00663048 -0.05699378 -0.04234176 -0.01159578 -0.05699378 -0.03798049 -0.02787542 -0.05699378 -0.03829866 -0.03129988 -0.05698055 -0.03781968 -0.03263682 -0.04774689 -0.0417155 -0.03017103 -0.04906761 -0.04128885 -0.02978926 -0.04694592 -0.04239624 -0.02920168 -0.05617725 -0.04362255 -0.008012175 -0.0586639 -0.03642863 -0.03382372 -0.05929589 -0.03681141 -0.03320127 -0.06093144 -0.03220117 -0.03584516 -0.06028944 -0.03630429 -0.03353768 0.04884988 0.00246483 -0.03499925 0.04886096 0.00448215 -0.03498208 0.04858624 9.95555e-4 -0.03540796 0.04784381 0.004924297 -0.03558349 0.05561822 5.74209e-4 -0.02417081 0.04925358 9.49878e-4 -0.03698241 0.05683493 5.01486e-4 -0.02506041 0.05812418 5.3732e-4 -0.02288413 0.04439491 0.00330466 -0.03597718 0.0456922 0.002052664 -0.03583991 0.04529649 0.01014441 -0.0358498 0.04829847 0.009978115 -0.03549575 0.03385508 0.01013129 -0.0370208 0.02313882 0.01014894 -0.03824323 0.02222436 0.0033046 -0.0384522 0.03057819 0.003306388 -0.03742063 0.05699646 0.02015268 -0.03407263 0.05245715 0.01378238 -0.03492534 0.06193006 0.01551556 -0.03334325 0.0683934 0.02100259 -0.03164339 0.06587535 0.01603811 -0.0324766 0.07226634 0.01659494 -0.03071868 0.07536137 0.02233523 -0.02925902 0.07788151 0.0178436 -0.028481 0.08823144 0.01898539 -0.02079045 0.08431446 0.01753818 -0.02476692 0.08685868 0.01583325 -0.02268457 0.04460209 0.01330363 -0.03588312 0.06446123 0.03439891 -0.03185313 0.0659371 0.02420806 -0.03211724 0.07047551 0.03330034 -0.030245 0.06177043 0.02715045 -0.03289908 0.0594446 0.03763908 -0.03277325 0.06376975 0.03670781 -0.03185307 0.07160317 0.02544927 -0.03042459 0.07742238 0.0412572 -0.02570927 0.07491415 0.04011386 -0.02747344 0.0779311 0.03895455 -0.02593129 0.0783059 0.02772086 -0.02737087 0.07933723 0.03719061 -0.02540606 0.08574306 0.02681559 -0.02214753 0.0868321 0.02866661 -0.02047884 0.08401334 0.03635358 -0.02149027 0.08357208 0.02636921 -0.02420288 0.0811904 0.01834511 -0.02677273 0.08582025 0.0193594 -0.02324515 0.09016972 0.01567143 -0.01857739 0.08968013 0.007510066 -0.0200985 0.09510099 -0.01679533 -0.001681268 0.09458762 -0.01641166 -0.005198299 0.09350955 -0.02514392 -0.002975583 0.09471368 -0.02298837 0.003410577 0.09283256 -0.03180223 0.00350964 0.09387069 -0.02829211 0.006144404 0.09160083 -0.03720688 0.006144523 0.09547162 -0.0198006 0.006144404 0.09574025 -0.009018123 -0.002989053 0.09465193 -0.01264095 -0.007065832 0.09544575 -0.004506349 -0.006174623 0.09441399 -0.004763543 -0.01033705 0.09497261 0.004050254 -0.008788108 0.09399336 -7.16948e-4 -0.01206862 0.09426957 0.008218467 -0.01080888 0.09333783 0.003177165 -0.01384955 0.09339123 0.01235353 -0.01264578 0.09245651 0.006910026 -0.01561886 0.092372 0.01641112 -0.01426351 0.09135878 0.0161882 -0.01645594 0.09061104 0.02209639 -0.01639384 0.09136694 0.00582832 -0.01768982 0.08967214 -1.16394e-4 -0.02029347 0.09074735 -0.003123879 -0.0186845 0.09314382 -0.02329075 -0.00693053 0.09194308 -0.03079742 -0.004886388 0.09174674 -0.03456765 2.40442e-4 0.08789575 0.007613956 -0.0222283 0.09201633 -0.002117931 -0.01659071 0.09082591 -0.0131272 -0.01748675 0.09289205 -0.006999909 -0.01422649 0.09313088 -0.01351714 -0.01211696 0.09118407 -0.02026724 -0.01466935 0.09064668 -0.03667634 -0.003507852 0.08977663 -0.03642338 -0.008140742 0.08932262 -0.008544743 -0.02036368 0.08832454 -0.0179339 -0.02014511 0.08667349 -0.01130342 -0.02300232 0.08717811 -0.01522296 -0.02194768 0.08583092 -0.02321857 -0.02207428 0.08738678 -0.02492421 -0.01994621 0.09001255 -0.02631032 -0.01478898 0.08841449 -0.02657866 -0.01766759 0.08803349 -0.03407728 -0.01512652 0.09069871 -0.02977347 -0.01125317 0.0881868 -0.03630077 -0.01318043 0.08520805 -0.01296025 -0.02411037 0.08535748 -0.01596224 -0.02364164 0.08299106 -0.01431763 -0.02572268 0.0678268 -0.02186083 -0.03156721 0.07146221 -0.02234077 -0.03044658 0.07066541 -0.01332819 -0.03119462 0.06413978 -0.01238787 -0.0328955 0.05942398 -0.02206629 -0.03345263 0.05488824 -0.01870125 -0.03434091 0.04875874 -0.02886933 -0.0348348 0.04578238 -0.01690953 -0.03561055 0.04424089 -0.01986873 -0.03570318 0.06322985 -0.01644223 -0.0329324 0.06362026 -0.02507847 -0.0324366 0.08418995 -0.02263212 -0.02368205 0.07565969 -0.02033931 -0.02901333 0.07884663 -0.02225363 -0.02733731 0.07719665 -0.01447319 -0.02884513 0.05224078 -0.01023459 -0.03497302 0.0448147 -0.009866237 -0.03585463 0.03455048 -0.01671665 -0.03678226 0.04501223 -0.00670886 -0.03587663 0.04783219 -0.001517593 -0.03558355 0.03385508 -0.006693422 -0.0370208 0.02441197 -0.006689369 -0.03807115 0.02272093 1.04546e-4 -0.03839498 0.02316719 -0.009862899 -0.03816044 0.03057819 1.31455e-4 -0.03742063 0.08618515 0.03680157 -0.01867449 0.08840978 0.02818065 -0.01845687 0.08110499 -0.0267837 -0.0253461 0.08818054 0.03775215 -0.01467311 0.08986294 0.02818709 -0.01571661 0.09154808 0.02811324 -0.01200407 0.09292399 0.02140367 -0.01104122 0.0929495 0.02699702 -0.007476449 0.09396135 0.01732587 -0.009313046 0.09459632 0.01768893 -0.006476461 0.09365493 0.02858042 -0.001994192 0.09424841 0.02325069 -0.004369139 0.09501373 0.02309566 9.60144e-4 0.09387069 0.03172999 0.006144404 0.09547162 0.02323848 0.006144404 0.09160041 0.04064655 0.006144702 0.09269595 0.0357573 0.003432631 0.09168124 0.03836947 4.59902e-4 0.07500135 0.03175193 -0.02854615 0.07206702 0.04034239 -0.02873098 0.07166701 0.03459799 -0.02959525 0.04765141 0.03202509 -0.03498607 0.05414324 0.02971684 -0.03415179 0.05437618 0.03612214 -0.03378343 0.04432773 0.02330708 -0.03569537 0.04119813 0.02954006 -0.03583079 0.03577727 0.02330595 -0.03658199 0.04572683 0.02028697 -0.03561329 0.05020761 0.02244108 -0.03499853 0.02647697 0.02333229 -0.03748065 0.02424657 0.01330816 -0.03802388 0.03424507 0.02204954 -0.03675168 0.01773548 0.01257771 -0.03898614 0.0353896 0.02013272 -0.03669697 0.01655155 0.005348622 -0.03936237 0.03542894 -0.01985538 -0.03660833 0.02563261 -0.01929628 -0.03759258 0.0411992 -0.0261026 -0.03583067 0.05606561 -0.03320223 -0.03350901 0.06432199 -0.03539204 -0.03153371 0.06540042 -0.02998268 -0.03168416 0.06898838 -0.0291962 -0.03073406 0.07271188 -0.036834 -0.02852642 0.07513052 -0.026914 -0.02863836 0.07794058 -0.03355002 -0.02633869 0.08186173 -0.03260582 -0.02371114 0.0775119 -0.03662848 -0.02597004 0.08470416 -0.03326153 -0.02064901 0.08656758 -0.03388947 -0.01783293 0.09654229 -0.01122605 0.006144404 0.09609425 -0.01058328 6.89431e-4 0.09707868 -0.002601623 0.006144404 0.096641 -0.004817128 0.00220865 0.09677141 0.003824293 0.002131283 0.09707868 0.0060395 0.006144404 0.09520328 0.01126128 -0.006447076 0.09615701 0.01095145 -7.9189e-4 0.09539127 0.01752221 -0.001957356 0.09583753 0.007449626 -0.004218101 0.0958569 0.002654731 -0.004766583 0.09643614 0.01233726 0.002657353 0.09654229 0.01466393 0.006144404 0.09065014 0.04005873 -0.00358504 0.09178209 0.03482747 -0.005028188 0.09053087 0.03614526 -0.008997976 0.08810263 0.03988343 -0.01329243 0.08962225 0.04013746 -0.008365213 0.04439425 1.34168e-4 -0.03597718 0.09267431 0.03358775 -0.001355469 0.09625536 -9.25601e-4 -0.002118766 0.09290492 -0.01977396 -0.01015031 0.09461361 -0.008754968 -0.00870645 0.04886454 -0.001044571 -0.03497636 0.04787808 -0.002031683 -0.03708416 0.04870271 -0.002562642 -0.03520399 0.04959177 -0.002726018 -0.03664273 0.05578708 -0.003907084 -0.02390283 0.05639725 -0.004021644 -0.02575236 0.04892677 -0.00539422 -0.03504538 0.05725181 -0.01001971 -0.03349673 0.05196386 -0.008369147 -0.03391891 0.05457389 -0.009147882 -0.03293436 0.0496453 -0.006536424 -0.03464424 0.07175803 -0.01231789 -0.03007364 0.07633364 -0.01278007 -0.02718502 0.08605915 -0.009928345 -0.02284216 0.08253425 -0.01307219 -0.02479279 0.08107519 -0.01320171 -0.02546346 0.08497321 -0.01207381 -0.02347517 0.07953673 -0.01316732 -0.02609038 0.08605915 0.01336622 -0.02284216 0.08135187 0.01686459 -0.02579647 0.07633364 0.01621794 -0.02718502 0.08386272 0.01643455 -0.02435195 0.08497327 0.01551163 -0.02347511 0.08615726 0.01462811 -0.02301216 0.06990367 0.01543533 -0.03067731 0.05431121 0.01255726 -0.03338587 0.05768549 0.01401782 -0.03383326 0.04897081 0.008368313 -0.03489118 0.05019372 0.01071578 -0.03455823 0.05247932 0.01203089 -0.03379088 0.04871946 0.005998015 -0.03520506 -0.02342545 0.05464994 -0.004187464 -0.02442526 0.05492579 -0.003488957 -0.02422547 0.05438762 -0.004827558 -0.02342528 0.04400438 -0.03016477 -0.0231229 0.04650306 -0.02850866 -0.02317279 0.04893451 -0.02658224 -0.0234251 0.05341762 -0.02196085 -0.02292543 0.05122441 -0.02443712 -0.02422547 0.04678559 -0.02766883 -0.0245583 0.04676157 -0.02830457 -0.02427327 0.04401248 -0.03014487 -0.02422863 0.0518254 -0.02382391 -0.02472543 0.04917156 -0.02637791 -0.02426069 0.05359607 -0.02171272 0.03843396 0.05452936 -0.004481613 0.03867411 0.05365025 -0.02135628 0.03880381 0.05510896 -0.003067255 0.03857439 0.04665547 -0.02838307 0.0388962 0.04926127 -0.02629822 0.03858685 0.05164724 -0.02394908 0.03773051 0.04417735 -0.02974325 0.03777909 0.04668313 -0.02775251 0.03755909 0.04615604 -0.02864223 0.03774017 0.04897183 -0.02654832 0.03753274 0.053348 -0.02198296 0.03757244 0.05118656 -0.02434045 0.03778046 0.05289179 -0.02182614 0.03862941 0.04398232 -0.03017014 0.03790932 0.05408924 -0.005555689 0.03738313 0.05469107 -0.00408709 -0.02894985 0.04499781 -0.0295276 -0.03254628 0.04860651 -0.02688986 -0.03699201 0.05070698 -0.02496606 -0.03430461 0.05339246 -0.0219922 -0.0317375 0.05538475 -0.01930987 -0.04329133 0.04561388 -0.02912783 -0.03463757 0.04676192 -0.02829957 -0.03973412 0.04342597 -0.03053736 -0.03685498 0.04244768 -0.03110629 -0.04675126 0.03933137 -0.03264826 -0.0345695 0.03910714 -0.03279387 -0.04826623 0.04188036 -0.03140592 -0.05328947 0.04069817 -0.03198325 -0.05147916 0.03729128 -0.03350263 -0.03182822 0.0382272 -0.03318315 -0.04618197 0.03560262 -0.03426527 -0.0165885 0.03650784 -0.0339027 0.003066539 0.03828948 -0.03315573 -0.001438558 0.04120349 -0.03176116 -0.01365351 0.03934645 -0.03267562 -0.02839452 0.04046785 -0.03213346 -0.02764475 0.04229569 -0.03117012 -0.002789199 0.04348683 -0.03048348 -0.002437412 0.0458002 -0.02901434 -0.001651465 0.04855811 -0.02689003 -0.005843818 0.0506547 -0.02503108 -4.23753e-5 0.05019658 -0.02544772 -0.01163125 0.05134195 -0.02431607 -0.01734215 0.05223447 -0.02335637 -0.02324283 0.03443527 -0.03468263 -0.04552412 0.03415113 -0.03478682 -0.007159888 0.03222984 -0.03541839 -0.04574841 0.03116422 -0.03574651 -0.003469288 0.03042596 -0.03595685 0.04013401 0.03216689 -0.03543865 0.03388714 0.02927988 -0.03627109 0.02149897 0.03357684 -0.03498005 0.04638564 0.03504395 -0.03446286 -0.04930752 0.02844208 -0.0364927 -0.007028937 0.02828872 -0.03652656 -0.05141466 0.02577179 -0.03711223 -0.0161426 0.02557098 -0.03715527 0.02929812 0.02688002 -0.0368601 0.02490836 0.02407473 -0.03745973 -0.02924966 0.02309644 -0.03764384 -0.04980581 0.02257418 -0.03773754 0.01212769 0.02309644 -0.03764384 0.01901048 0.01750642 -0.03849226 0.01386642 0.02091228 -0.03802323 0.01212769 0.01992148 -0.03816616 -0.01628392 0.01790994 -0.03844177 -0.02924966 0.01992148 -0.03816616 -0.0495333 0.01918113 -0.03827053 -0.03077143 0.02138644 -0.03793793 -0.04739445 0.01582318 -0.03868609 0.0181905 0.01589226 -0.03867864 -0.02924966 0.01317989 -0.03893917 0.008655846 0.01317989 -0.03893917 0.01051884 0.01134312 -0.03908145 0.01618808 0.008921086 -0.03922611 -0.04660165 0.01233059 -0.0390079 -0.03111279 0.01134479 -0.0390821 -0.04605954 0.008802592 -0.03923213 -0.02924966 0.01000493 -0.03916645 -0.01535177 0.007050633 -0.03930896 0.008655846 0.01000493 -0.03916645 -0.02924966 0.003306388 -0.03940254 -0.04682707 0.005289137 -0.0393632 0.002573192 0.003305196 -0.03940212 0.003280699 0.00457257 -0.0393812 0.05256825 0.03812342 -0.03322857 0.03336584 0.03686958 -0.03375703 0.04665136 0.03957766 -0.03256559 0.0513162 0.03977328 -0.03244739 0.0572713 0.04138946 -0.03168624 0.05345833 0.04267013 -0.03096896 0.05901938 0.04423213 -0.02999585 0.05661982 0.04576992 -0.02908837 0.0533322 0.04502362 -0.0295273 0.04924279 0.04925185 -0.02637368 0.05724281 0.05075776 -0.02492123 0.06011557 0.04613828 -0.02859157 0.05506932 0.05286347 -0.02265638 0.05471491 0.05442309 -0.02064055 0.04239642 0.05480372 -0.02012234 0.05325853 0.0561735 -0.01799076 0.04893445 0.05708092 -0.01637899 0.05102241 0.05938762 -0.01118081 0.04537636 0.04515266 -0.0294342 0.04515057 0.04294484 -0.03080254 0.009263753 0.04311269 -0.03070449 0.009307265 0.04460066 -0.02979552 0.008687198 0.04160064 -0.03154873 0.04576683 0.0411821 -0.03177201 0.02447187 0.04526245 -0.02936172 0.009298443 0.04618602 -0.02872616 0.02406841 0.04755043 -0.02771317 0.008098959 0.04836726 -0.02706807 0.0157864 0.05014407 -0.02549928 0.02379345 0.05087321 -0.024782 0.03003799 0.05183488 -0.02379512 0.00668174 0.04995638 -0.02567118 0.007061123 0.0397033 -0.03250288 -0.0308178 0.03888469 -0.03278887 -0.02998101 0.03956627 -0.03257727 -0.0190407 0.05373817 -0.006168305 -5.06153e-4 0.05184811 -0.00224632 -0.003847539 0.05128455 -0.01364433 0.00251317 0.05011355 -0.02486163 0.005086123 0.05174314 -5.13611e-4 0.009371101 0.05119425 -0.007945775 0.01165521 0.05047374 -0.01877558 0.01409929 0.05143272 -0.006231129 0.01750999 0.05079603 -0.01797825 0.01930242 0.05182272 -0.005242943 0.02275753 0.05136609 -0.0163719 0.02439457 0.05243527 -0.003840446 0.02766555 0.0520128 -0.01604223 0.02910935 0.05299013 -0.005355119 0.03312844 0.05304485 -0.01456308 0.03323596 0.0545324 0.006142497 0.03657871 0.05524665 0.006144404 0.0421012 0.05662131 0.006144165 -0.01415288 0.05249935 -0.0127936 -0.008971989 0.05181831 -0.01306802 0.02712047 0.05350124 0.006144404 0.02162081 0.05283117 0.006144404 0.04652386 0.05724316 -0.003602504 0.04901641 0.05797165 -0.004882454 0.04318279 0.0563234 -0.002349495 0.04667085 0.05800479 0.006144404 0.0156297 0.05237227 0.006144404 0.009164154 0.05217796 0.006144404 -0.003698885 0.05265814 0.006144404 0.002597272 0.05228394 0.006144404 -0.006617903 0.05238175 -0.00149399 -0.009663999 0.05324697 0.006144404 -0.01237058 0.05305373 -0.001408576 -0.01523745 0.05399417 0.006144404 -0.02035909 0.05484193 0.006144404 -0.02393573 0.05551725 0.00614351 -0.03392678 0.05636531 -0.01366269 -0.02853584 0.05545383 -0.008494079 -0.03240835 0.05740088 0.006144344 -0.03213614 0.05669856 -0.00285542 -0.03430283 0.057078 -0.004972934 0.03778046 -0.04945397 -0.02182614 0.03790932 -0.05065137 -0.005555689 0.03775918 -0.0407992 -0.02961242 0.03843396 -0.05109149 -0.004481613 -0.0232523 -0.05099618 -0.005372226 -0.02339369 -0.04956412 -0.02198499 -0.02356016 -0.05055683 -0.005786359 -0.02407872 -0.05119019 -0.004242122 -0.02350014 -0.04556757 -0.01796144 0.03852981 0.04685342 -0.0232129 0.03784894 0.04904311 -0.01786941 0.008655846 0.009505748 -0.04069727 -0.01483166 0.006870985 -0.04081654 -0.02924966 0.009505748 -0.04069727 0.01629108 0.008782923 -0.04073494 0.01080632 0.01159369 -0.0405755 0.01869827 0.0147916 -0.04030942 0.008655846 0.01367807 -0.04040187 -0.01089131 0.01658695 -0.04011106 0.01981782 0.01877748 -0.03984141 0.01212769 0.01942646 -0.0397526 0.0142489 0.02141481 -0.03946042 0.02447408 0.02258211 -0.03926229 0.0142216 0.023979 -0.03900539 0.01212769 0.02358835 -0.03907859 -0.02924966 0.02358835 -0.03907859 -0.009678244 0.02745062 -0.0382725 -0.05249798 0.02797108 -0.03814911 -0.04906809 0.02979665 -0.03768545 -0.0511896 0.0302388 -0.03755694 -0.006085753 0.03108865 -0.03732764 0.033257 0.02912819 -0.03786098 0.03936725 0.03199946 -0.0370593 0.02878433 0.02671211 -0.03843653 -0.02924966 0.01367807 -0.04040187 -0.04853206 0.01530569 -0.04024678 -0.02924966 0.01942646 -0.0397526 -0.04854023 0.01968276 -0.03971642 -0.03074973 0.02033871 -0.03962022 -0.03095299 0.01272779 -0.04048079 -0.04631817 0.01077723 -0.04062157 -0.04705828 0.006211459 -0.04083764 -0.02924966 0.003806352 -0.04089552 -0.006464123 0.003806352 -0.04089552 -0.001435995 0.03434342 -0.03630352 -0.01907259 0.03736907 -0.03517317 0.01698374 0.03701692 -0.0353145 0.04549932 0.03483062 -0.03613382 0.05157041 0.0378279 -0.03498482 -0.04646587 0.03330761 -0.03664952 -0.04663735 0.03199553 -0.03706049 -0.04947644 0.03645396 -0.03553479 -0.05321556 0.03368169 -0.03658705 -0.05843883 0.03860211 -0.0346561 -0.05795687 0.03396159 -0.0364567 0.04891169 0.04697293 -0.0300067 0.05955684 0.04657006 -0.0303089 0.05216056 0.04592806 -0.03072273 0.05823421 0.04901522 -0.02847176 0.003101527 0.04765427 -0.02951556 0.01412302 0.05153703 -0.02625107 0.001507818 0.04998272 -0.02765995 0.003783345 0.05147659 -0.02630913 0.05785554 0.05107879 -0.02667689 0.04245865 0.05010092 -0.02755761 0.02172404 0.0489704 -0.02850252 0.005988001 0.04626876 -0.03050035 -0.01770019 0.04904806 -0.02844011 -0.04117357 0.04765832 -0.02951258 -0.03756046 0.05077666 -0.02695572 -0.001456439 0.05174589 -0.02604526 -0.006652235 0.05220282 -0.02558845 -0.03649151 0.05231976 -0.02546137 -0.01182168 0.05283838 -0.02493119 -0.03411722 0.05372613 -0.02393883 -0.02196955 0.05444049 -0.02308094 -0.03390723 0.05534881 -0.02190715 -0.0269047 0.055561 -0.02162629 -0.03226608 0.05696129 -0.01957356 0.04608732 0.04468846 -0.03151953 0.007181584 0.04291838 -0.03253996 0.04706621 0.04141432 -0.03335183 0.05016869 0.04050689 -0.03379529 0.026304 0.04149103 -0.03329735 0.0030272 0.03983205 -0.03410422 0.05777537 0.04228168 -0.03290671 0.05244719 0.04314696 -0.03240668 0.007236123 0.04434221 -0.03171956 0.00571084 0.04110115 -0.03349989 -3.78688e-4 0.04383569 -0.03202468 -0.02943193 0.04273962 -0.03264278 -0.02973335 0.04489439 -0.03137713 -2.61328e-4 0.04193836 -0.03306663 -0.03019112 0.04111897 -0.0334866 -0.03299653 0.03967607 -0.03417629 -0.03557205 0.04157489 -0.03328597 -0.04735237 0.04370701 -0.03213036 -0.03227514 0.0464676 -0.03035765 4.72858e-4 0.04602396 -0.03065627 -0.03515392 0.04511094 -0.031264 -0.05031287 0.02393138 -0.03901445 -0.0305826 0.02276843 -0.03923189 0.02447879 0.05244457 -0.02534621 0.05680459 0.05290603 -0.02484941 0.02957481 0.05323302 -0.02449125 0.03487336 0.054138 -0.02344799 0.0442788 0.05681782 -0.01980489 0.0546382 0.05458116 -0.02291971 0.05512827 0.05712825 -0.01929223 0.04652673 0.05761867 -0.01846134 0.05285012 0.05949014 -0.01479846 0.00260806 0.00475645 -0.0408827 0.004778444 0.003528177 -0.04068142 0.01668649 0.005285561 -0.04087078 0.03781598 -0.04330962 -0.02347129 0.03849577 -0.04580181 -0.01738977 0.04303711 0.05720448 -0.01116704 0.03939068 0.05547451 -0.02151638 -0.01684969 0.05364847 -0.0237782 0.0345664 0.05425983 -0.02306157 0.01935774 0.05190581 -0.02561461 0.008960366 0.0514273 -0.02607583 0.003839492 -0.001376628 -0.04024124 -0.02924966 0.01992148 -0.03918206 0.01212769 0.01992148 -0.03918206 0.01212769 0.02309644 -0.03866821 -0.02924966 0.02309644 -0.03866821 0.008655846 0.01000493 -0.040169 -0.02924966 0.01000493 -0.040169 0.008655846 0.01317989 -0.03994441 -0.02924966 0.01317989 -0.03994441 -0.02924966 1.31452e-4 -0.04040265 -0.006464123 1.31453e-4 -0.04040265 -0.005833506 0.00330621 -0.04040306 -0.02988046 0.003306031 -0.04040247 -0.02924966 -0.009742021 -0.03994441 0.008655846 -0.009742021 -0.03994441 0.008655846 -0.00656706 -0.040169 -0.02924966 -0.00656706 -0.040169 -0.02924966 -0.0164836 -0.03918206 0.01212769 -0.0164836 -0.03918206 -0.02924966 -0.01965856 -0.03866821 0.01212769 -0.01965856 -0.03866821 0.04343777 -0.01658457 -0.03736436 0.03386104 -0.01851433 -0.03808242 0.03527194 -0.0162186 -0.03822278 0.04545688 -0.01990121 -0.03706067 0.03556817 -0.02037483 -0.03810006 0.04506099 -0.0167157 -0.03695458 0.04471468 -0.01036196 -0.03736197 0.03098642 -0.01904642 -0.03857237 0.02440613 -0.01036828 -0.03952068 0.04544812 -0.01350784 -0.03722292 0.05028069 -0.006248116 -0.03677362 0.04578506 -0.006259024 -0.0372976 0.03387492 -0.006193459 -0.03853213 0.04576385 -3.38489e-4 -0.03735619 0.05675166 -0.01742362 -0.03560292 0.05010151 -0.01628649 -0.03660231 0.05511462 -0.01008713 -0.0360369 0.06291007 -0.02174133 -0.03429788 0.06525588 -0.01347994 -0.03412538 0.06880855 -0.01660102 -0.03313195 0.06933575 -0.01073825 -0.03325694 0.07525426 -0.01504355 -0.03114861 0.07827061 -0.02055329 -0.02946984 0.07849609 -0.01211059 -0.02997183 0.08219808 -0.01324224 -0.02805775 0.08030557 -0.02666628 -0.02768188 0.08104383 -0.03447204 -0.02588373 0.07922142 -0.03635907 -0.02678102 0.07613611 -0.02953392 -0.02952349 0.07452619 -0.03776115 -0.02917826 0.0710864 -0.03486365 -0.03101646 0.07090955 -0.03174936 -0.03146505 0.05878895 -0.03281831 -0.03452128 0.06596928 -0.03084415 -0.03305858 0.06489437 -0.03382718 -0.03306829 0.06069701 -0.009148359 -0.0351423 0.03316122 -3.68537e-4 -0.0386455 0.02317214 -0.006182909 -0.03975307 0.02228361 -0.008508861 -0.03984302 0.03387492 0.009631335 -0.03853213 0.02805674 0.003806352 -0.03920429 0.02346909 0.009636402 -0.03971385 0.04520231 0.009746074 -0.03736937 0.04522359 0.003789365 -0.03739571 0.04783082 0.005488038 -0.03709012 0.04958975 0.008760631 -0.03689008 0.04943037 0.004520237 -0.03689652 0.04929876 0.00249195 -0.03692334 0.04491561 0.01367503 -0.03734511 0.04561263 0.02009385 -0.03713721 0.05289983 0.02761554 -0.03595238 0.07730132 0.02936464 -0.02941006 0.07384437 0.02789294 -0.0310142 0.07502943 0.04062223 -0.02906036 0.08103901 0.03790968 -0.02589452 0.07808005 0.0413196 -0.02718406 0.0808959 0.02774024 -0.02764147 0.08236974 0.0305522 -0.02627092 0.07682663 0.02072733 -0.03038513 0.07040762 0.02420288 -0.03246074 0.07646811 0.01526504 -0.03092163 0.06784737 0.02009505 -0.03339695 0.06965905 0.01404362 -0.03316909 0.06338214 0.01922094 -0.03444564 0.06063288 0.01268285 -0.03516125 0.05900973 0.02078837 -0.03523272 0.02361959 0.01370662 -0.03961324 0.02164006 0.003384828 -0.04005587 0.02312606 -3.83691e-4 -0.0398029 0.03388589 0.01380616 -0.03847509 0.03563797 0.01992648 -0.03817659 0.08993482 0.01395362 -0.02179497 0.08750081 0.01385146 -0.02430969 0.08608275 0.01633459 -0.02538222 0.08379113 0.03665137 -0.02395564 0.08659756 0.02350556 -0.02402096 0.08987218 0.02278655 -0.02042204 0.09235107 0.01193457 -0.01844459 0.09133034 0.008607625 -0.02035117 0.09287136 -9.2778e-5 -0.01835495 0.09181541 -0.01088404 -0.01899766 0.09309709 -0.008785367 -0.01712119 0.09313732 -0.01542198 -0.01560705 0.09180968 -0.01946181 -0.01713961 0.09217613 -0.0247671 -0.0143423 0.09036254 -0.02854061 -0.01653879 0.0907008 -0.0335139 -0.01293939 0.08729213 -0.04094868 -0.01587426 0.08944767 -0.040641 -0.01063901 0.08930486 -0.03510308 -0.0153222 0.08835953 -0.03295022 -0.01820003 0.0897926 -0.0243532 -0.01909351 0.09050172 -0.01531994 -0.02022218 0.08838939 -0.02414739 -0.02112495 0.0877093 -0.02088069 -0.02275532 0.08875733 -0.01300221 -0.02276295 0.08989739 7.03423e-4 -0.02237051 0.08971989 -0.007778763 -0.02219456 0.0881738 -0.004232287 -0.02406567 0.08791029 0.007544875 -0.02434235 0.08383083 0.02203476 -0.02641201 0.08121949 0.01629906 -0.02863252 0.05489796 0.01615011 -0.03602355 0.0495969 0.006166934 -0.03661137 0.04942893 -0.00108236 -0.03689837 0.07215023 -0.02089273 -0.03189128 0.08421361 -0.01922249 -0.02604794 0.08669245 -0.01190048 -0.02493667 0.08325421 -0.03338295 -0.02433174 0.08554321 -0.03430902 -0.02177274 0.08424013 -0.02346086 -0.0255382 0.07559615 -0.02275812 -0.03049039 0.06858646 -0.03019839 -0.03237515 0.0567727 -0.02748256 -0.03520154 0.05190223 -0.02675676 -0.03600382 0.04672664 -0.02848345 -0.0366193 0.0532459 -0.03261673 -0.03548395 0.04041677 -0.02602344 -0.03742516 0.07131969 0.03622359 -0.03118723 0.06978124 0.03980493 -0.03131425 0.03495156 0.02337259 -0.03816479 0.0339567 0.02189612 -0.03829264 0.04041123 0.02945917 -0.03742581 0.04672324 0.03191995 -0.03661978 0.05334627 0.03601729 -0.03547197 0.05752921 0.03105115 -0.03505754 0.0585646 0.03757327 -0.03447389 0.06485825 0.03716176 -0.03316587 0.0685507 0.03350782 -0.03238672 0.0449233 0.02334654 -0.03712314 0.09010529 0.03516906 -0.01570397 0.08610534 0.0386579 -0.02073717 0.08641713 0.04147231 -0.01900196 0.08708518 0.0442177 -0.01627016 0.08881288 0.04347759 -0.01310908 0.09200727 0.03379535 -0.01146638 0.09234064 0.02721399 -0.01435565 0.09210538 0.02041995 -0.017277 0.09328049 0.02116805 -0.01456767 0.09370839 0.01210767 -0.01584744 0.08703744 0.0288493 -0.02242678 0.08870345 0.03247439 -0.01922017 0.09030777 0.02878838 -0.01792442 0.08615034 0.04253923 -0.01889705 0.08996063 0.04404568 -0.008903741 0.09263312 0.0347706 -0.008420705 0.09453928 0.02924293 -0.00540626 0.09282326 0.0365979 -0.005433142 0.09385132 0.03451687 -0.002438008 0.09559428 0.02669298 -0.001783728 0.09415555 0.03525942 0.001370966 0.09548699 0.03017723 0.003043591 0.09644716 0.02454483 0.00213772 0.0969116 0.0199247 1.02789e-4 0.09615588 0.02037405 -0.004717648 0.09399163 0.02627146 -0.01011025 0.09514546 0.02299493 -0.007750391 0.09496653 0.01704186 -0.01136809 0.09050387 0.04483401 -0.005048513 0.09245181 0.04042547 -0.001321017 0.09160405 0.04401403 4.49004e-4 0.09297424 0.04047083 0.003331243 0.09776818 0.01292169 0.001356601 0.09707653 0.01117795 -0.004688501 0.09779882 0.005771875 -0.00182116 0.09704542 0.00647372 -0.006235957 0.09751939 0.001223981 -0.004066467 0.09672719 0.001310408 -0.008086919 0.09706979 -0.003727257 -0.005983293 0.09620815 -0.003786385 -0.009723126 0.096363 -0.01072245 -0.007119536 0.09542036 -0.008898198 -0.01140731 0.0950616 -0.01677477 -0.009683907 0.09419745 -0.0158829 -0.01284039 0.09420067 -0.006484329 -0.01508593 0.09548652 -0.001492202 -0.01226103 0.09617364 0.008431911 -0.00955367 0.09599691 0.01664388 -0.007765591 0.09703403 0.01548606 -0.002829492 0.098293 0.005955398 0.002561628 0.09815156 0.001164376 5.69777e-4 0.09825837 -0.003520309 0.002553522 0.0977717 -0.009680926 0.001341223 0.09775936 -0.003996133 -0.001683712 0.09718221 -0.008639395 -0.003778994 0.09703201 -0.01454538 -7.17582e-4 0.09571784 -0.01827627 -0.006057739 0.09630888 -0.01909869 -0.001752972 0.09516507 -0.02399301 -0.003858685 0.09315472 -0.025294 -0.0113517 0.09406054 -0.0255866 -0.007802784 0.09162378 -0.03389042 -0.009766399 0.09633922 -0.02139627 0.001718461 0.09497982 -0.02815997 0.001009523 0.09237712 -0.03424632 -0.006249129 0.09383296 -0.03062248 -0.003281354 0.09339731 -0.03497534 0.001944601 0.09160405 -0.04057615 4.49004e-4 0.09160399 -0.03858119 -0.003658771 0.08615034 -0.03910142 -0.01889705 0.08649337 -0.03664666 -0.01952922 0.09135472 -0.001340985 -0.02050906 0.09373116 0.002658665 -0.01661932 0.09520012 0.007901906 -0.01280868 0.09468752 6.97775e-4 -0.01457166 0.05398523 0.01187258 -0.03621494 0.09435307 0.01488912 -0.01383042 0.04504334 -0.009866297 -0.0368449 0.04403406 -0.006693422 -0.03698277 0.02399873 -0.006694257 -0.03913742 0.0244866 -0.009868025 -0.03899508 0.04502838 1.33548e-4 -0.03692573 0.04403835 0.003306388 -0.03702288 0.02322524 0.003306686 -0.03929412 0.02249711 1.32643e-4 -0.03934568 0.04403132 0.01330626 -0.03694367 0.02442932 0.01330703 -0.03900659 0.0244131 0.01013189 -0.03907006 0.04403781 0.01013129 -0.03698021 0.06254816 -0.03568392 -0.03343152 0.06623154 -0.03593164 -0.03210908 0.06795781 -0.03683543 -0.03176939 0.0695753 -0.0396865 -0.03015244 0.07858014 -0.03984957 -0.0261442 0.07353508 -0.04096072 -0.02808684 0.07539814 -0.04177963 -0.02667349 0.0780301 -0.04304766 -0.02399814 0.08343869 -0.04185384 -0.02064371 0.08335638 -0.04337722 -0.01878356 0.08074283 -0.04469424 -0.01927369 0.08344596 -0.04535007 -0.01453387 0.08338457 -0.04618805 -0.01116883 0.08653777 -0.04557394 -0.00677967 0.08427697 -0.04650193 -0.007573008 0.08610594 -0.04659992 -1.44928e-4 0.0874257 -0.04355829 -0.01137304 0.09023249 -0.04241937 -0.00376439 0.08874696 -0.04421895 -0.004235923 0.08568167 -0.04000258 -0.01908153 0.07876318 -0.0441752 -0.0217626 0.06857877 -0.03643035 -0.0288515 0.07089078 -0.03471499 -0.02885413 0.07084405 -0.03197503 -0.02885329 0.06868535 -0.03036922 -0.02885377 0.06617671 -0.03102034 -0.02885228 0.06505423 -0.03334444 -0.02885538 0.06607782 -0.03568631 -0.02885615 0.06568181 0.03475803 -0.03251093 0.07930505 0.04434293 -0.02507293 0.07996761 0.04725933 -0.02160155 0.08434373 0.0453791 -0.01937043 0.07533013 0.04568517 -0.02622568 0.07395291 0.04419839 -0.02811998 0.06643223 0.04077386 -0.03213143 0.06666165 0.03979271 -0.03197985 0.06970268 0.04309111 -0.03014177 0.07242995 0.04882758 -0.02353525 0.0807138 0.04819935 -0.01916277 0.08331692 0.04868358 -0.01504993 0.08840078 0.04610973 -0.01038253 0.08598905 0.0474044 -0.01361674 0.08400779 0.04944473 -0.0108397 0.0877915 0.04804646 -0.006793081 0.08956825 0.04729026 -0.001876533 0.08741182 0.04936301 -9.52201e-4 0.08427697 0.04993981 -0.007573008 0.08210515 0.05128276 -0.003242254 0.08455926 0.04427999 -0.02010077 0.0672571 0.0398215 -0.02900189 0.06533384 0.03806871 -0.02885288 0.06536841 0.03543579 -0.02888441 0.0681023 0.03363788 -0.02889341 0.07085186 0.03542548 -0.02885496 0.07050186 0.03898185 -0.02887153 -0.05580627 -0.01952034 -0.03782963 -0.05725896 -0.01955729 -0.03450781 -0.055803 -0.01907026 -0.03624922 -0.05580145 -0.008010923 -0.03623771 -0.05580145 -0.008010923 -0.03786563 -0.0564751 -0.00701642 -0.03761506 -0.05701094 -0.006993114 -0.03492939 -0.05873781 -0.007011115 -0.03458768 -0.06018394 -0.007011115 -0.03492861 -0.06101822 -0.007010936 -0.03617537 -0.05728703 -0.00702548 -0.03353387 -0.0576536 -0.007010936 -0.03274273 -0.05810874 -0.007255434 -0.03223955 -0.06183511 -0.007011711 -0.03593331 -0.06094211 -0.007010936 -0.03226822 -0.06145417 -0.007027804 -0.03282308 -0.06176298 -0.007010936 -0.0335496 -0.05580526 0.0104807 -0.03786218 -0.05689859 0.01043403 -0.03518062 -0.05580276 0.01122319 -0.03623783 -0.05580145 0.02198863 -0.03623771 -0.0558114 0.02295541 -0.03782778 -0.05713576 0.02301311 -0.03466415 -0.05873215 0.02298557 -0.03457617 -0.06015694 0.02299046 -0.03493332 -0.0573498 0.02298861 -0.03333055 -0.0576536 0.02298861 -0.03274273 -0.05810785 0.02298861 -0.03226822 -0.06161206 0.02298885 -0.03310036 -0.06083351 0.02298861 -0.03267347 0.00267452 0.04724699 -0.02699548 0.002171933 0.04019778 -0.03331387 0.006919562 0.04392832 -0.03136944 -6.41396e-5 0.04284882 -0.02685868 0.002652168 0.0403909 -0.02686506 0.006320178 0.04229992 -0.02685928 0.006275475 0.04559314 -0.02685499 0.004991292 -0.03736066 -0.03295534 0.002172827 -0.03696101 -0.03307288 -2.83139e-4 -0.03937613 -0.03190481 0.001815438 -0.04358118 -0.02693361 -2.08224e-4 -0.04064941 -0.02685785 0.002648591 -0.0369516 -0.02685457 0.006808102 -0.0391575 -0.02685439 0.004615783 -0.04375344 -0.02685707 0.003391742 -0.04424405 -0.02285134 -2.59859e-4 -0.04201221 -0.0228058 0.001896202 -0.04502093 -0.02491784 0.005180299 -0.04472661 -0.0250228 -9.09461e-4 -0.041709 -0.02767658 -5.94881e-4 -0.03856915 -0.03011566 6.26972e-4 -0.03773975 -0.02283215 0.00290209 -0.03607702 -0.03211635 0.005706787 -0.03676617 -0.03139382 0.007425785 -0.03922313 -0.02988582 0.007469832 -0.04151183 -0.02781248 0.006866395 -0.04191201 -0.022803 0.001113295 -0.03937184 -0.02282816 -4.12514e-4 -0.0397737 -0.02284264 0.002536833 -0.03676414 -0.02284264 0.003233313 -0.03821694 -0.02277553 0.004018545 -0.03676414 -0.02284264 0.005298972 -0.03911215 -0.02285796 0.005384624 -0.03733807 -0.02284264 0.006777882 -0.03894227 -0.02284532 0.00220257 -0.04261112 -0.02284973 0.006981253 0.0422427 -0.0230925 0.007555603 0.0430873 -0.02997118 0.007286369 0.04377675 -0.0230925 0.006087541 0.04036486 -0.0316841 0.006112277 0.04094219 -0.0230925 0.004811763 0.04007321 -0.0230925 0.003321707 0.03976404 -0.02309775 0.006857395 0.0461387 -0.02697104 0.00668025 0.04598957 -0.02305948 0.003928303 0.04848021 -0.02459144 8.73241e-4 0.04713261 -0.02309459 -4.258e-4 0.0422427 -0.0230925 -9.46834e-4 0.04432272 -0.02812618 2.33315e-4 0.04061448 -0.03140872 0.001743674 0.04007321 -0.0230925 4.43176e-4 0.04094219 -0.0230925 0.002608776 0.03950202 -0.03185111 -4.683e-4 0.04413217 -0.02278655 0.001017212 0.04427671 -0.02280598 0.002594113 0.04597544 -0.02281111 0.005292713 0.04511207 -0.02284193 0.004872679 0.04205703 -0.02283829 0.002627849 0.04136592 -0.02282208 0.00170964 0.0420826 -0.0228334 5.42056e-4 0.04773896 -0.02585107 0.004524648 -0.0386402 -0.02686911 0.005264341 -0.04109835 -0.02685832 0.001886367 -0.03887695 -0.0268594 0.001228153 -0.04086351 -0.02685832 0.003097832 -0.04262262 -0.02686673 0.005257666 0.04471218 -0.02686738 0.002854347 0.04582631 -0.02685809 0.001291096 0.0444349 -0.02685832 0.002030789 0.0419768 -0.02686917 0.00466901 0.04221349 -0.0268594 -0.0529071 0.03982061 -0.02236145 -0.05335986 0.03899592 -0.02261263 -0.05273073 0.03903514 -0.02275633 -0.05174541 0.0358662 -0.02284264 -0.05112272 0.03640973 -0.02304089 -0.04980462 0.03638792 -0.02284264 -0.04842776 0.03601473 -0.02284264 -0.04717487 0.03490096 -0.02283829 -0.04687225 0.03144222 -0.02284717 -0.04898965 0.02972865 -0.02284771 -0.05274957 0.03485298 -0.02284264 -0.05323231 0.03351062 -0.02284264 -0.05304425 0.03188198 -0.02283376 -0.0503748 0.02961635 -0.02284848 -0.0521472 0.03615152 -0.02583587 -0.05126512 0.03676539 -0.0274049 -0.0530166 -0.03616273 -0.02222496 -0.05334734 -0.03516978 -0.02298796 -0.05215978 -0.03273284 -0.02609741 -0.05201256 -0.03250813 -0.02304089 -0.0526843 -0.03596806 -0.02299404 -0.05256628 0.03674077 -0.03372353 -0.05357903 0.03564834 -0.03340399 -0.05432194 0.03444403 -0.034747 -0.05448043 0.03288769 -0.03451651 -0.05419462 0.03143692 -0.034814 -0.05356568 0.03012758 -0.03606212 -0.05170381 0.0300374 -0.0230419 -0.05232745 0.02908933 -0.03598719 -0.05086898 0.02855181 -0.03575992 -0.04784536 0.02898484 -0.03563028 -0.04774636 0.03035736 -0.0230419 -0.04660874 0.02990478 -0.03568482 -0.04645615 0.03277248 -0.0230419 -0.0454508 0.03263449 -0.03462904 -0.04718655 0.03655844 -0.03337985 -0.04916876 0.03741627 -0.03247606 -0.05455267 0.02823919 -0.03645497 -0.05716973 0.03560352 -0.03426605 -0.05646991 0.03104948 -0.03574299 -0.04906761 0.04472672 -0.02978926 -0.05037629 0.03161692 -0.02874445 -0.0514118 0.03256303 -0.02880495 -0.05143129 0.03394156 -0.02885508 -0.05080902 0.03456377 -0.02885508 -0.04963904 0.03457778 -0.02874356 -0.04848682 0.03394156 -0.02885508 -0.04843527 0.03236579 -0.02877354 -0.0491091 0.03161936 -0.02885508 -0.04767036 0.04520285 -0.03010326 -0.05866956 0.03987544 -0.03379505 -0.05951189 0.04025989 -0.03310495 -0.06050223 0.0395587 -0.03419262 -0.04812401 0.03533226 -0.02885687 -0.04720348 0.03206372 -0.0291956 -0.04928284 0.03029656 -0.02891969 -0.05264222 0.03216826 -0.02890378 -0.05260217 0.03431797 -0.02918827 -0.05105668 0.03580373 -0.02897542 -0.05134218 0.03060692 -0.03020751 -0.04832231 0.03556007 -0.03008615 -0.05046814 0.03621464 -0.03508341 -0.04770523 0.03517758 -0.03541809 -0.04685264 0.03301578 -0.03602015 -0.04863005 0.0303151 -0.03691309 -0.05112272 -0.03297191 -0.02304089 -0.04722583 -0.03306394 -0.03279 -0.04839038 -0.03280192 -0.0230419 -0.04728871 -0.03194308 -0.0230419 -0.04622453 -0.03198146 -0.03313678 -0.0466082 -0.03072321 -0.0230419 -0.04647094 -0.02933526 -0.02287793 -0.04545056 -0.02919375 -0.03463584 -0.04685664 -0.02799636 -0.0230419 -0.04663354 -0.02648586 -0.03533476 -0.04775768 -0.02693289 -0.02284771 -0.04783225 -0.02552449 -0.03592503 -0.04898512 -0.02627384 -0.0230419 -0.0493167 -0.02506721 -0.03577369 -0.0503748 -0.02617841 -0.02284973 -0.051696 -0.02661216 -0.0228765 -0.05230712 -0.02568048 -0.03558951 -0.05347919 -0.02666556 -0.03561401 -0.05275499 -0.02751952 -0.0230419 -0.05336517 -0.02877604 -0.0230419 -0.05445319 -0.02945494 -0.03425627 -0.05343818 -0.03017103 -0.0230419 -0.05422604 -0.03089839 -0.03364211 -0.05296248 -0.03148442 -0.0230419 -0.05354464 -0.03218954 -0.03303498 -0.04973948 -0.0331642 -0.0230419 -0.04995268 -0.03402441 -0.03262835 -0.05437761 -0.03252506 -0.03412455 -0.05070406 -0.02836328 -0.02885508 -0.05124944 -0.02890866 -0.02885508 -0.05144906 -0.02965372 -0.02885508 -0.05070406 -0.0309441 -0.02885508 -0.04921406 -0.0309441 -0.02885508 -0.048469 -0.02965372 -0.02885508 -0.04921406 -0.02836328 -0.02885508 -0.04995906 -0.02816367 -0.02885508 -0.05124944 -0.03039872 -0.02885508 -0.04995906 -0.03114372 -0.02885508 -0.04866868 -0.03039872 -0.02885508 -0.04866868 -0.02890866 -0.02885508 -0.05067372 -0.03262567 -0.02894628 -0.0527628 -0.03036624 -0.02885442 -0.05217283 -0.02783799 -0.02885395 -0.05072033 -0.0268253 -0.02907866 -0.0470972 -0.0291047 -0.0290144 -0.04748386 -0.0314536 -0.02911955 0.04820615 0.05866611 -0.01326024 0.03671938 0.05546218 -0.01279824 0.02964484 0.05395716 -0.01443749 0.02261137 0.05300599 -0.01433449 0.01607501 0.05243784 -0.01477485 0.009021699 0.05212968 -0.01603597 0.001813888 0.05234706 -0.01491868 -0.005363345 0.05280649 -0.01526558 -0.001220762 0.05327606 -0.003996253 -0.008188068 0.05384135 -0.004543602 -0.006127178 0.05438148 0.006144404 -0.01137739 0.05497276 0.006144404 0.005828261 0.05291742 -0.005023241 0.01234459 0.05296248 -0.004966557 0.0141738 0.05380684 0.006144404 0.01923948 0.05343115 -0.003736019 0.01907402 0.05411088 0.006144404 0.02390432 0.05459398 0.006144404 0.02623534 0.05414837 -0.004427075 0.02866452 0.05525618 0.006144404 0.03312981 0.05537194 -0.003405928 0.04002177 0.05695408 -0.003247201 0.03797501 0.0571177 0.006144404 0.03335475 0.05609738 0.006144404 0.04252523 0.05831706 0.006144404 0.04686522 0.05898702 -0.00285542 0.04822182 0.05928301 -0.004853785 -0.0122714 0.05366271 -0.01409208 -0.01864916 0.05468308 -0.01337116 -0.02563619 0.05603194 -0.01310205 -0.03270977 0.05730783 -0.01785039 -0.01454538 0.05469131 -0.004040241 -0.01669764 0.05574315 0.006144404 -0.02079331 0.05573767 -0.003866255 -0.02721369 0.05702018 -0.004012763 -0.02754819 0.05782115 0.006144404 -0.03398424 0.05794882 -0.01338768 -0.03414011 0.05858802 -0.004860877 -0.03279995 0.05841046 -0.00285542 -0.03307849 0.05912876 0.006144404 0.04700547 0.05969554 0.006144404 -0.04550975 -0.04048389 -0.03019493 -0.04997563 -0.03287655 -0.03502559 -0.04930472 -0.02659279 -0.03700387 0.08475458 -0.04177844 -0.01170128 0.0872308 -0.04154872 -0.01053261 0.08590275 -0.04092341 -0.01050293 0.08818507 -0.03880709 -0.01087486 0.08700042 -0.03877985 -0.01017045 0.08391773 -0.04343217 -0.01351875 0.08383673 -0.0421741 -0.01228708 0.08376526 -0.04498422 -0.007812142 0.08357846 -0.04582363 -0.00173974 0.08317726 -0.04166179 0.006144404 0.08332496 -0.04651588 0.006145477 0.08439773 -0.04126173 0.006144404 0.08616322 -0.03944206 0.006144404 0.08542847 -0.04049551 0.006144404 0.08652627 -0.03821015 0.006144404 0.08663803 0.04328507 -0.01016962 0.08705592 0.04513561 -0.01051044 0.08601903 0.04425251 -0.01034164 0.08700042 0.04221773 -0.01017045 0.08388113 0.04727452 -0.01212191 0.08386224 0.04563081 -0.01299148 0.08473736 0.04520452 -0.0111826 0.08372455 0.04862666 -0.006470382 0.08317744 0.04510551 0.006144404 0.0833258 0.0499947 0.006140291 0.08661824 0.04670065 -0.007377147 0.08620196 0.04813355 -0.001665115 0.08654314 0.04855519 0.006141841 0.08947449 0.04417616 -0.002925872 0.08935755 0.04604971 0.006143391 0.09133827 0.04164904 0.006145894 0.08856379 0.04600262 -0.001034796 0.08885377 0.04218262 -0.009170413 0.09053927 0.04188048 -5.12571e-4 0.08623617 0.03791797 -0.01683419 0.08496266 0.03691488 -0.01873052 0.08264875 0.03612989 -0.02257728 0.08151936 0.03619074 -0.02350085 0.08022385 0.03665512 -0.02429497 0.07756739 0.04006451 -0.02554523 0.07855385 0.03799229 -0.02529853 0.08705163 0.04001289 -0.01204293 0.08663594 0.0387867 -0.01426041 0.07797789 0.04419237 -0.02376812 0.08001661 0.04530966 -0.01894474 0.08140313 0.04694342 -0.01725906 0.07874196 0.04433852 -0.02174443 0.07818257 0.04360806 -0.02304702 0.07772958 0.04266238 -0.02421271 0.08142185 0.04578626 -0.01605921 0.08074814 0.04471522 0.006144404 0.08217781 0.04513198 0.006144404 0.0795691 0.04380655 0.006144404 0.07880395 0.04252964 0.006144404 0.07855868 0.04106146 0.006144404 0.07886725 0.0396052 0.006144404 0.07968693 0.03836262 0.006144404 0.08090418 0.0375058 0.006144404 0.08235043 0.03715342 0.006144404 0.0838254 0.03735423 0.006144404 0.08512479 0.03808051 0.006144404 0.08606863 0.03923153 0.006144404 0.08653199 0.04064798 0.006144285 0.08906728 -0.03670662 -0.008273661 0.08732867 -0.03648459 -0.01291197 0.07738834 -0.03796786 -0.02560722 0.07769274 -0.03920006 -0.0249927 0.07830828 -0.04056698 -0.02359557 0.07881051 -0.04106336 -0.02194392 0.08001661 -0.04187178 -0.01894474 0.08137559 -0.04323297 -0.0176571 0.08142185 -0.04234838 -0.01605921 0.08642786 -0.0349738 -0.01504141 0.07920616 -0.03387212 -0.02522224 0.07846754 -0.03457558 -0.02558112 0.07778096 -0.03587049 -0.02566421 0.07985746 -0.03340446 -0.02465957 0.08071017 -0.03296798 -0.02417182 0.08594876 -0.03417277 -0.01733559 0.08348411 -0.03273254 -0.02165156 0.08666127 -0.03716558 0.006144344 -0.06180047 0.01045936 -0.03366243 -0.06144315 0.01044642 -0.03280502 -0.06094211 0.00435394 -0.03226822 -0.06094211 0.01044881 -0.03226822 -0.06094211 -9.16096e-4 -0.03226822 -0.05952501 0.004324734 -0.03171062 -0.05952495 -8.89017e-4 -0.03175151 -0.05810785 -9.16096e-4 -0.03226822 -0.05810785 0.00435394 -0.03226822 -0.05770927 0.01045554 -0.03266984 -0.05735194 0.01044881 -0.0333262 -0.05813026 0.01056653 -0.03234982 -0.04642403 -0.03631538 -0.0211746 -0.04735875 -0.03798514 -0.03086692 -0.04673314 -0.03789073 -0.02180975 -0.04133993 -0.04098606 -0.02160769 0.05802452 0.04650801 -0.0277307 0.05752944 0.04493618 -0.02128398 -0.04729986 0.04131132 -0.03030794 -0.04681652 0.04052346 -0.02128082 -0.04681754 0.04118007 -0.02219879 -0.04641073 0.03975874 -0.02126342 -0.04017686 -0.03992021 -0.02125644 -0.04095917 -0.04157012 -0.02866327 -0.0369656 -0.0482645 -0.02306306 0.06361562 -0.04115188 -0.02770912 0.06393808 -0.04035264 -0.02921628 0.05808156 -0.04317474 -0.02720016 0.06549382 -0.03818905 -0.03023737 0.06359535 -0.03912788 -0.02998483 0.05847436 -0.0493294 -0.02242106 0.06806898 -0.04549491 -0.02291256 0.06475615 -0.04972261 -0.01689255 0.0663973 -0.04754024 -0.02051585 0.0558651 -0.05377042 -0.01454198 0.06676286 -0.05076307 -0.01042634 0.05439996 -0.05519151 -0.01076424 0.07939648 -0.04707968 -0.004880666 0.07493478 -0.04866242 -0.004855394 0.08178889 -0.04565989 -0.008416593 0.08156335 -0.04639738 -0.003663301 0.08181744 -0.04704815 0.006130754 0.08196437 -0.04621785 -0.003876984 0.08233314 -0.04683566 0.006144404 0.073628 -0.04048252 -0.02648514 0.06760418 -0.04366165 -0.02552306 0.07864791 -0.04420149 -0.01816636 0.08155655 -0.04454958 -0.01409339 0.05181854 -0.0571317 -0.004852652 0.05392318 -0.05630999 -0.004855394 0.07672733 -0.04285502 -0.02219897 0.08577328 -0.01599317 -0.02132451 0.08565127 -0.02234321 -0.02138775 0.06341254 -0.04098159 -0.0219835 0.06329226 -0.03940045 -0.02131098 0.05801457 -0.04291856 -0.02152538 0.05751574 -0.04150366 -0.02131307 0.0858159 0.01982975 -0.02127528 -0.04061317 0.0440436 -0.02132385 -0.04123598 0.04484587 -0.02835327 -0.0415734 0.04432195 -0.02196139 -0.04215914 0.04515272 -0.02910262 -0.04018729 0.043352 -0.02125751 0.06410098 0.04406082 -0.02896654 0.06570541 0.04580664 -0.02731817 0.06339949 0.0447399 -0.02840739 0.06328767 0.04284065 -0.0212748 0.063308 0.0444113 -0.02151328 0.05812913 0.04616791 -0.02153366 0.06362456 0.0425502 -0.03004097 0.06052339 0.04881066 -0.02841413 0.05963867 0.05179411 -0.02578115 0.05850774 0.05405032 -0.02327418 0.06819367 0.05164545 -0.02141118 0.05833435 0.05610406 -0.01970225 0.0710209 0.05244112 -0.01727092 0.05638778 0.05842059 -0.01538556 0.07054287 0.05439686 -0.0106886 0.05473107 0.05992025 -0.0118016 0.05394196 0.06066 -0.009519577 0.05437767 0.06118893 -0.004855394 0.0513423 0.06219327 -0.0048545 0.05706149 0.05980461 -0.007839798 0.06812351 0.05442637 -0.01426869 0.07551294 0.05349636 -0.004855394 0.08091706 0.05153095 -0.00484842 0.0725708 0.05416226 -0.007841289 0.06921052 0.05225127 -0.01940655 0.08233255 0.05190283 0.006133556 0.0515002 0.06139659 -0.009126245 0.05037069 0.06040054 -0.01265412 0.06782543 0.04108273 -0.02983295 0.07261008 0.04308915 -0.02740901 0.05934023 0.050767 -0.02476352 0.07383769 0.04464054 -0.02565503 0.06825333 0.04825145 -0.02377462 0.0571376 0.05476886 -0.01968479 0.06854736 0.04962128 -0.02154958 0.06718975 0.05175858 -0.01825457 0.07643997 0.05103498 -0.008474707 0.07494127 0.05210888 -0.004855394 0.07671928 0.04553776 -0.02321654 0.07781839 0.04703289 -0.02016824 0.07039994 0.05232167 -0.01290136 0.08157932 0.04810315 -0.01355767 0.08192765 0.04959958 -0.004839301 0.06824302 0.05222648 -0.01596403 0.08196473 0.04965674 -0.00386703 0.08156329 0.04983514 -0.003663182 0.08181744 0.05048596 0.006130754 0.08233314 0.05027353 0.006144404 0.06752169 0.0540409 -0.009827077 0.05361986 0.05901789 -0.01030808 0.05392318 0.05974787 -0.004855394 0.05173724 0.06050884 -0.004855036 0.05481952 0.05744987 -0.01496785 0.07907825 0.04186338 -0.0254954 0.07900667 0.04091233 -0.02587246 0.08007234 0.04364377 -0.0237742 0.08096754 0.04426819 -0.02261751 0.07942944 0.0428043 -0.02477502 0.08205562 0.04459291 -0.02143108 0.0839743 0.04429644 -0.01977813 0.08523762 0.04330259 -0.01898711 0.08330845 0.04452705 -0.02029311 0.07927465 0.03981375 -0.02593767 0.08000439 0.03869742 -0.02562767 0.08282065 0.03764152 -0.02343738 0.08419924 0.03806787 -0.02194488 0.08530229 0.03903436 -0.02044665 0.08613562 0.04017168 -0.0195176 0.08125609 0.04385089 0.006144404 0.0819534 0.04434657 -0.008475959 0.08255767 0.04414796 0.006144404 0.08078217 0.04386287 -0.007832407 0.08021223 0.04301846 0.006144404 0.08385932 0.04385089 0.006144404 0.08454596 0.04368615 -0.006701886 0.08490318 0.04301846 0.006144404 0.08539247 0.04264163 -0.005557179 0.08547425 0.04182863 0.006146728 0.08548241 0.04048043 0.006144404 0.08547818 0.03977435 -0.006884813 0.08490318 0.03927755 0.006144404 0.08444321 0.03851473 -0.00753349 0.08330887 0.03798621 -0.008168041 0.08199113 0.0379374 -0.008765697 0.08079397 0.03839641 -0.009230136 0.08021897 0.03928458 0.006141126 0.07947897 0.0400325 -0.009587824 0.07929295 0.04124695 -0.009111642 0.07956564 0.04249155 -0.009892225 0.07963293 0.04181557 0.006144404 0.07963293 0.04048043 0.006144404 0.08125609 0.03844511 0.006144404 0.08259403 0.0381385 0.005779266 0.08385932 0.03844511 0.006144404 0.08653092 0.04164803 0.006144404 0.05816048 0.01301354 -0.02718502 0.05894142 0.008584678 -0.02284216 0.05870515 0.00992465 -0.02305281 0.05849099 0.01113915 -0.02366495 0.05831897 0.01211452 -0.02462142 0.05739653 0.01260489 -0.02580827 0.0823543 -4.02357e-4 -0.02284193 0.08398598 0.001926481 -0.02284145 0.0813964 0.003729104 -0.0228421 0.06723713 0.003724873 -0.02284216 0.07981204 0.002380371 -0.02270436 0.06899273 0.002129614 -0.02284932 0.08006685 6.09233e-4 -0.02284508 0.06723713 -2.87015e-4 -0.02284216 0.05894142 -0.005146801 -0.02284216 0.06475716 4.37545e-4 -0.02284204 0.06506276 0.003202319 -0.02284222 0.05816048 -0.009575664 -0.02718502 0.05739784 -0.009167253 -0.02580869 0.05831897 -0.008676648 -0.02462142 0.05849099 -0.007701277 -0.02366495 0.05870515 -0.006486773 -0.02305281 0.08318006 8.09086e-5 -0.02434211 0.08355695 0.003298878 -0.02434784 0.07942187 0.002514302 -0.02434533 0.08116191 -2.87015e-4 -0.02434211 0.05842077 -0.008099377 -0.02723741 0.08352684 -0.01250457 -0.02664119 0.07058894 -0.0104078 -0.03183001 0.05333292 -0.007490992 -0.03537964 0.05211561 -0.007145106 -0.03567618 0.07858043 -0.03728485 0.006144404 0.07872366 -0.03885018 0.006144404 0.07945895 -0.04023945 0.006144404 0.0806728 -0.04123812 0.006144404 0.08217781 -0.0416941 0.006144404 0.07905143 -0.03578513 0.006144404 0.08006387 -0.03458279 0.006144404 0.08146142 -0.03386336 0.006144404 0.08302831 -0.03373795 0.006144404 0.08452248 -0.034226 0.006144404 0.08571326 -0.03525209 0.006144404 0.07901704 -0.03734701 -0.02589702 0.07952523 -0.03953027 -0.02461069 0.07910597 -0.03854382 -0.02542418 0.08025693 -0.04037111 -0.0235185 0.08121323 -0.04093837 -0.02233135 0.08235788 -0.04118055 -0.02113562 0.08358687 -0.04101097 -0.02007031 0.0600146 -0.04689925 -0.02718216 0.06049591 -0.04834377 -0.02540147 0.05849236 -0.05075484 -0.02307736 0.05720418 -0.052652 -0.02052795 0.05770969 -0.05340182 -0.01845628 0.07272809 -0.04860502 -0.01663541 0.05496376 -0.05630373 -0.01235997 0.07257223 -0.05073684 -0.007844626 0.05706149 -0.05636674 -0.007839798 0.08199506 -0.04771798 -0.004800021 0.07551294 -0.05005848 -0.004855394 0.08233255 -0.04846495 0.006133556 0.05142533 -0.05882561 -0.004856407 0.05437767 -0.05775105 -0.004855394 0.05665361 -0.05458545 -0.01625418 -0.03042775 0.04516363 -0.030065 -0.03413116 0.04572552 -0.02888351 -0.03355377 0.03995025 -0.03350472 -0.02955716 0.04264891 -0.0290246 -0.03128057 0.04587912 -0.02885431 -0.03546166 0.044128 -0.03000211 -0.03560507 0.04306304 -0.02885413 -0.03161579 0.04011577 -0.02910327 -0.03474986 0.04084581 -0.02891951 -0.0313484 0.04234641 -0.02885508 -0.03114879 0.04309141 -0.02885508 -0.03263878 0.04160141 -0.02885508 -0.03392916 0.04234641 -0.02885508 -0.03338378 0.04180103 -0.02885508 -0.03412878 0.04309141 -0.02885508 -0.03392916 0.04383647 -0.02885508 -0.03338378 0.04438185 -0.02885508 -0.03263878 0.04458147 -0.02885508 -0.0313484 0.04383647 -0.02885508 -0.03189378 0.04438185 -0.02885508 -0.03189378 0.04180103 -0.02885508 -0.03332489 0.03986358 -0.02284264 -0.03457844 0.04042172 -0.02284264 -0.03549665 0.04144144 -0.02284264 -0.03598159 0.04338651 -0.02282994 -0.03417205 0.04623562 -0.022821 -0.03053438 0.04571956 -0.02283757 -0.02929049 0.04332965 -0.02282929 -0.02978092 0.04144144 -0.02284264 -0.03069913 0.04042172 -0.02284264 -0.03195267 0.03986358 -0.02284264 -0.05810785 0.02896857 -0.03226822 -0.05916905 0.02891361 -0.03180778 -0.06031429 0.02896857 -0.03191947 -0.06101596 0.02891784 -0.0323435 -0.03219825 0.04710793 -0.02702105 -0.03017586 0.04620915 -0.02769446 -0.02864563 0.04146617 -0.03120523 -0.02852255 0.04356586 -0.02993917 -0.03113698 0.03903949 -0.03223061 -0.03241878 0.03878617 -0.03236728 -0.03623193 0.04069137 -0.03165394 -0.03650128 0.04455327 -0.02900582 0.06743323 0.03359782 -0.02284264 0.06617969 0.0341559 -0.02284264 0.06526154 0.03517568 -0.02284264 0.06483751 0.03648072 -0.02284264 0.06566184 0.03903162 -0.02286088 0.06755489 0.04006552 -0.02285939 0.0700311 0.03961336 -0.02283364 0.06498092 0.03784537 -0.02284264 0.07129728 0.03572487 -0.02283346 0.0694186 0.03371804 -0.02282911 0.07120621 0.03805774 -0.02290445 0.07023113 0.04023855 -0.02813684 0.06583946 0.04025238 -0.02974408 0.06419444 0.03859299 -0.03154736 0.06659418 0.03287196 -0.0309717 0.0684719 0.03265565 -0.03031098 0.07212746 0.03641039 -0.02815586 0.05155104 0.04576593 -0.0289421 0.04682064 0.04528653 -0.02996462 0.05224877 0.04386198 -0.02885037 0.04815471 0.04652738 -0.02895456 0.04626172 0.04281979 -0.0291168 0.05195683 0.04200071 -0.02895432 0.04861783 0.04069215 -0.03004789 0.04871022 0.04081714 -0.02885961 0.05061614 0.04292094 -0.02885508 0.05081576 0.04366594 -0.02885508 0.04932576 0.04217594 -0.02885508 0.04803538 0.04292094 -0.02885508 0.0478357 0.04366594 -0.02885508 0.04803538 0.044411 -0.02885508 0.04932576 0.045156 -0.02885508 0.04858076 0.04495638 -0.02885508 0.05007076 0.04495638 -0.02885508 0.05061614 0.044411 -0.02885508 0.05007076 0.04237556 -0.02885508 0.04858076 0.04237556 -0.02885508 0.08616322 0.04287993 0.006144404 0.08542847 0.04393339 0.006144404 0.08439773 0.0446996 0.006144404 0.0473861 0.04099625 -0.02284264 0.04863965 0.04043811 -0.02284264 0.0464679 0.04201596 -0.02284264 0.04598093 0.04393523 -0.02283084 0.0477451 0.04678755 -0.02282524 0.05143433 0.04628962 -0.02283805 0.05267339 0.04390358 -0.02283042 0.05218356 0.04201596 -0.02284264 0.05126541 0.04099625 -0.02284264 0.05001187 0.04043811 -0.02284264 0.05076402 0.04739826 -0.02608817 0.05284249 0.0412063 -0.03133255 0.04965263 0.03931999 -0.0323792 0.04752975 0.03969967 -0.03210628 0.04740571 0.0470978 -0.02670997 0.09137731 -0.03821063 0.006141066 0.08548241 -0.0383777 0.006144404 0.08490318 -0.03958058 0.006144404 0.08385932 -0.04041302 0.006144404 0.08255767 -0.04071009 0.006144404 0.08125609 -0.04041302 0.006144404 0.08021223 -0.03958058 0.006144404 0.07963293 -0.0383777 0.006144404 0.07963293 -0.03704255 0.006144404 0.09006828 -0.04146832 0.006141006 0.08778101 -0.04426103 0.006143689 0.08550959 -0.03712165 0.006141424 0.08490318 -0.03583967 0.006144404 0.08385932 -0.03500723 0.006144404 0.08255767 -0.03471016 0.006144404 0.08125609 -0.03500723 0.006144404 0.08021986 -0.03584539 0.006139338 0.0800246 -0.03523904 -0.02561634 0.08279091 -0.03420108 -0.02346628 0.08414411 -0.03459995 -0.02201116 0.08564841 -0.03616821 -0.01986688 0.08591282 -0.03693187 -0.01930832 0.08525145 -0.03552997 -0.02052515 0.08599001 -0.03788977 -0.01889312 0.08327984 -0.04075598 -0.001323163 0.0844748 -0.04030209 -0.006682991 0.08528566 -0.03939485 -0.005675315 0.0845803 -0.03518342 -0.007409155 0.08315271 -0.03451472 -0.008199036 0.08194208 -0.03450912 -0.008735895 0.08078473 -0.03496509 -0.009201645 0.07947558 -0.03660196 -0.009628593 0.07929134 -0.03784638 -0.009280681 0.07960045 -0.03913158 -0.009964942 0.08107084 -0.04056042 -0.006161332 0.08210372 -0.04093235 -0.00841248 0.0894261 -0.0386604 -0.006749272 0.08516252 0.01589334 -0.02577471 0.08588355 0.01567894 -0.02531194 0.08676433 0.01478105 -0.02461028 0.08361423 0.01595145 -0.02662914 0.05894142 -0.005146801 -0.02434211 0.06723713 -2.87015e-4 -0.02434211 0.08707875 -0.01010817 -0.02434211 0.06506162 2.38313e-4 -0.02434211 0.06478697 0.00301516 -0.02434211 0.05894142 0.008584678 -0.02434211 0.06723713 0.003724873 -0.02434211 0.06900417 0.001552641 -0.02434211 -0.0297271 -0.03901851 -0.03042244 -0.0333628 -0.03655433 -0.03347611 -0.03084611 -0.04121994 -0.03036713 -0.02967423 -0.03978967 -0.0288527 -0.03064662 -0.03748607 -0.02885085 -0.03526169 -0.0380966 -0.02929711 -0.03251457 -0.0365591 -0.02921009 -0.03553664 -0.04085552 -0.02905136 -0.0320549 -0.04281961 -0.02894169 -0.0313484 -0.04039859 -0.02885508 -0.03189378 -0.04094398 -0.02885508 -0.03338378 -0.04094398 -0.02885508 -0.03412878 -0.03965359 -0.02885508 -0.03392916 -0.04039859 -0.02885508 -0.03392916 -0.03890854 -0.02885508 -0.03338378 -0.03836315 -0.02885508 -0.03263878 -0.03816354 -0.02885508 -0.03189378 -0.03836315 -0.02885508 -0.0313484 -0.03890854 -0.02885508 -0.03114873 -0.03965359 -0.02885508 -0.03263878 -0.04114359 -0.02885508 -0.03069913 -0.03698384 -0.02284264 -0.03195267 -0.0364257 -0.02284264 -0.02978092 -0.03800356 -0.02284264 -0.02929049 -0.03989213 -0.02282929 -0.03061509 -0.04234826 -0.02300184 -0.03263878 -0.04295355 -0.02284264 -0.03468781 -0.04232388 -0.02283596 -0.03598165 -0.03994834 -0.02282994 -0.03549665 -0.03800356 -0.02284264 -0.03457844 -0.03698384 -0.02284264 -0.03332489 -0.0364257 -0.02284264 -0.05865567 -0.02529287 -0.03384685 -0.05775851 -0.02512788 -0.03718161 -0.05961209 -0.03106498 -0.033158 -0.06025379 -0.03087365 -0.03355175 -0.05954468 -0.02532064 -0.03306949 -0.05891281 -0.03095871 -0.03342002 -0.06039428 -0.02529287 -0.03384685 -0.06101632 -0.02517122 -0.03617084 0.08940672 -0.04108732 -0.002070188 -0.03277039 -0.04363626 -0.02692794 -0.02859193 -0.04013222 -0.02937728 -0.03003358 -0.03609877 -0.03210461 -0.03239905 -0.03527545 -0.03270387 -0.03412789 -0.03554254 -0.03253567 -0.03671252 -0.03859543 -0.03080856 -0.03666007 -0.04050511 -0.02955257 -0.03555852 -0.04246962 -0.02796608 0.0886088 -0.04279887 6.36168e-4 0.08653712 -0.04345721 -0.00690478 0.08580791 -0.04494923 -0.001409471 0.04520207 -0.03994023 -0.03006142 0.04843378 -0.04410022 -0.02618139 0.04702609 -0.04376608 -0.02730238 0.05326873 -0.0412169 -0.02869737 0.05161637 -0.04348838 -0.0270065 0.04993647 -0.03590345 -0.03236651 -0.05775922 0.004612505 -0.037193 -0.05775666 -0.001174628 -0.03720188 -0.05859529 0.004446804 -0.03404927 -0.05859327 -0.001011013 -0.03407979 -0.05885684 -0.001051843 -0.03470957 -0.05951815 -0.00105971 -0.03500813 -0.06101822 -0.001120805 -0.03617537 -0.06012785 -0.001091778 -0.03477668 -0.06045669 -0.001011013 -0.03407979 -0.06101822 0.004558682 -0.03617537 -0.06045669 0.00444889 -0.03407979 -0.06016135 -9.77682e-4 -0.03344339 -0.05982732 0.00439912 -0.03313058 -0.05888861 -9.77682e-4 -0.03344339 -0.05953836 -9.63066e-4 -0.03315317 -0.05952501 0.004503846 -0.0351721 -0.06112432 0.01044607 -0.03614145 -0.06045669 0.02871859 -0.03407979 -0.06003534 0.02876973 -0.03328365 -0.05911016 0.02877068 -0.03325545 -0.05865567 0.02873075 -0.03384685 -0.06018394 0.01044893 -0.03492861 -0.05873781 0.01044893 -0.03458768 -0.05775696 0.02855497 -0.0372008 -0.06182497 0.01044887 -0.03593939 -0.05239999 0.01948225 -0.03905642 -0.05158632 -0.01347392 -0.03935265 -0.04932856 0.001718878 -0.04020327 -0.0610162 0.02860903 -0.03617107 -0.06098604 0.03413593 -0.0360549 -0.05888831 -0.01954537 -0.03499215 -0.06035614 -0.01953965 -0.03455436 -0.05995374 0.02867662 -0.03489708 -0.05929207 0.02867299 -0.03494906 -0.0587033 0.0286976 -0.03449422 -0.05269122 0.02470082 -0.0387625 -0.06031692 -0.02525675 -0.0345363 -0.05908733 -0.02523237 -0.03500223 -0.05114662 0.01752489 -0.03791248 -0.05548858 0.02594423 -0.03638684 -0.053065 -0.01843816 -0.03723156 -0.05548858 -0.02250641 -0.03638684 -0.05013465 -0.01023018 -0.03828752 -0.05610728 -0.02630043 -0.03603845 -0.04694592 0.04583406 -0.02920168 0.03721296 0.02959805 -0.03766095 0.04578965 0.03339958 -0.03653424 -0.04106587 0.05021196 -0.02602446 -0.0332514 0.05720889 -0.01799219 -0.04171663 0.04877448 -0.02845042 -0.04311347 -0.04462254 -0.02865308 0.03721201 -0.02614915 -0.03765636 0.0466029 -0.03014951 -0.03644657 0.04900443 -0.04342323 -0.0289939 0.04639667 -0.04109704 -0.03013694 0.04840159 -0.03717404 -0.0331245 -0.03591388 -0.05629831 -0.004855394 -0.03928935 -0.05434954 -0.004855394 -0.04173719 -0.05191349 -0.008160948 -0.04096972 -0.05058419 -0.008093953 -0.03857153 -0.05297082 -0.004855394 0.03814214 -0.02636808 -0.03604644 0.04727959 -0.03022032 -0.03483748 0.03579705 0.02877855 -0.03631997 0.04726684 0.03365266 -0.03483951 -0.0404523 0.04886984 -0.02571177 -0.04096972 0.05402207 -0.008093953 -0.04173719 0.05535137 -0.008160948 -0.03857153 0.0564087 -0.004855394 -0.03591251 0.05794388 -0.004855394 -0.03928935 0.05778735 -0.004855394 -0.03591388 0.05973619 -0.004855394 0.05231672 -0.04094475 -0.02895671 0.05189061 -0.03875136 -0.03002017 0.05145078 -0.03824168 -0.02885502 0.04859465 -0.03716725 -0.02888232 0.04702764 -0.037992 -0.0292384 0.04658532 -0.04144757 -0.02885752 0.05140382 -0.04234802 -0.02885329 -0.04789096 -0.02765381 -0.03023886 -0.05289632 -0.02954787 -0.02981305 0.04855477 -0.04375451 -0.0230444 0.04616034 -0.04181504 -0.02303272 0.04582762 -0.03986042 -0.0230419 0.05160838 -0.04301494 -0.0230425 0.05289131 -0.04043769 -0.02302753 0.05237191 -0.03846937 -0.0230419 0.05139321 -0.03738248 -0.0230419 0.05005705 -0.03678756 -0.0230419 0.04859441 -0.03678756 -0.0230419 0.04725831 -0.03738248 -0.0230419 0.0462796 -0.03846937 -0.0230419 0.05706745 0.007587611 -0.02468609 0.05714589 0.007618784 -0.02306675 0.05715948 0.005052149 -0.02455848 0.05553334 0.004939973 -0.02430683 0.05794805 0.005311548 -0.02290183 0.05584478 0.00287944 -0.02381354 0.05696147 0.002945482 -0.02486121 0.05834174 -0.002382934 -0.02281928 0.0555334 -0.001502096 -0.02430677 0.05693936 -0.001596987 -0.02492308 0.04949367 -0.004427254 -0.03671914 0.08698695 -0.01101297 -0.02446854 0.08507579 -0.01246881 -0.02580869 0.05308276 0.01089841 -0.03575855 0.07060849 0.01385682 -0.03187948 0.05105441 0.01022762 -0.03631347 0.04858076 -0.03893768 -0.02885508 0.04932576 -0.03873807 -0.02885508 0.04803538 -0.03948307 -0.02885508 0.0478357 -0.04022806 -0.02885508 0.04803538 -0.04097312 -0.02885508 0.04858076 -0.0415185 -0.02885508 0.04932576 -0.04171812 -0.02885508 0.05007076 -0.0415185 -0.02885508 0.05061614 -0.04097312 -0.02885508 0.05081576 -0.04022806 -0.02885508 0.05061614 -0.03948307 -0.02885508 0.05007076 -0.03893768 -0.02885508 0.06801378 -0.02979826 -0.02303117 0.07092839 -0.03042882 -0.02921301 0.06380987 -0.03286504 -0.03139984 0.07200247 -0.03457009 -0.02806097 0.0712611 -0.03178614 -0.02312272 0.05512523 0.008584678 -0.02495747 0.0563777 0.01154583 -0.02498573 0.05612897 0.01025104 -0.02391302 0.05512523 -0.005146801 -0.02495747 0.05621838 -0.006787836 -0.02374964 0.05651861 -0.008118569 -0.02475637 0.05685889 0.00939089 -0.02515816 0.05879396 0.001425981 -0.02433151 0.05804342 -0.003803968 -0.02443158 0.05676275 -0.005930721 -0.02531433 0.05862647 0.002244651 -0.02285015 0.05787557 -0.007746875 -0.02613669 0.05746603 -0.007016479 -0.0252006 0.05874627 -0.00625354 -0.02456057 0.05874627 0.009691417 -0.02456057 0.05746597 0.01044565 -0.02519142 0.05787771 0.0111857 -0.02613741 0.05842077 0.01153725 -0.02723741 0.06638091 -0.03715276 -0.02948945 0.06828749 -0.037409 -0.02872645 0.0701189 -0.03690725 -0.02838176 0.06738936 -0.03691214 -0.02303677 0.06550544 -0.03574138 -0.0230419 0.06477415 -0.03447473 -0.0230419 0.06462126 -0.03302013 -0.0230419 0.06507319 -0.03162908 -0.0230419 0.0660519 -0.03054213 -0.0230419 0.07018685 -0.03054213 -0.0230419 0.07168507 -0.03375381 -0.02303463 0.07024544 -0.03626817 -0.02303576 0.0688644 0.03553527 -0.02885508 0.06811934 0.0353356 -0.02885508 0.06940978 0.03608065 -0.02885508 0.0696094 0.03682565 -0.02885508 0.06940978 0.03757065 -0.02885508 0.0688644 0.03811603 -0.02885508 0.06811934 0.03831565 -0.02885508 0.06737434 0.03811603 -0.02885508 0.06682896 0.03757065 -0.02885508 0.06662935 0.03682565 -0.02885508 0.06682896 0.03608065 -0.02885508 0.06737434 0.03553527 -0.02885508 0.06851214 -0.03487342 -0.02885615 0.06960237 -0.0337904 -0.02885633 0.06920957 -0.03230482 -0.02885621 0.06811934 -0.03189778 -0.02885508 0.06702917 -0.03447073 -0.02885621 0.06662935 -0.03338778 -0.02885508 0.06703639 -0.03229761 -0.02885633 -0.001975655 -0.003371953 0.04501789 -0.003063261 -0.003489434 0.04501271 -0.002027451 -0.00333029 0.03963148 -0.003021657 -0.003437697 0.03963148 -0.00337696 9.73164e-4 0.04514497 -0.003335595 0.001873493 0.03963637 -0.003074169 0.006826579 0.04501718 -0.003032386 0.006774902 0.03963148 -0.001986205 0.006711363 0.04502218 -0.002038002 0.006669521 0.03963148 -0.002344965 0.001677274 0.03963822 -0.002251446 0.001718819 0.04513144 -0.02782386 -0.01539981 0.04365688 -0.02787959 -0.01539576 0.03963148 -0.0284447 -0.01452863 0.04357522 -0.02845317 -0.01457661 0.03963148 -0.03443956 -0.0200234 0.04284894 -0.0344327 -0.0199843 0.03963148 -0.03504443 -0.01915842 0.04276955 -0.03500628 -0.01916515 0.03963148 -0.02767521 0.01916176 0.04366588 -0.02821624 0.01823872 0.04360157 -0.02772897 0.01915204 0.03963148 -0.02822893 0.01828604 0.03963148 -0.03519421 0.02227604 0.04275029 -0.03515702 0.02228599 0.03963148 -0.03466659 0.02318972 0.0428214 -0.03465706 0.02315199 0.03963148 -0.03641647 0.0201562 0.04259145 -0.03640699 0.02012091 0.03963148 -0.03694146 0.01924568 0.04252231 -0.03690701 0.01925492 0.03963148 -0.02943325 0.01613324 0.04345983 -0.0294789 0.01612102 0.03963148 -0.02996689 0.01521009 0.04339677 -0.02997887 0.01525497 0.03963148 -0.02897995 -0.01376605 0.04351276 -0.02902674 -0.01375746 0.03963148 -0.02959215 -0.012892 0.04344111 -0.02960032 -0.01293832 0.03963148 -0.03558647 -0.01838332 0.04269963 -0.03557986 -0.01834601 0.03963148 -0.03618979 -0.01752048 0.04262113 -0.03615343 -0.01752686 0.03963148 -0.004824042 0.0248022 0.04283642 -0.006406247 0.0200392 0.04369854 -0.004859447 0.0247845 0.03963148 -0.008026123 0.01529926 0.03963148 -0.008000075 0.01524716 0.04434996 -0.009026288 0.01559013 0.04431009 -0.008974611 0.01561594 0.03963148 -0.007421612 0.02037835 0.04364448 -0.005807936 0.02510118 0.03963148 -0.005821228 0.02514904 0.04277163 -0.01182562 0.0191394 0.04387497 -0.01184231 0.01924085 0.03963142 -0.01068013 0.02680939 0.04240417 -0.01071494 0.02673941 0.03963148 -0.01383358 0.01698523 0.03964155 -0.0134257 0.0172376 0.04410499 -0.016245 0.01653677 0.0441966 -0.01625418 0.0166884 0.03963148 -0.01613938 0.01772147 0.0440393 -0.01577395 0.01758569 0.0398159 -0.0128715 0.01913923 0.03963178 -0.01390975 0.01825916 0.04396462 -0.01283729 0.01955991 0.0437901 -0.01172423 0.02691382 0.04237872 -0.01170402 0.02688658 0.03963148 -0.08857142 -0.02948099 0.03309458 -0.09054714 -0.003095448 0.03235048 -0.09181666 -0.02854883 0.0318256 -0.08770316 -5.48872e-4 0.03340554 -0.08555227 -0.01624637 0.03414845 -0.08206117 -0.03141164 0.03524744 -0.08290612 -0.004077672 0.03499174 -0.08721786 0.00171864 0.03358042 -0.08443093 0.01695746 0.03451412 -0.08765804 0.003964662 0.03342807 -0.08856832 0.03291952 0.03309577 -0.09116262 0.006773948 0.03210806 -0.09307801 -0.01166391 0.03128153 -0.09564137 -0.004724919 0.0300979 -0.09504824 -0.02764934 0.0303775 -0.09819197 -0.02681189 0.02872473 -0.09784013 -0.004166185 0.02892464 -0.09950274 0.001720309 0.02794009 -0.1012852 -0.02603876 0.02675366 -0.1016156 -0.004455745 0.02651578 -0.1031284 -0.009707331 0.02533823 -0.1029983 0.01144939 0.02544581 -0.1047433 0.001725196 0.02388095 -0.1042601 0.02880042 0.02434283 -0.1056574 0.02927494 0.02293306 -0.1062532 0.001330733 0.022255 -0.1069584 0.02827024 0.021375 -0.1074966 0.001816332 0.02063596 -0.1081562 -0.02587109 0.01962667 -0.1085315 0.001711189 0.01900184 -0.1091203 -0.02449601 0.01790636 -0.1069584 -0.02483266 0.021375 -0.1012852 0.02947634 0.02675366 -0.09819203 0.03024953 0.02872473 -0.09784054 0.007603287 0.0289244 -0.09512674 0.03196859 0.03033554 -0.09474724 0.009543836 0.03052175 -0.09181487 0.03198695 0.03182631 -0.01287889 0.001718819 0.04663139 -0.01351165 0.003662705 0.04659539 -0.0136401 -0.002266228 0.04656231 -0.01986747 -0.009901523 0.04600328 -0.01399904 0.006015181 0.04655426 -0.01585233 0.009269058 0.04638755 -0.02743601 -0.01611149 0.04520064 -0.02429002 0.01720768 0.04554831 -0.02743601 0.01954919 0.04520064 -0.03797453 0.001565992 0.0438981 -0.03147894 -0.002141296 0.04472619 -0.03398138 0.02386188 0.0444169 -0.04073983 0.02780431 0.04352021 -0.04362708 0.001759529 0.04310888 -0.04764372 0.03147333 0.04250681 -0.04764366 -0.02803564 0.04250681 -0.04073971 -0.02436661 0.04352021 -0.03398132 -0.02042418 0.0444169 -0.05465543 -0.03149116 0.04136538 -0.05652523 -0.004276514 0.04103964 -0.05952143 -0.01798039 0.04049688 -0.06174272 -0.03477311 0.04007673 -0.06408649 -0.01711469 0.03961557 -0.06902575 -0.03542262 0.03857678 -0.06174278 0.0382108 0.04007673 -0.05872601 0.01793497 0.04064357 -0.05465549 0.03492885 0.04136538 -0.06473171 0.01989495 0.03948527 -0.06902647 0.03886008 0.0385766 -0.07048439 0.01811861 0.0382505 -0.07552415 0.03779155 0.03704202 -0.07473957 0.01333934 0.03724002 -0.07957708 0.01431119 0.03596544 -0.08203715 0.0358594 0.03525257 -0.07926833 -0.01290601 0.03605139 -0.07554388 -0.03339892 0.03703814 -0.07642006 -6.37964e-4 0.03681397 -0.0719614 -0.009526789 0.0379101 -0.1081213 0.02807605 0.01968789 -0.1091203 0.02793359 0.01790636 -0.1094464 0.001855373 0.01723188 -0.109948 0.02784085 0.01607573 -0.1101183 0.005501031 0.01564455 -0.1106223 0.02891212 0.01422089 -0.110619 -0.02435427 0.01423597 -0.1112216 0.001701295 0.01218461 -0.1116033 -0.0243557 0.01062136 -0.1099479 -0.02440327 0.01607573 -0.1116033 0.02779328 0.01062136 -0.1118772 0.001717627 0.009347319 -0.1056588 -0.02626281 0.02293032 -0.1042601 -0.02536284 0.02434283 -0.06711149 7.88436e-4 0.03899091 -0.06187766 9.76715e-4 0.04005068 -0.05236184 0.001278221 0.04175192 0.04658502 0.001718878 0.04513144 0.04679363 0.004400789 0.04509949 0.007533669 0.008800327 0.04491382 -0.01516646 0.00844556 0.0449413 0.02821528 0.01135432 0.04473519 0.02933865 0.01109206 0.04475933 0.04777777 0.007480621 0.04498529 0.04852986 0.009540081 0.04486668 -0.0179075 0.01220929 0.04465907 0.02820384 0.01427942 0.04445993 -0.02066528 0.01499909 0.04437816 0.00575459 0.01743936 0.04407745 0.0226143 0.01708728 0.0441246 -0.02670073 0.01996916 0.04370957 -0.02092719 0.02326953 0.04313868 -0.02804195 0.02586787 0.04261708 -0.02415221 0.03176593 0.04112654 0.06158155 0.02965211 0.04170715 0.0185281 0.03097873 0.04134887 0.04163843 0.03238946 0.04094451 0.06486201 0.03377103 0.04051852 0.0583499 0.02541589 0.04270803 0.03707522 0.02725487 0.04230016 0.02832758 0.02359724 0.04308283 0.006445288 0.02263742 0.04325634 0.0270406 0.02002936 0.04370754 0.02233886 0.01831507 0.04395681 0.02576214 0.01816231 0.04357093 -0.03331148 0.02440035 0.04291766 -0.0312047 0.02659887 0.04246532 -0.03318566 0.02828526 0.04207545 -0.04729378 0.03224778 0.04098397 -0.03559482 0.03012818 0.04159021 -0.03845405 0.03085428 0.04141592 -0.04006797 0.03355801 0.04059517 -0.0436514 0.03380119 0.04052287 -0.049232 0.03671342 0.03953713 -0.04511076 0.03657037 0.03957563 -0.04014676 0.04101198 0.0377627 -0.04368042 0.0415017 0.03753811 -0.03570032 0.04498893 0.03575849 -0.03932207 0.04527235 0.03559821 -0.03056073 0.04958111 0.03284448 -0.03523075 0.04881203 0.03334939 -0.03148889 0.05204933 0.03076511 -0.0268687 0.05227947 0.03055888 -0.05999898 0.03855687 0.03879827 -0.050704 0.03943878 0.03846228 -0.06137406 0.04216152 0.03723078 -0.05701315 0.04221683 0.03722381 -0.05802929 0.04456222 0.03595274 -0.05076766 0.04641413 0.03498792 -0.05213791 0.04621833 0.03504395 -0.05279785 0.04799604 0.03384149 -0.05108338 0.0466187 0.03479981 -0.05181241 0.04851746 0.03350144 -0.04380494 0.05098909 0.03174787 -0.04582858 0.05302125 0.0297566 -0.039756 0.05372244 0.02914392 -0.03792554 0.05503141 0.02769756 -0.04038882 0.05668699 0.0254454 -0.03356558 0.05592626 0.02655792 -0.03739702 0.05864953 0.02225643 -0.02674376 0.05417823 0.0286532 -0.03189051 0.05382388 0.02905064 -0.02314662 0.05336982 0.02950423 -0.01949095 0.05263471 0.03022414 -0.01201975 0.05140256 0.03133326 -0.02229964 0.05137515 0.03136068 -0.00446105 0.05053055 0.0320549 -0.01788979 0.05043238 0.03213417 -0.02166128 0.04672002 0.03480941 -0.0215913 0.05006515 0.03243309 -0.02497208 0.04619222 0.0350911 -0.02944988 0.04108607 0.03772908 -0.004474997 0.04838144 0.03365051 -0.01291477 0.04912662 0.03313529 -0.01470345 0.04609298 0.0351293 -0.004487752 0.0461266 0.03509885 -7.54745e-4 0.04451251 0.03602206 -0.01664167 0.04315471 0.03673619 0.02839469 0.04297375 0.03682726 0.04044252 0.04126721 0.03764635 0.06828469 0.0392571 0.03852319 0.04397678 0.03931146 0.0385006 -0.01849371 0.04034548 0.03806054 0.003333032 0.04163509 0.03747594 -0.003760218 0.04592788 0.0352174 0.001411199 0.04592782 0.03521746 0.001939415 0.04592221 0.03522127 0.04534673 0.04474985 0.03589165 0.04792028 0.04645478 0.03490054 0.02686882 0.04718106 0.03444689 0.04088896 0.04869014 0.03343558 0.0678004 0.04705947 0.03452289 0.06556218 0.04957735 0.03279078 0.06962823 0.04431354 0.03613364 -0.003573715 0.04834139 0.03367805 0.001236021 0.05013 0.03237092 -0.003587365 0.05045461 0.03211557 0.01637846 0.04833579 0.03368192 0.01357775 0.05006098 0.0324245 0.01927661 0.05042141 0.03214198 0.04425126 0.05055087 0.03203868 0.02493834 0.05104339 0.03163641 0.03050494 0.05192774 0.03087431 0.06230461 0.05189239 0.03090584 0.0357815 0.05303436 0.02983868 0.06001317 0.05401307 0.02883267 0.04052191 0.05427086 0.02855134 0.04469984 0.05557143 0.02700823 0.05942505 0.05589032 0.02657717 0.04843115 0.05692285 0.02512401 0.05711734 0.05785286 0.02357292 0.0499432 0.05853492 0.02232611 0.05195587 0.06086468 0.01577895 0.002115011 0.05008834 0.03240323 0.007856011 0.04995298 0.03250765 0.06833773 0.03785032 0.03908544 0.04493308 0.03674805 0.03950178 0.03504931 0.03494912 0.04013377 0.006065428 0.03572052 0.03986942 -0.02034038 0.0375458 0.03920346 -0.005998551 0.03422486 0.04037326 0.05521345 0.02109098 0.0435267 0.04368263 0.02296334 0.0431962 0.02944737 0.02079695 0.04357904 0.03537118 0.01801818 0.04400038 0.05227059 0.01664763 0.04418021 0.03097653 0.01548451 0.04433065 0.04930609 0.01199173 0.04467821 -0.0472157 0.04578238 0.03532981 -0.04528391 0.04363977 0.03648716 -0.05463886 0.04019796 0.0381363 -0.04070299 0.04718786 0.03444254 -0.04128897 0.05024212 0.03228336 -0.0361225 0.05073553 0.03190952 -0.03723621 0.05329591 0.02960467 -0.03351432 0.03645133 0.03960978 -0.03082555 0.03580945 0.03983831 -0.0266329 0.04079657 0.03785973 -0.02627015 0.05104947 0.03163802 -0.02597767 0.04809546 0.03391945 -0.03437864 0.0429753 0.03682667 -0.02997636 0.04734939 0.03435558 -0.03118729 0.04271572 0.03695601 -0.03856414 0.0388168 0.03870368 -0.03548902 0.03828084 0.03891825 0.01275509 0.0385316 0.03881829 -0.0150147 0.04889947 0.03333789 -0.0194804 0.04622197 0.03514575 -0.01910829 0.04329556 0.03669244 -0.02478647 0.03929227 0.03850853 -0.02551418 0.03447246 0.04030758 -0.02872854 0.03412175 0.0404067 0.02549904 0.0170539 0.04396164 0.03183054 0.01814371 0.04377061 -0.002716243 0.02960503 0.04172116 -0.06229424 0.04253596 0.03873217 -0.05687946 0.04162359 0.03913092 -0.05210518 0.04607546 0.03686726 -0.05485624 0.03992027 0.03988552 -0.04724013 0.04288977 0.03854852 -0.05085414 0.03726375 0.04093164 -0.04755622 0.04497903 0.03751295 -0.0414071 0.04718047 0.03621453 -0.04119712 0.04977601 0.03450417 -0.03708606 0.05054688 0.03394007 -0.03710055 0.05334877 0.03162342 -0.03201496 0.05398559 0.03100937 -0.04728436 0.049232 0.03488546 -0.05231344 0.0485903 0.03536564 -0.04301363 0.05208575 0.03272008 -0.04634112 0.05318379 0.03178519 -0.03829926 0.05519509 0.0297892 -0.04217731 0.05604416 0.02881252 -0.03311032 0.05734699 0.02715682 -0.03950744 0.0585348 0.02545642 -0.02401554 0.05484014 0.03014266 -0.01445746 0.04559212 0.03713965 0.02735406 0.04650831 0.03661638 -0.01276403 0.04816842 0.03559547 0.02729517 0.04363769 0.03817254 -0.01669943 0.04291605 0.03852748 0.02268755 0.04021495 0.03974837 0.06906622 0.04186624 0.03902184 0.06851392 0.04032075 0.0397011 0.06847321 0.04515224 0.0373817 0.06649702 0.04791283 0.03575921 0.03079301 0.04887956 0.03512632 0.06516879 0.05055141 0.03393608 0.03931272 0.05109149 0.03352338 0.06181174 0.05306464 0.03187316 0.0258134 0.05261766 0.03227323 0.01591074 0.05161607 0.03312224 0.01350837 0.05008006 0.0342853 0.005884289 0.0514096 0.03327906 -0.0133934 0.04987823 0.03442925 -0.01996296 0.03730499 0.0408951 0.02880054 0.03671598 0.0411086 0.067312 0.03839057 0.04048585 0.06517815 0.03422313 0.04194891 0.01852184 0.03311103 0.04229414 0.06194812 0.03002053 0.04316276 -0.02745193 0.02585947 0.04414761 0.01543885 0.02854776 0.04353439 -0.02369672 0.03155815 0.04274642 0.01314592 0.02411115 0.0445044 -0.02920079 0.02492719 0.04434186 -0.02687209 0.0203309 0.04517102 -0.0306704 0.02572774 0.0441876 -0.03116232 0.0275284 0.04378956 -0.03310519 0.02815896 0.04362845 -0.03588551 0.03053903 0.04304206 -0.03865557 0.02998334 0.04320263 -0.04081243 0.03280735 0.04240179 -0.04344522 0.03382998 0.04209613 -0.04028171 0.03404313 0.04201173 -0.04558265 0.03519684 0.04163718 -0.04530751 0.03653496 0.04118037 -0.02604812 0.03456133 0.0418514 -0.02828598 0.03389137 0.04205411 -0.02445447 0.038984 0.04025197 -0.01875329 0.04459947 0.03775721 -0.0168178 0.04962599 0.03453743 -0.01453179 0.04961663 0.03452301 -0.02007466 0.04471468 0.03764778 -0.01813977 0.05095309 0.03362435 -0.02083915 0.05025011 0.03419494 -0.02605968 0.04483884 0.03749364 -0.02247023 0.04641044 0.03670167 -0.02702194 0.04108452 0.03937315 -0.02910947 0.04078876 0.03950202 -0.03111886 0.0361787 0.04129785 -0.03308361 0.03620249 0.04128986 -0.03576105 0.03866243 0.04037982 -0.03818678 0.03852885 0.04043209 -0.03399389 0.04268693 0.03863787 -0.03045159 0.04409921 0.03794074 -0.02999579 0.04670548 0.03649938 -0.0247659 0.05003839 0.03434115 -0.0249722 0.05131304 0.03338229 -0.0228371 0.05132633 0.03312438 -0.02723962 0.05290621 0.03203827 -0.009070098 0.05246645 0.03240412 -0.0306617 0.05218303 0.03266865 -0.01918298 0.05383032 0.03115653 -0.03209525 0.04882413 0.03516358 -0.03512477 0.04832786 0.03549152 -0.03630989 0.04502624 0.03744965 -0.0392608 0.04470777 0.03762042 -0.0406993 0.04115784 0.03934079 -0.04410469 0.04050731 0.03962004 0.04658502 0.001718878 0.04663139 0.04679363 0.004436194 0.04659903 0.04781252 0.007255434 0.0464974 0.0482344 0.009649455 0.04636275 -0.01797938 0.01242297 0.04614591 0.04977345 0.01210975 0.04617351 0.01841956 0.01421111 0.04597246 -0.02076989 0.01526516 0.0458576 0.0518527 0.01684206 0.04566812 -0.02375543 0.01788198 0.04553133 0.05471849 0.02135473 0.04500406 0.05858302 0.02573406 0.04417419 0.03551697 0.0544551 0.03054106 0.058896 0.05540126 0.02955257 0.04471117 0.05693012 0.02770394 0.05875325 0.05727797 0.02723026 0.04762715 0.05816638 0.02596408 0.04017448 0.0556752 0.0292285 0.05788934 0.05885112 0.02476221 0.04947936 0.06003481 0.02272218 0.05416905 0.06059908 0.02144795 0.05175089 0.0625078 0.01475423 -0.09088087 -0.02399814 0.03058946 -0.09079682 -0.0239157 0.02114123 -0.08589714 -0.02401435 0.0324499 -0.08579838 -0.02391558 0.02113175 -0.09078949 -0.0229153 0.02117013 -0.08579838 -0.0229156 0.02113175 -0.08479839 -0.02591502 0.02113234 -0.08580064 -0.02591401 0.02141678 -0.08479839 -0.01091611 0.02113234 -0.08579838 -0.01391571 0.02113175 -0.08579832 -0.01291573 0.02112984 -0.09079682 -0.01391583 0.02114123 -0.09078949 -0.01291543 0.02117013 -0.09088087 -0.01399827 0.03058946 -0.08589714 -0.01401448 0.0324499 -0.08580052 -0.01091378 0.02161055 -0.08469611 -0.02601784 0.03285133 -0.08469611 -0.01081347 0.03285133 -0.08589714 -0.02601432 0.0324499 -0.07216596 -0.01278316 0.03632098 -0.07229894 -0.01291567 0.02114123 -0.07717686 -0.01279413 0.03506493 -0.07729846 -0.01291573 0.02113175 -0.0723015 -0.01391607 0.02117055 -0.07729846 -0.01391571 0.02113175 -0.07829844 -0.0109167 0.02113211 -0.07729613 -0.01091432 0.02141815 -0.07729846 -0.0229156 0.02113175 -0.07829844 -0.02591496 0.02113258 -0.07729846 -0.02391558 0.02112984 -0.07229894 -0.02291554 0.02114123 -0.0723015 -0.02391594 0.02117055 -0.07841718 -0.01079708 0.03473126 -0.07841712 -0.02603423 0.03473019 -0.0772956 -0.02591919 0.02161186 -0.07717686 -0.02603715 0.03506493 -0.07717686 -0.02403718 0.03506493 -0.07216596 -0.02404814 0.03632098 -0.08589786 -0.01081579 0.03247207 -0.08589714 -0.01281696 0.0324499 -0.09088212 -0.01283311 0.03059214 -0.09088087 -0.0228331 0.03058946 -0.08589744 -0.02281647 0.03247511 -0.07717663 -0.0107941 0.03506588 -0.07216596 -0.01404827 0.03632098 -0.07216596 -0.02278304 0.03632098 -0.07717686 -0.01403731 0.03506493 -0.07717686 -0.022794 0.03506493 -0.05693292 -0.01225852 0.03682631 -0.05436152 -0.01370471 0.03989392 -0.05918961 -0.01079869 0.03904211 -0.05688661 0.01571822 0.0368275 -0.05926787 0.01411569 0.03901833 -0.05683135 0.01589596 0.03913903 -0.05436152 0.01714235 0.03989392 -0.05837947 0.01381903 0.03659987 -0.05397373 0.01614063 0.03996026 -0.05853807 0.0134136 0.03915631 -0.003874659 0.04698634 0.0220927 -0.004376173 0.04703354 0.02232998 -0.004176199 0.05137807 0.02213174 -0.003665804 0.04623359 0.02312296 -0.003672719 0.05132007 0.02232998 0.001323699 0.04703354 0.02232998 0.00182712 0.04703354 0.02213174 0.001312553 0.04624718 0.02256166 0.001323878 0.05100721 0.0223084 0.002034068 0.04623359 0.02312296 0.00182712 0.05099999 0.02213174 -0.02846163 0.05611032 0.02848953 -0.02723497 0.05676192 0.01818436 -0.02372378 0.05499774 0.02972441 -0.02135866 0.05554068 0.01852184 -0.02362143 0.05699282 0.007131934 -0.01830142 0.0560081 0.007131934 -0.02900916 0.05815064 0.007131934 -0.0189017 0.05401802 0.03070902 -0.01606059 0.05459189 0.01899069 -0.01401561 0.05318093 0.03148651 -0.01093792 0.05383789 0.01936608 -0.007864475 0.05455803 0.007131934 -0.005869925 0.05325669 0.01965123 -0.002747535 0.0540927 0.007131934 -0.004110455 0.05197137 0.0325222 -8.10035e-4 0.05284529 0.01985627 0.002301692 0.05380052 0.007131934 8.83737e-4 0.05161619 0.03280884 0.004301428 0.05260676 0.01998984 0.007283329 0.05368143 0.007131934 0.009634613 0.0525496 0.02011561 0.0109058 0.05144566 0.03294384 0.01569592 0.05267077 0.0209521 0.0208956 0.05204534 0.03246116 0.02207368 0.05336594 0.01876169 0.02790766 0.05405688 0.01935046 0.0307331 0.05346328 0.03122812 0.03271532 0.05490833 0.01906096 0.03619426 0.05669718 0.007133305 0.03982824 0.05758202 0.007132351 0.04295516 0.05744206 0.0180996 0.04469984 0.05896109 0.007131934 0.02182209 0.05436289 0.007131934 0.026533 0.05493628 0.007131934 0.03117626 0.05568277 0.007131934 0.04469984 0.05712437 0.02721577 -0.05129331 0.04671418 0.01615834 -0.05223369 0.04957085 0.0309655 -0.0528118 0.05073565 0.01613181 -0.05204218 0.04643136 0.01616227 -0.05351388 0.05033034 0.01613181 -0.08336156 0.03327125 0.03327983 -0.08328253 0.03323251 0.02637618 -0.08279842 0.03177529 0.03345549 -0.08254104 0.03127491 0.02611631 -0.08236664 0.0335738 0.02622073 -0.08377438 0.03029477 0.02635157 -0.08411633 0.03121292 0.02652066 -0.0808953 0.02967488 0.0261501 -0.08181047 0.02933275 0.02648931 -0.08240967 0.03074264 0.03357505 -0.08184546 0.02924382 0.03374612 -0.08080589 0.0296334 0.03405427 -0.08381074 0.03021776 0.03313761 -0.06292885 0.04346895 0.0171231 -0.06217247 0.04376381 0.01652193 -0.06300795 0.04329341 0.03270888 -0.06198954 0.04368156 0.03276604 -0.06269037 0.04512667 0.01613181 -0.06194883 0.04366028 0.03477632 -0.05941122 0.03685206 0.03276479 -0.05923986 0.03655272 0.03902357 -0.05935615 0.03629529 0.01613724 -0.07496309 0.03873682 0.03203839 -0.07556331 0.04071974 0.01613181 -0.07488322 0.03891658 0.01632428 -0.07516044 0.03921288 0.03391861 -0.07499855 0.03873026 0.03487712 -0.07451766 0.03746551 0.03574699 -0.07238471 0.03190737 0.03203719 -0.07230615 0.03159421 0.03628778 -0.07207953 0.03149181 0.01613724 -0.07412379 0.03919625 0.0171231 -0.07395565 0.03912079 0.03209489 -0.07112318 0.02885407 0.0165975 -0.07104849 0.03102594 0.01612925 -0.07037508 0.02925205 0.01652777 -0.07128357 0.02964711 0.01613181 -0.07119429 0.02864265 0.03654873 -0.07010972 0.02904987 0.03679811 -0.07081788 0.03092175 0.03663569 -0.07133102 0.03177434 0.01613181 -0.05982208 0.03526425 0.0161305 -0.0601046 0.0360127 0.01613181 -0.05873435 0.03438484 0.01613181 -0.05835831 0.03367173 0.01692479 -0.0591551 0.03348791 0.01652777 -0.05810743 0.03355836 0.03923177 -0.0588153 0.03543007 0.03910207 -0.05907356 0.03554677 0.01613724 -0.05878436 0.03651511 0.01655495 -0.05849921 0.03575974 0.01655495 -0.07179695 0.0307433 0.01613724 -0.07236874 0.03052353 0.01655495 -0.07265388 0.0312789 0.01655495 -0.07189983 0.03051561 0.03638386 -0.07137733 0.03229135 0.0320937 -0.05858433 0.03680133 0.03914457 -0.05815905 0.03567671 0.03922235 -0.06042957 0.03646397 0.03270769 -0.08233153 0.03366309 0.03359889 -0.06327396 0.04440754 0.01613181 -0.06301015 0.04325002 0.03470218 -0.06277889 0.04258549 0.03679603 -0.06161218 0.03944814 0.03859031 -0.06035971 0.03612798 0.03881371 -0.06318306 0.04492217 0.01613181 -0.08419674 0.03124326 0.03301376 -0.07480502 0.04097616 0.01613181 -0.07411694 0.03958731 0.03368878 -0.07367783 0.03848195 0.03598034 -0.07122731 0.03200387 0.03654104 -0.0729593 0.0313462 0.03613156 -0.07255369 0.03026998 0.03622925 -0.06580364 0.03406262 0.03773325 -0.05993771 0.03500825 0.03889328 -0.06538677 0.03296113 0.0378198 -0.05923199 0.03313571 0.039025 -0.05313479 0.04893076 0.03213542 -0.09823042 0.03386056 0.02461671 -0.08079832 0.03906881 0.03205019 -0.06358826 0.04462957 0.03485339 -0.0699594 0.0422905 0.03584873 -0.09096425 0.0342136 0.03174269 -0.08110785 0.03809493 0.0342769 -0.06728279 0.04214763 0.03792548 -0.08851051 0.03638142 0.03103405 -0.09462684 0.03465908 0.02812218 -0.09824728 0.03305637 0.02731335 -0.1018217 0.03093045 0.02607798 -0.1086837 0.02970355 0.01827096 -0.104651 0.03172314 0.02195304 -0.1095203 0.0307812 0.0137102 -0.06817042 0.04052358 0.03853935 -0.06188577 0.04513871 0.03555268 -0.06113827 0.03894919 0.04014235 -0.06146544 0.04565626 0.03416574 -0.04780995 0.03259021 0.04242795 -0.05552458 0.04801553 0.03523552 -0.06844359 0.04087895 0.03650099 -0.08750575 0.0351336 0.03077965 -0.0843206 0.03512346 0.03280711 -0.09527957 0.03162389 0.02859395 -0.08994626 0.03236234 0.03096586 -0.1024459 0.03113102 0.02152669 -0.09525275 0.0328561 0.0274468 -0.1024294 0.03081715 0.02289682 -0.1024321 0.02970153 0.02406781 -0.07958638 0.03547471 0.03440469 -0.08478081 0.03389543 0.03282356 -0.1003528 0.02931952 0.02581858 -0.03937673 0.02715617 0.04219448 -0.02216881 0.01557028 0.04426211 -0.04600232 0.03074431 0.04124021 -0.05273306 0.03412437 0.04016977 -0.03777849 0.0590645 0.01960307 -0.06071829 0.04436218 0.03403502 -0.04012554 0.05918741 0.02218323 -0.03802919 0.06051623 0.0208705 -0.04053252 -0.02436661 0.04203462 -0.01831501 -0.00853908 0.04464977 -0.0135467 -0.001101076 0.04508638 -0.03225106 -7.49193e-4 0.0431208 -0.03301066 -0.003810167 0.04263579 -0.032251 0.004187762 0.0431208 -0.03330874 -5.81989e-4 0.04298913 -0.0333094 0.004021286 0.04299008 -0.0339924 -0.003482103 0.04250246 -0.03399217 0.006920099 0.0425024 -0.03521323 -0.006050586 0.04274779 -0.03521317 0.009489178 0.04274779 -0.06314373 0.008893251 0.03827267 -0.06119316 -0.009629905 0.0386545 -0.05747586 0.001425921 0.03934621 -0.05857712 -0.009880602 0.03914594 -0.05632263 -0.01156723 0.0392211 -0.06695771 -0.007780313 0.03749006 -0.06495326 -0.03560286 0.03790509 -0.06870287 -0.03542262 0.03711193 -0.03428035 -0.006591618 0.04286712 -0.03301066 0.00724852 0.04263597 -0.03428041 0.01003032 0.04286706 -0.04411739 -1.13653e-4 0.04152041 -0.04908376 0.0106641 0.04076153 -0.09306699 -0.006691038 0.02964782 -0.08887201 -0.006499588 0.0313791 -0.08157753 -0.01238352 0.03382641 -0.08352363 0.00173366 0.03322875 -0.08777791 0.009412109 0.03178584 -0.09280735 0.02218443 0.02976459 -0.09149998 0.009314 0.0303415 -0.09464174 0.009204387 0.02890455 -0.09181725 -0.02838218 0.03019726 -0.09535098 -0.02784758 0.0285561 -0.09481012 -0.003908097 0.0288279 -0.09694415 -5.70001e-4 0.02771729 -0.09889435 -0.022026 0.02657192 -0.0989865 7.08822e-4 0.02649223 -0.09967434 -0.01990473 0.02604675 -0.1004683 -0.00395739 0.02549391 -0.09904289 0.02438133 0.02647519 -0.1015751 0.02155023 0.02465981 -0.0971291 0.00366342 0.02760988 -0.08870142 -0.02998441 0.03144115 -0.08190691 -0.03184479 0.03372579 -0.07534384 -0.03334671 0.03554141 -0.0750826 -0.005149066 0.03560763 -0.06145882 -0.03477311 0.03860384 -0.05440169 -0.03149116 0.03988701 -0.05397254 -0.01270169 0.03996044 -0.0511865 -0.01856714 0.04042541 -0.04741483 -0.02803564 0.04102438 -0.05495303 -0.003680169 0.03979194 -0.07726007 0.02196067 0.03504282 -0.02116602 -0.01165819 0.04436719 -0.01583105 -0.005515396 0.04488301 -0.1008307 -0.02595788 0.02535504 -0.0990234 -0.02364873 0.02653163 -0.1006609 -0.01908862 0.02536672 -0.1021261 -0.004969239 0.02422094 -0.1016674 -0.01880162 0.024603 -0.1029686 -0.01845365 0.02348518 -0.1037941 -0.001195013 0.02271014 -0.1044392 -0.0188589 0.02204227 -0.1051208 0.001288294 0.02127099 -0.1043787 0.02246439 0.02210801 -0.1059485 0.02418124 0.02023428 -0.1027998 0.02210223 0.02364379 -0.1059681 -0.02076429 0.02020823 -0.1065801 0.001700282 0.01931411 -0.1072418 -0.02213174 0.01824659 -0.1078705 0.001731634 0.01705104 -0.108507 -0.02215403 0.01563692 -0.1088613 0.001712918 0.01472604 -0.1094464 -0.02217739 0.01296108 -0.1094489 0.02561503 0.01295304 -0.1101697 -0.02220213 0.01015907 -0.1101772 0.02563971 0.01012629 -0.1085124 0.02559173 0.01562386 -0.1072426 0.02556926 0.01824527 -0.07877546 -0.03981107 0.01312148 -0.07925927 -0.03832948 0.01205343 -0.08246594 -0.03986155 0.01022851 -0.08284401 -0.03836113 0.01024204 -0.08559572 -0.03981763 0.01274549 -0.08537214 -0.0383237 0.01238757 -0.08450949 -0.03825354 0.01640534 -0.08142501 -0.03974437 0.01694321 -0.07987445 -0.03826022 0.01602196 -0.08460736 -0.03976064 0.01601129 -0.05469787 -0.03615331 0.04002046 -0.05686068 -0.03780299 0.03931385 -0.05460321 -0.03678876 0.03930133 -0.04169797 -0.04645264 0.03439843 -0.04751151 -0.04154986 0.03750783 -0.03625124 -0.05014669 0.03145736 -0.03708261 -0.04996961 0.03104501 -0.03717923 -0.05094242 0.03027832 -0.04731088 -0.04580813 0.03487646 -0.0429607 -0.04865294 0.03271543 -0.04500156 -0.04681539 0.0335673 -0.03817582 -0.05140268 0.03012579 -0.05167734 -0.0428996 0.03671622 -0.05673331 -0.03900408 0.03840219 -0.05725204 -0.03960126 0.03851705 -0.05465131 -0.03675079 0.03814119 -0.05693924 -0.03881788 0.03719794 -0.04083877 -0.0375688 0.03940999 -0.04560548 -0.03162485 0.04168081 -0.04984194 -0.03227114 0.04149287 -0.03926074 -0.04127007 0.03762042 -0.04356992 -0.03754079 0.03941959 -0.0363416 -0.04160541 0.03744083 -0.03507655 -0.04490643 0.03548145 -0.03201836 -0.04540932 0.03514713 -0.03053045 -0.04890304 0.03254276 -0.02726012 -0.04947382 0.03204649 -0.009087622 -0.04902988 0.0323987 -0.0255025 -0.04779058 0.03345912 -0.02253067 -0.04829454 0.03300559 -0.0265752 -0.0446304 0.03569692 -0.03240358 -0.05058002 0.03097593 -0.01918393 -0.0503928 0.03115636 -0.02371686 -0.05152666 0.03001403 -0.03306186 -0.05387836 0.02719253 -0.04136312 -0.05257642 0.02884411 -0.04095268 -0.05448287 0.0262739 -0.03685182 -0.05611073 0.02373439 -0.03702074 -0.04712098 0.03393024 -0.0414406 -0.04375594 0.03620678 -0.04586046 -0.04032373 0.03810989 -0.05153298 -0.03588384 0.04013973 -0.06514644 -0.0378254 0.03924375 -0.02993631 -0.04329472 0.03648418 -0.0315535 -0.03958487 0.03847616 -0.03399384 -0.03924924 0.03863787 -0.03575968 -0.03522419 0.04038 -0.03818607 -0.0350877 0.04043352 -0.04319316 -0.03064805 0.04198479 -0.04029476 -0.03008013 0.04215341 -0.04453057 -0.02767485 0.04289084 -0.04046815 -0.02883434 0.04255461 -0.03638076 -0.02820426 0.0427401 -0.03301489 -0.02454978 0.04367893 -0.03409051 -0.02127879 0.04438257 -0.03089028 -0.02252656 0.04412221 -0.03018611 -0.02482503 0.043536 -0.02604323 -0.03112369 0.04185134 -0.02828776 -0.03050476 0.04203695 -0.0250808 -0.03540205 0.04023319 -0.01803344 -0.04742366 0.03370124 -0.01390242 -0.04677855 0.0341894 -0.01588046 -0.04534298 0.03525549 9.79531e-4 -0.04814267 0.03314524 -0.02088272 -0.0468223 0.03418225 -0.02218919 -0.04333275 0.03650623 -0.02702188 -0.03764677 0.03937315 -0.02517122 -0.04184812 0.03730767 -0.0290482 -0.03737497 0.03949218 -0.0312711 -0.03256356 0.04136115 -0.03309321 -0.0327894 0.04128074 -0.01988971 -0.04095894 0.03786087 -0.02879858 -0.02148383 0.04434299 -0.02687209 -0.0168932 0.04517102 0.0446999 -0.01993042 0.04464644 0.0446999 -0.01242333 0.04578846 -0.02375537 -0.01444423 0.04553133 -0.02076989 -0.01182746 0.0458576 -0.01797938 -0.00898528 0.04614591 0.0446999 -0.005126714 0.0464304 -0.01551228 -0.005833208 0.04638743 -0.01447612 -0.004107773 0.04648512 0.0446999 -0.001632511 0.04658234 -0.02750074 -0.02234756 0.0441634 0.0446999 -0.0274074 0.04294329 -0.02369666 -0.02812045 0.04274642 0.0446999 -0.03108698 0.04185283 -0.01991093 -0.03386771 0.04089498 0.0446999 -0.03474622 0.04056537 0.0446999 -0.03833544 0.03906434 -0.01622378 -0.039469 0.03853231 0.0446999 -0.04180258 0.03733366 -0.0144574 -0.04215437 0.03713965 -0.01276397 -0.04473066 0.03559547 0.0446999 -0.04509544 0.03535735 -0.01272195 -0.04566562 0.03497397 0.02079665 -0.04663026 0.034294 0.01590538 -0.04817724 0.0331152 0.0446999 -0.04817283 0.03311115 -0.04575681 -0.05062073 0.03093159 -0.0493766 -0.04774707 0.03345751 -0.05392754 -0.04418224 0.03593659 -0.0287618 -0.05254894 0.02887016 0.02105933 -0.04859441 0.03277134 0.03069132 -0.0499897 0.03154164 0.0446999 -0.05099028 0.03056728 0.03587883 -0.0511015 0.03044575 0.04013627 -0.05222618 0.02924627 0.0446639 -0.05349349 0.02770233 -0.03110498 -0.04895442 0.03187298 -0.03907173 -0.04501354 0.03481429 -0.03542989 -0.04779809 0.0315178 -0.0506227 -0.03606468 0.03961032 -0.04880541 -0.03363686 0.04056054 -0.03858941 -0.04246819 0.0364964 -0.05112975 -0.03565621 0.03861421 -0.04528379 -0.04020214 0.0364871 -0.03248471 -0.05007994 0.02935796 -0.04070287 -0.04375016 0.03444248 -0.03099769 -0.04914933 0.03028851 -0.03523063 -0.04537433 0.03334939 -0.04368036 -0.038064 0.03753811 -0.04866588 -0.03375422 0.03934997 -0.03932201 -0.04183465 0.03559821 -0.04523879 -0.03301459 0.040811 -0.03386223 -0.04004991 0.03781205 -0.02611696 -0.04775607 0.03285932 -0.03399503 -0.04307633 0.03601527 -0.03060555 -0.04606205 0.03290766 -0.04351854 -0.03047853 0.04048514 -0.04531121 -0.03295099 0.03964674 -0.0380485 -0.02785009 0.04242032 -0.02733731 -0.04005736 0.03777962 -0.02132165 -0.04694372 0.03349477 -0.02968281 -0.04083067 0.03752732 -0.04065346 -0.02948957 0.0408135 -0.03791832 -0.02799481 0.04123413 -0.03499835 -0.02740502 0.04246258 -0.03214055 -0.02621078 0.04281032 -0.01697784 -0.04613411 0.03415101 -0.01937431 -0.0459243 0.03305792 -0.02724307 -0.03663438 0.03938651 -0.03340578 -0.02456945 0.04215043 -0.03561973 -0.02665716 0.0416119 -0.02824789 -0.0221284 0.04370933 -0.02230012 -0.03113621 0.04125672 -0.01594167 -0.04077887 0.03737461 -0.01521438 -0.04513961 0.03362464 -0.02202397 -0.03584408 0.03975874 -0.02798736 -0.02251023 0.04259592 -0.03109192 -0.02332383 0.04242646 -0.03043955 0.02768003 0.04323196 -0.02845561 0.0252676 0.04381078 -0.02469491 0.0356003 0.04107999 -0.01284813 0.04892992 0.03452837 -0.02230018 0.03457391 0.04125672 -0.03571504 0.02998083 0.04278039 -0.02672755 0.04068398 0.03902113 -0.025424 0.03845471 0.04004555 -0.03808462 0.0312581 0.04234886 -0.03377074 0.04005295 0.03937423 -0.02128374 0.05042707 0.03346061 -0.03154784 0.03869372 0.03979659 -0.02613002 0.05117183 0.03304988 -0.03654319 0.04082477 0.03891813 -0.03876692 0.04224663 0.03838807 -0.0282188 0.05167764 0.03262215 -0.03106397 0.05242848 0.03183853 -0.04860448 0.03724408 0.04059219 -0.03675633 0.0474919 0.03557932 -0.04985696 0.04009568 0.03933471 -0.03907179 0.04845124 0.03481429 -0.0478751 0.04528504 0.03674471 -0.05576795 0.04308164 0.03797912 -0.0430181 0.05157077 0.03267449 -0.03805255 -0.05140548 0.02793782 -0.04390192 -0.04754734 0.03171753 -0.05064105 -0.04306042 0.03491091 -0.04128891 -0.04680448 0.03228336 -0.04721575 -0.04234462 0.03532987 -0.03723341 -0.04986089 0.02960133 -0.02256309 -0.04219979 0.03538787 -0.02663284 -0.03735888 0.03785973 -0.03082549 -0.03237169 0.03983831 -0.02064609 -0.0412864 0.0359261 -0.02478641 -0.03585457 0.03850853 -0.02872848 -0.03068405 0.0404067 -0.01721787 -0.04579961 0.03306615 -0.01793587 -0.04704797 0.03209257 -0.01299142 -0.04552215 0.03327196 -0.01488012 -0.04238742 0.03527706 -0.0184679 -0.03694748 0.03804206 -0.01664161 -0.03971695 0.03673619 -0.02034032 -0.0341081 0.03920346 -0.02414637 -0.02833688 0.0411235 -0.01910823 -0.03985786 0.03669244 -0.02551418 -0.03103464 0.04030758 -0.0357002 -0.04155123 0.03575843 -0.0401467 -0.03757429 0.0377627 -0.02851903 -0.04532343 0.0334829 -0.03437858 -0.0395376 0.03682667 -0.03856408 -0.03537911 0.03870368 -0.02695858 -0.0491653 0.03027254 -0.02255129 -0.0480929 0.03123146 -0.02384114 -0.0440033 0.03437125 -0.02944982 -0.03764832 0.03772908 -0.03351426 -0.03301364 0.03960978 -0.02638405 -0.04422968 0.03417611 -0.03118723 -0.03927803 0.03695601 -0.03548896 -0.03484314 0.03891825 -0.09619659 -0.001478731 0.0319786 -0.09243255 -0.003605604 0.03200966 -0.09814882 0.001745998 0.02932673 -0.09740155 0.00257498 0.03205204 -0.09648829 0.006409525 0.03010088 -0.09472656 0.006156146 0.03201454 -0.08653271 0.004139184 0.03127533 -0.08974355 0.006049156 0.02880877 -0.08932548 -0.004025518 0.03049141 -0.08925896 -0.002309203 0.02883982 -0.08779841 -3.38929e-4 0.02898401 -0.0881856 0.002999782 0.02871572 -0.09441685 0.006626188 0.028728 -0.08582586 -1.43781e-4 0.03188973 -0.09724408 0.003050267 0.02887892 -0.09616971 -2.23543e-4 0.02891927 -0.0936976 -0.002299547 0.02885675 -0.09455281 0.005360186 0.02880609 -0.09174096 0.006026208 0.02901571 -0.0900703 0.005317091 0.02884411 -0.08897513 -7.94473e-4 0.0288735 -0.09062689 -0.002194464 0.02884411 -0.09644782 0.002083778 0.02878135 -0.09593373 0.003548979 0.02885508 -0.08829754 0.001105785 0.02878266 -0.0900436 0.005360245 0.03204411 -0.08816814 0.002743244 0.03204411 -0.08867096 -3.8594e-4 0.03188461 -0.08954393 -0.001524984 0.03201735 -0.09329324 -0.002533197 0.03195673 -0.09633225 5.71037e-4 0.03204411 -0.09647446 0.002105772 0.03204411 -0.0958445 0.003870427 0.03194683 -0.09307599 0.005878925 0.03204411 -0.09512382 0.00481826 0.03204411 -0.09564524 -8.08699e-4 0.03204411 -0.08829015 0.00483042 0.03205096 -0.08723664 0.001777172 0.03202301 -0.08834892 -0.001461327 0.03202712 0.02601224 0.01848506 0.03752338 0.02718484 0.01518368 0.03754854 0.02578651 0.01696342 0.03905326 0.02933502 0.01458919 0.04095292 0.03047144 0.01518869 0.03756505 0.02829253 0.01461666 0.04054933 0.02671146 0.01545399 0.04392111 0.02720904 0.02002185 0.03755211 0.02861952 0.02081525 0.0404455 0.03076803 0.01979112 0.03755736 0.03089141 0.01976448 0.04326921 0.03181612 0.01696753 0.03794103 0.02880817 0.01595276 0.03740769 0.03046685 0.01756763 0.03740602 0.02884274 0.01923692 0.03740531 0.02718359 0.0176016 0.03740334 0.06249618 0.01535499 0.03756731 0.06162697 0.01448392 0.04240733 0.06073373 0.01438951 0.03969269 0.05864399 0.01537835 0.0375213 0.0586465 0.01530474 0.04306191 0.06002676 0.01441895 0.04277843 0.05752182 0.01702934 0.04309004 0.05757331 0.01800382 0.03969752 0.05773723 0.01846075 0.03751015 0.05838793 0.01964497 0.04294121 0.05899047 0.02004349 0.03755587 0.06054377 0.02082884 0.0395891 0.06210196 0.02007168 0.03756797 0.06002098 0.02080905 0.04255133 0.06338185 0.01882028 0.04183179 0.06341701 0.01845395 0.03757631 0.0636391 0.0174601 0.03977477 0.06202161 0.01679831 0.03740334 0.05979424 0.01618713 0.03748387 0.06134623 0.01905339 0.03740304 0.05912041 0.01836836 0.03740274 0.05898267 -0.01171129 0.03755497 0.05768722 -0.01495915 0.03752952 0.05755472 -0.01353126 0.03906512 0.06075865 -0.01735794 0.04027718 0.06210279 -0.01663321 0.03756785 0.06305563 -0.01585251 0.04190766 0.05900871 -0.01662516 0.03756153 0.06001001 -0.01721608 0.04249495 0.05740678 -0.01480817 0.04314494 0.05839222 -0.01209235 0.0430777 0.06045722 -0.01094865 0.03926265 0.06211823 -0.01167112 0.03757494 0.06310218 -0.01248466 0.04199582 0.06119799 -0.01083934 0.04248052 0.06378912 -0.01423996 0.03810679 0.06002318 -0.01093631 0.04277634 0.06135815 -0.01560819 0.03740036 0.06179034 -0.01289242 0.03744029 0.05954533 -0.01297885 0.03750777 0.05912786 -0.01494204 0.03740024 0.02597779 -0.01326543 0.03751528 0.02720969 -0.01658457 0.03755229 0.02579629 -0.01478934 0.03905946 0.03181689 -0.01474648 0.03787374 0.03188365 -0.01475489 0.04393464 0.03069603 -0.01648503 0.04324686 0.02940535 -0.01721191 0.04353666 0.03044724 -0.01657915 0.03756719 0.02835226 -0.01720684 0.03934657 0.02664595 -0.01624065 0.0437476 0.02577745 -0.01360511 0.0439338 0.02677267 -0.01194262 0.04434478 0.02722293 -0.01174342 0.03757715 0.02932953 -0.01118308 0.03978085 0.03076756 -0.01196581 0.03755396 0.03084677 -0.01194041 0.04390877 0.02821177 -0.01717638 0.04356408 0.02828121 -0.0110442 0.04436963 0.03182965 -0.01360994 0.04401433 0.02992254 -0.01528263 0.03738981 0.02841579 -0.0156669 0.03738951 0.0303384 -0.01374101 0.03738617 0.02880269 -0.01251447 0.03740888 0.02718305 -0.01416939 0.03740435 0.06640338 0.01050347 0.04130643 0.06098914 0.01150441 0.04263865 0.06794738 0.01744759 0.04068368 0.06064903 0.02355855 0.04229974 0.06005799 0.01191002 0.04262506 0.05426168 0.0171225 0.04367202 0.05516082 0.01820409 0.04358595 0.05579531 0.0180453 0.0399295 0.09300345 0.02245086 0.02473187 0.09301364 0.01494771 0.0263701 0.09189158 0.01994985 0.02716881 0.09103906 0.02767783 0.02671426 0.08884888 0.02600646 0.02968567 0.08203041 0.03122013 0.03398227 0.081119 0.02247035 0.03531229 0.07668727 0.03045952 0.03664499 0.07439541 0.04166525 0.03625279 0.07985079 0.03857463 0.03405553 0.07893919 0.04021209 0.03434449 0.0826357 0.03619486 0.03277474 0.08711332 0.03073006 0.03041183 0.09669011 0.008852362 0.01440149 0.09693318 0.001061558 0.01320666 0.09635239 0.002901017 0.01890856 0.09613448 0.008225679 0.01942735 0.09582287 0.01422643 0.01878196 0.09548878 0.005653202 0.02267742 0.09466814 0.01527893 0.02291131 0.09432226 0.01036715 0.02474492 0.09247738 0.005782544 0.02810859 0.09036934 0.01592081 0.02952718 0.08787184 0.0167998 0.03178113 0.07381069 0.01537364 0.03886336 0.07761377 0.01323562 0.03747045 0.0717656 0.006144523 0.03978574 0.05238324 0.005670666 0.04432761 0.06351208 0.002862453 0.04212361 0.05844008 0.002606332 0.04324299 0.09153956 -0.00210309 0.02918606 0.08952295 0.003272414 0.03112483 0.07533383 0.001937329 0.03858852 0.07976114 0.002673387 0.03681218 0.06789875 -0.001524507 0.04097515 0.05503863 0.01162904 0.04381871 0.0690307 0.02622497 0.0398463 0.07292222 0.02517765 0.03860324 0.07259702 0.03580594 0.03774273 0.08432197 0.02024787 0.03374457 0.07726234 0.0223906 0.03711158 0.08255726 0.03742635 0.03253811 0.083498 0.03751415 0.03187578 0.0846942 0.0381183 0.03082555 0.08721703 0.04041534 0.02767777 0.0938853 0.02393352 0.02225434 0.09146726 0.0332877 0.02342349 0.09339135 0.02800327 0.02103662 0.08883213 0.04066711 0.02507114 0.09376049 0.03162151 0.01207631 0.09155052 0.04077643 0.01045048 0.09355622 0.03313541 0.007131934 0.09480458 0.02571529 0.01412969 0.09512436 0.02537083 0.007131934 0.09570145 0.02122485 0.01040995 0.09499752 0.02152699 0.01863604 0.09340381 0.03128409 0.0173878 0.09117347 0.04071968 0.01613014 0.09624809 0.0175296 0.007131934 0.09644907 0.01490366 0.01032584 0.09631353 0.01391464 0.01508337 0.09692382 0.009637057 0.007131934 0.09714931 0.001718938 0.007131934 0.09570574 0.01955646 0.01482725 0.08670449 0.00502485 0.03307545 0.08388227 0.01169854 0.03455156 0.08325815 0.004631519 0.03510189 0.08062028 0.01140248 0.03624576 0.09443581 0.003140389 0.02502489 0.09049159 0.04067623 0.02088099 0.06182849 0.01681679 0.04231727 0.05924355 0.01786828 0.04284 0.0608412 0.01893222 0.04245501 0.06026661 -0.01998496 0.04231482 0.05420017 -0.006323814 0.04398292 0.05423367 -0.01466417 0.04375422 0.05563181 -0.0146417 0.04031962 0.05574953 -0.01368743 0.0400629 0.05499672 -0.01356261 0.04363149 0.07460987 -0.004394233 0.03878182 0.07969945 -0.006809651 0.03670316 0.08349704 -0.00515449 0.03486502 0.08625906 -0.003070414 0.0333383 0.08811086 -0.007197976 0.03188037 0.08721107 -0.01722514 0.03176426 0.09015935 -0.01092433 0.02988702 0.08941489 -0.01966702 0.02962321 0.08732306 -0.02756005 0.03016656 0.0905494 -0.02359116 0.0275774 0.08759826 -0.03483861 0.02781397 0.09036487 -0.02814346 0.02632248 0.0903846 -0.03723675 0.02115464 0.09216356 -0.028934 0.022098 0.09320056 -0.02848893 0.01779001 0.09117352 -0.03728181 0.01613014 0.09154576 -0.03733277 0.01035076 0.09344202 -0.02954572 0.01221251 0.09355628 -0.02969753 0.007131934 0.04830443 -0.005761325 0.04493439 0.09357094 -0.003032386 0.02657556 0.09692382 -0.006199181 0.007131934 0.09547913 -0.004097163 0.02260142 0.09593445 -0.01085191 0.01881355 0.09624814 -0.01409167 0.007131934 0.09512442 -0.02193289 0.007131934 0.09610742 -0.01411169 0.01208889 0.09146571 -0.02704745 0.02479815 0.09370648 -0.02006042 0.0229116 0.09320563 -0.01584076 0.02540165 0.09142482 -0.01386523 0.02831119 0.09469741 -0.02271372 0.01475387 0.08911269 -0.03720873 0.02447527 0.08012557 -0.01355099 0.0361824 0.075832 -0.02157479 0.03749728 0.07451319 -0.009731292 0.03868317 0.08621311 -0.03716987 0.02896744 0.08375573 -0.0341947 0.0316649 0.08288806 -0.03400272 0.03236895 0.08468794 -0.02369576 0.03274565 0.07972586 -0.03377085 0.03433221 0.07294708 -0.03282618 0.03755503 0.06887817 -0.03443062 0.03888028 0.07144051 -0.0205084 0.0392155 0.06689482 -0.02453041 0.04036569 0.06367182 -0.02265256 0.04139637 0.07629626 -0.03739291 0.03552609 0.07746201 -0.02787518 0.03620558 0.05806416 -0.02194631 0.04270595 0.05508387 -0.01746314 0.04355973 0.05223608 -0.01312845 0.0441938 0.06027352 -0.007967889 0.04280149 0.06749606 -0.01435679 0.04081487 0.08134883 -0.02255505 0.03486043 0.06599271 -0.008725166 0.04138553 0.09676259 -0.004826307 0.01400345 0.09632915 -0.01007837 0.01500999 0.09413099 -0.02220851 0.01968747 0.09548592 -0.01686418 0.01628381 0.09511584 -0.01021522 0.02202385 0.08500462 -0.01311409 0.03362649 0.06190991 -0.01446068 0.04223936 0.0592513 -0.0144627 0.04283767 0.06110638 -0.01296174 0.04247426 0.06057089 -0.01545763 0.04251378 0.02296864 -0.01340693 0.04409915 0.0234465 -0.01369285 0.04124772 0.02222484 -0.0149517 0.0439071 0.02224153 -0.01346951 0.04414749 0.02339321 -0.01465588 0.04157 0.02542912 -0.01470202 0.04373222 0.02879953 -0.02049505 0.04295527 0.02826088 -0.02011907 0.04308688 0.02935355 -0.01987534 0.04306566 0.02938115 -0.01105266 0.04444104 0.0293194 -0.01909565 0.04033362 0.0446999 -0.001581132 0.04508322 0.0247718 -0.004264891 0.04497528 0.006088852 -0.005392551 0.04491031 0.002822875 -0.007634162 0.0447548 0.008574247 -0.009578645 0.04458457 0.001874268 -0.01164299 0.04436892 -0.002671957 -0.01452732 0.04400581 -0.02375537 -0.01424199 0.04404503 0.0446999 -0.01222234 0.0443018 0.03811073 -0.008836627 0.04465323 0.0446999 -0.005025029 0.04493379 0.03501677 -0.01365029 0.04406946 0.03511995 -0.01470363 0.0439372 0.03935897 -0.01630645 0.04374468 0.0446999 -0.01962894 0.04317688 0.0446999 -0.02700066 0.04149943 0.01847815 -0.02432775 0.04217994 0.0446999 -0.0305972 0.04043471 0.02283197 -0.02945816 0.0407918 0.02579212 -0.03203231 0.03995633 -3.36092e-4 -0.0315265 0.04012864 -0.002673506 -0.03466129 0.03898972 0.02818948 -0.03629648 0.03832298 2.45009e-4 -0.03856724 0.0373013 0.004413187 -0.04059278 0.0362817 0.00335294 -0.04386544 0.03436857 0.0446999 -0.04397398 0.03429847 0.0304144 -0.04567635 0.03313291 0.0446999 -0.04696822 0.0321542 0.01862621 -0.04692929 0.03218501 0.02409291 -0.04749536 0.03172773 0.01313328 -0.04660582 0.03243786 0.006724357 -0.04534602 0.0333693 0.0446999 -0.03409337 0.03920906 0.02377927 -0.03897494 0.03710484 0.0446999 -0.03747951 0.03780549 0.0446999 -0.04079061 0.0361759 0.02657133 -0.04156833 0.03574883 0.02964258 -0.04833084 0.03104192 0.04507005 -0.05224651 0.02687942 0.0371077 -0.04988348 0.02957445 0.0446999 -0.0497123 0.02972441 0.007603943 -0.04651612 0.032507 0.00207138 -0.04665255 0.03240174 -0.003427445 -0.0470035 0.03212618 -0.008804917 -0.04754728 0.03168481 -0.01396214 -0.04825013 0.03108632 -0.01886725 -0.04908019 0.03033417 -0.02435684 -0.05017852 0.02926236 -0.03369152 -0.05253732 0.02651965 -0.03744608 -0.05526071 0.0220049 -0.0401411 -0.05347275 0.02514779 -0.04752445 -0.0478605 0.03149193 -0.0541948 -0.0434513 0.03460633 -0.0625422 -0.03817421 0.03752744 -0.06267189 -0.03656584 0.03821766 -0.05451375 -0.03268229 0.03972625 -0.04764294 -0.02904987 0.0409125 -0.03335618 -0.02111935 0.04288643 -0.006159722 -0.0197491 0.04315429 -0.02687209 -0.01665866 0.04368948 0.0100879 -0.01740646 0.04356849 0.01055771 -0.02171838 0.04276311 -0.006201624 -0.02564191 0.0418564 0.02944326 -0.008044421 0.04472088 0.02887582 -0.007397472 0.04476416 0.02830743 -0.007845282 0.0446738 0.02781665 -0.01505547 0.04394 0.03006029 -0.01345551 0.04417955 0.0294457 -0.01528584 0.04390996 0.02792882 -0.01315027 0.04421079 0.03325933 -0.01372462 0.03958636 0.02832007 -0.009849667 0.03993982 0.02924901 -0.009357035 0.03975832 0.02292561 0.01811414 0.04308605 0.02929019 0.01157331 0.04270839 0.0343402 0.01706361 0.04373687 0.02938354 0.02340394 0.04267406 0.02835214 0.01284831 0.03987878 0.02388876 0.01710498 0.04021418 0.0288707 0.01902067 0.04387629 0.03012108 0.01723313 0.04414272 0.02847558 0.01629471 0.0442366 0.02753806 0.0176447 0.0440613 0.03243637 0.01809513 0.03913277 0.03366672 0.01715952 0.03986722 0.02838671 0.02241545 0.04003971 0.06240719 -0.02622073 0.04170763 0.06731206 -0.03441154 0.03908693 0.06408727 -0.03033995 0.04051703 0.06090199 -0.05058085 0.02882641 0.06441038 -0.04839658 0.03095567 0.06619244 -0.04610174 0.03281944 0.06653124 -0.04362589 0.03452157 0.07106542 -0.0403372 0.03644555 0.06851398 -0.0362966 0.03832048 0.05884516 -0.05247193 0.02655798 0.04842334 -0.05347669 0.02513688 0.05630183 -0.05451422 0.0234282 0.0499432 -0.05509704 0.02232629 0.05193787 -0.05741697 0.01589751 0.04762977 -0.00264275 0.0465573 0.0495243 -0.008282423 0.04621279 0.05535483 -0.01777869 0.0450282 0.0587269 -0.02230119 0.0441758 0.06192821 -0.02649337 0.04318612 0.06511259 -0.03076231 0.04195576 0.06731206 -0.0349527 0.04048585 0.06859475 -0.03714692 0.0395832 0.06847327 -0.04171437 0.0373817 0.06649714 -0.04447501 0.03575921 0.0665009 -0.0470795 0.03396052 0.06218862 -0.04957127 0.03191941 0.06151837 -0.05183488 0.02967661 0.05881768 -0.05388194 0.02717441 0.04762554 -0.05472755 0.02596616 0.0556544 -0.0562275 0.02347874 0.04942286 -0.05632895 0.02322506 0.05112326 -0.05827903 0.01835608 0.0523917 -0.05881935 0.01638323 0.05417871 -0.008242249 0.045484 0.05280816 0.001054048 0.04578542 0.09851628 -7.59538e-4 0.01101166 0.09817409 -0.00512433 0.01520079 0.09827214 0.004173398 0.01563692 0.09773761 -0.004243671 0.01983404 0.09553939 -0.01521533 0.02386587 0.09632658 -0.002667546 0.02462321 0.09518665 -0.00967437 0.02609485 0.09380668 -0.02022337 0.02611958 0.09376746 -0.02416193 0.02481436 0.0917741 -0.02882385 0.02673321 0.09161698 -0.03308856 0.02506673 0.08958697 -0.03324353 0.02832335 0.08951747 -0.04079359 0.02500915 0.08649492 -0.04093903 0.02935934 0.09525585 -0.02353459 0.02066034 0.09291732 -0.03266543 0.02192169 0.09506732 -0.02648198 0.01866769 0.09659403 -0.02162045 0.01130753 0.09529012 -0.02749186 0.01485013 0.09731215 -0.01681739 0.01153403 0.09785449 -0.01227915 0.01108163 0.08335155 -0.0201559 0.03574311 0.08367913 -0.01202338 0.03619241 0.079279 -0.01898461 0.03787487 0.07879811 -0.02704149 0.0373364 0.07941395 -0.03952461 0.03526186 0.0826649 -0.02841889 0.03514939 0.08600306 -0.003281354 0.03522664 0.08759886 -0.01320767 0.03383243 0.08914744 2.33689e-4 0.03320544 0.08461821 0.001718938 0.03611153 0.08199316 -0.004920482 0.03735214 0.07841432 -0.01275283 0.03862947 0.07416856 -0.02462553 0.03951561 0.07494151 -0.03763931 0.03778594 0.07140243 -0.03084141 0.03995048 0.06820791 -0.03384095 0.040762 0.07818233 -0.004219114 0.03904503 0.07491582 0.001718878 0.04035675 0.07436841 -0.01059472 0.04030567 0.07000416 0.001718878 0.04195773 0.06857043 -0.005866706 0.04227423 0.05848705 -0.008513867 0.0446819 0.06112706 0.002589225 0.0442183 0.06742346 -0.02370566 0.04184108 0.07181334 -0.01662957 0.0409066 0.0679652 -0.01549553 0.04215979 0.06417554 -0.01071143 0.04333257 0.08570015 -0.03069967 0.03274995 0.09143322 -0.02290976 0.02906864 0.09302377 -0.0143662 0.0287193 0.09048211 -0.01291269 0.03147947 0.09169703 -0.001231312 0.03119665 0.08900165 -0.02943402 0.03020662 0.08463621 -0.03915393 0.03179496 0.09094601 -0.04184472 0.01935285 0.09350085 -0.03431761 0.01651579 0.09202444 -0.04070556 0.01059198 0.09347391 -0.03568613 0.01172643 0.09456402 -0.03129559 0.01256912 0.09298652 -0.03466933 0.01948785 0.06594097 0.002514421 0.04308146 0.07985275 0.001718938 0.03842157 0.09344702 -0.009308218 0.02866458 0.09405928 0.002589166 0.02861702 0.09763413 0.004147529 0.02073204 0.09635776 -0.01559787 0.0211209 0.09772717 -0.008817434 0.01733732 0.09731078 -0.0141673 0.01658558 0.09439325 -0.02476936 0.02289712 0.08539229 -0.02312588 0.03418689 0.088099 -0.02209967 0.03234428 0.09648948 -0.02000081 0.01673203 0.08612316 -0.03726738 0.01777678 0.08593887 -0.03622502 0.02925002 0.0854333 -0.03537905 0.03021627 0.08468365 -0.03467386 0.03080415 0.08153927 -0.03412479 0.03316754 0.08054941 -0.03456497 0.03367155 0.07985031 -0.03513801 0.0339958 0.07929182 -0.03589171 0.03450167 0.07894074 -0.03677296 0.03422141 0.0788213 -0.03770601 0.03419423 0.07917302 -0.03927838 0.03353041 0.07987505 -0.04029172 0.03269809 0.08085918 -0.0410152 0.03186994 0.08210635 -0.04128313 0.01875525 0.0820021 -0.04154318 0.03071302 0.0820412 -0.04473358 0.02624714 0.08207088 -0.04579299 0.02282577 0.08217972 -0.04651117 0.01792716 0.08218282 -0.04685479 0.01012068 0.06925636 -0.0507726 0.02111345 0.06901323 -0.05122524 0.01849025 0.0545538 -0.05654048 0.01822757 0.05978393 -0.05393505 0.02259826 0.06940597 -0.05137854 0.01428365 0.05330121 -0.05730909 0.01242935 0.06391936 -0.05017566 0.0286327 0.07354468 -0.04739356 0.02713578 0.06021422 -0.05285763 0.02562761 0.07987159 -0.04349398 0.0300365 0.07128477 -0.04925376 0.02444046 0.07494908 -0.04301744 0.03275239 0.04882442 -0.05465871 0.01386898 0.0446999 -0.05552327 0.007131934 0.0446999 -0.05368655 0.02721577 0.05741745 -0.05695557 0.01936113 0.05556941 -0.05788624 0.01653218 0.05903762 -0.05577421 0.02285915 0.06215059 -0.05338478 0.02699935 0.05411797 -0.05857712 0.01351511 0.06598722 -0.05030262 0.03017765 0.06584036 -0.04897493 0.0321092 0.07165902 -0.04069787 0.03784167 0.07003277 -0.05215239 0.02086561 0.07465577 -0.05075538 0.01871228 0.07600486 -0.05049192 0.0159744 0.07198351 -0.05216187 0.01007741 0.08577257 -0.04703384 0.01407951 0.0852769 -0.04686176 0.01886999 0.08524775 -0.04612439 0.02344077 0.07203292 -0.05047333 0.02502954 0.08272111 -0.04608601 0.02645683 0.08102178 -0.04455453 0.03059685 0.08241033 -0.0451681 0.02872663 0.07732421 -0.0427981 0.03431046 0.08789473 -0.04435235 0.02321797 0.0864619 -0.04360127 0.02696055 0.08200198 -0.04300153 0.03170889 0.08728671 -0.04609304 0.01801449 0.08961248 -0.04445159 0.01611083 0.0815882 -0.03603094 0.01183187 0.08255767 -0.03577119 0.01183187 0.08087849 -0.03674066 0.01183187 0.08061873 -0.03771013 0.01183187 0.08087849 -0.03867959 0.01183187 0.0815882 -0.03938931 0.01183187 0.08255767 -0.03964906 0.01183187 0.0835272 -0.03938931 0.01183187 0.08423686 -0.03867959 0.01183187 0.08449667 -0.03771013 0.01183187 0.08423686 -0.03674066 0.01183187 0.0835272 -0.03603094 0.01183187 0.08638083 -0.03996443 0.02768337 0.08977949 -0.03819406 0.02242791 0.08789902 -0.04159271 0.0237078 0.09064352 -0.03815722 0.01824122 0.08965361 -0.04162484 0.01743292 0.09132492 -0.03808903 0.01032525 0.0862087 -0.04450696 0.02104991 0.08778584 -0.04408001 0.01591604 0.08603477 -0.04521346 0.01612597 0.08309388 -0.04392552 0.02753508 0.08304309 -0.04539781 0.02263903 0.08299237 -0.04629051 0.01682543 0.08290773 -0.04662799 0.007131934 0.0830056 -0.04127991 0.01834368 0.08310735 -0.04136967 0.0300064 0.08612173 -0.03815162 0.01759856 0.08572006 -0.03920978 0.007131934 0.08590239 -0.03925573 0.02828675 0.08546251 -0.03997933 0.02846366 0.08503252 -0.04018497 0.007131934 0.08480972 -0.04063183 0.02878177 0.08405727 -0.04087251 0.007131934 0.08401077 -0.04110509 0.02923697 0.08620822 -0.03824907 0.02870005 0.0781635 -0.04073393 0.03350818 0.08315408 -0.03620058 0.02167135 0.08382236 -0.03668922 0.02141606 0.08415722 -0.03738683 0.02066355 0.08396959 -0.03693807 0.03085041 0.08255666 -0.03614652 0.03209739 0.08153039 -0.03646129 0.02236402 0.08136188 -0.03671962 0.03278827 0.08102774 -0.0371921 0.02256852 0.08102154 -0.03783416 0.03277748 0.08145493 -0.03881746 0.03225302 0.08098363 -0.03807812 0.02242672 0.08138167 -0.03882622 0.02187442 0.08208191 -0.03926253 0.02160179 0.08231729 -0.03610789 0.02200412 0.08411735 -0.03817337 0.02122199 0.08386588 -0.03860193 0.03048408 0.08370906 -0.0388655 0.02074819 0.0829609 -0.03927862 0.02208268 0.0826416 -0.0392673 0.03131151 0.06957501 0.0388199 0.04017567 0.05620664 0.01485854 0.04505759 0.05265969 0.01633679 0.04564082 0.0549314 0.00836867 0.04538518 0.07306969 0.02517241 0.04014748 0.07522696 0.01239264 0.04004192 0.0784136 0.02112066 0.03835058 0.08403235 0.02755945 0.03490638 0.08317559 0.01833897 0.03626573 0.08845371 0.01843386 0.03307682 0.08818405 0.02288222 0.0326507 0.08552181 0.03146564 0.03338092 0.08762836 0.03071624 0.03187304 0.08827298 0.03608834 0.03012281 0.09070682 0.02737468 0.02956289 0.09231418 0.02612292 0.02793866 0.0903393 0.03626382 0.02757114 0.09344613 0.02603513 0.02617788 0.09279876 0.03224158 0.02479195 0.09383881 0.03487843 0.01934325 0.094141 0.03033 0.02262133 0.09510338 0.03031736 0.01792562 0.09452134 0.03447353 0.0144236 0.09571504 0.0294615 0.01287126 0.09343355 0.03936666 0.01072818 0.09247368 0.0416575 0.01567649 0.08896774 0.04403477 0.02608013 0.09106576 0.0392068 0.024706 0.09074932 0.04459065 0.02134811 0.08390223 0.009964048 0.03633111 0.08695048 0.006156563 0.03467011 0.08852344 0.01040601 0.03347653 0.09210038 0.01525956 0.03011763 0.09432578 0.01221013 0.02767622 0.09617972 0.004971504 0.02476185 0.09568428 0.01469177 0.02458679 0.09683436 0.01197642 0.02199572 0.09669291 0.02259349 0.01595205 0.09784168 0.01315742 0.01541292 0.09789055 0.01546996 0.01061171 0.09672749 0.02411359 0.01178205 0.09613382 0.02336394 0.01937603 0.09588491 0.02016276 0.0222916 0.09305608 0.01909267 0.02831947 0.09031915 0.02268981 0.03083431 0.07962626 0.01266008 0.03828364 0.09439551 0.01623511 0.02682816 0.09732657 0.01418817 0.01896667 0.09838855 0.00721544 0.01287269 0.09238934 0.03931152 0.02071136 0.08682942 0.04405748 0.02911496 0.08429211 0.04402905 0.03157615 0.08532536 0.0375843 0.03234881 0.0810796 0.04236781 0.03440964 0.07737916 0.02955901 0.03807049 0.06891196 0.01630038 0.04197776 0.06795406 0.02661788 0.04172587 0.06129515 0.02114731 0.04377377 0.08084303 0.0334025 0.03596746 0.08137708 0.02624917 0.03654325 0.07523447 0.04167574 0.03758978 0.06330281 0.0141502 0.04354488 0.0861231 0.04070532 0.01777678 0.08620613 0.04061019 0.02867251 0.08210629 0.044721 0.01875525 0.08085548 0.04444932 0.03169542 0.0820018 0.04498094 0.03072512 0.07987463 0.04373055 0.03286325 0.07917153 0.04271489 0.03366672 0.07883673 0.04147076 0.03405219 0.0792914 0.0393297 0.03453928 0.08054924 0.03800284 0.03369033 0.08153921 0.03756266 0.03316754 0.08542686 0.03881287 0.02998203 0.08594113 0.03966212 0.02946799 0.08213579 0.05013501 0.0153746 0.08209919 0.04980355 0.01941698 0.08206963 0.04919946 0.02293646 0.08203804 0.04799765 0.02660769 0.08218204 0.05029135 0.01007491 0.06799769 0.05539619 0.01260828 0.05283045 0.06096798 0.01031881 0.05405604 0.06039524 0.01448196 0.05587482 0.05932945 0.01948046 0.06736898 0.05503612 0.02014487 0.05978381 0.05737286 0.02259826 0.07388865 0.05120795 0.025972 0.08071631 0.04750698 0.02860182 0.06311792 0.05391699 0.02860909 0.06636989 0.05118596 0.03091961 0.07605826 0.04468882 0.03404664 0.07787948 0.04598462 0.03216642 0.0627579 0.05528295 0.02596169 0.06252956 0.05662739 0.0271511 0.0641697 0.0543887 0.03019082 0.06696784 0.05043035 0.03389042 0.07119649 0.04427707 0.03783398 0.05529397 0.06126886 0.01852953 0.0545637 0.0618056 0.01453673 0.05891799 0.05926036 0.02283233 0.07279628 0.04987686 0.03210574 0.05334132 0.06237828 0.01033127 0.07716643 0.0536946 0.01106822 0.07023561 0.05603861 0.01580071 0.08554327 0.04990297 0.02120977 0.08543676 0.05035388 0.01785773 0.07007259 0.05559217 0.02075368 0.08577251 0.05047172 0.01407951 0.07228326 0.05417019 0.02375596 0.08541816 0.04924881 0.02428108 0.08272099 0.04952389 0.02645683 0.08181804 0.04766649 0.03064632 0.08253014 0.04881811 0.02824205 0.07782387 0.04597777 0.03437983 0.08862519 0.04739493 0.02258235 0.08943372 0.048258 0.01507121 0.08609336 0.04700332 0.02744489 0.09098339 0.04607552 0.01523244 0.08352708 0.03946882 0.01183187 0.08255761 0.03920906 0.01183187 0.0842368 0.04017853 0.01183187 0.08449661 0.041148 0.01183187 0.0842368 0.04211747 0.01183187 0.08352708 0.04282718 0.01183187 0.08255761 0.04308694 0.01183187 0.08158814 0.04282718 0.01183187 0.08087843 0.04211747 0.01183187 0.08061867 0.041148 0.01183187 0.08087843 0.04017853 0.01183187 0.08158814 0.03946882 0.01183187 0.09134095 0.04152637 0.01032221 0.09064346 0.04159516 0.01824122 0.08969438 0.04463005 0.018588 0.08899116 0.0416547 0.02458608 0.0853061 0.04514753 0.027574 0.0870018 0.04639768 0.02337604 0.08305317 0.04872351 0.02373152 0.08666735 0.0481348 0.01853513 0.08308547 0.04720121 0.02740454 0.08949011 0.04609614 0.0113247 0.08290958 0.05011832 0.007137537 0.08299231 0.04972845 0.01682543 0.08300554 0.04471778 0.01834368 0.08310735 0.04498511 0.03000605 0.08621358 0.04168903 0.02864825 0.08612167 0.04158955 0.01759856 0.08590233 0.04269361 0.02828675 0.08572 0.04264765 0.007131934 0.08546245 0.04341721 0.02846366 0.08503246 0.04362291 0.007131934 0.08480966 0.0440697 0.02878177 0.08405721 0.04431045 0.007131934 0.08401072 0.04454296 0.02923697 0.08206522 0.03960132 0.02166056 0.08137089 0.04005062 0.02244472 0.08098518 0.04075187 0.02184677 0.0813682 0.04011756 0.03278952 0.08102595 0.04126757 0.03278118 0.08274298 0.03962463 0.03195828 0.08394742 0.0403276 0.03087967 0.08293706 0.03957921 0.02271139 0.08368331 0.03996306 0.0203731 0.08410191 0.04065227 0.02180474 0.08413165 0.04155784 0.02128297 0.08386516 0.04204154 0.03049147 0.08372139 0.0422908 0.02076023 0.08296674 0.04271501 0.02207791 0.08099246 0.04155325 0.02239269 0.08139008 0.04227304 0.02186614 0.0814644 0.04226267 0.03224307 0.08208686 0.04270195 0.02159988 0.08264118 0.0427047 0.03131067 -0.008241295 0.05215376 0.01770561 -0.01360297 0.05267977 0.01928681 -0.008976519 0.05316567 0.007131934 -0.01468384 0.05390954 0.007131934 -0.002872526 0.05259215 0.007131934 -0.02300536 0.05430048 0.01875334 -0.02855151 0.05559664 0.01723295 -0.01847779 0.05450618 0.007133901 -0.03445774 0.05714786 0.01573938 -2.84552e-4 0.051768 0.01458078 0.00701934 0.05122941 0.01796996 0.01026475 0.05218756 0.007131934 0.0120151 0.05113822 0.0195384 0.01668733 0.05243068 0.007134735 0.02122563 0.05170571 0.01947128 0.02822172 0.05366295 0.007131934 0.02653735 0.05234885 0.01921832 0.02274042 0.05294579 0.007131934 0.03174144 0.05321264 0.01885503 0.03317528 0.05452698 0.007131934 0.03683531 0.05529952 0.007136046 0.0413655 0.05555182 0.01684653 0.04554188 0.05676072 0.01679009 0.04025971 -0.05425739 0.007131934 0.03473615 -0.05138909 0.00714153 0.02816641 -0.05021238 0.007140696 0.02274054 -0.04950797 0.007131934 0.01674902 -0.04899728 0.007131934 0.009714245 -0.05023384 0.007131278 0.01026481 -0.04874974 0.007131934 0.003564655 -0.04880988 0.007131934 -2.00244e-4 -0.05045467 0.007134437 -0.002872467 -0.0491544 0.007131934 -0.02173227 -0.05164927 0.007130503 -0.02593672 -0.05401569 0.007132172 -0.02971214 -0.05333203 0.007131934 -0.07544434 -0.03991574 0.007131934 -0.07470959 -0.03841012 0.007130563 -0.0881465 -0.03841543 0.007131934 -0.08955717 -0.03991186 0.007131934 -0.09039759 -0.03548264 0.007131338 -0.09144216 -0.03274518 0.007132411 -0.09303694 -0.03379398 0.007131934 -0.08880889 -0.03526639 0.00713402 -0.004135847 -0.04852509 0.03263992 -0.02479994 -0.05235493 0.02327704 0.01090216 -0.04799747 0.03306108 -0.01675975 -0.05061656 0.0263046 0.02533239 -0.04935061 0.02963519 0.005898594 -0.04799437 0.03301674 0.03952699 -0.05307132 0.01819235 0.03374624 -0.05225962 0.01249623 0.02893 -0.05120277 0.01461434 0.02279353 -0.05039155 0.01445192 0.02721416 -0.05028587 0.02195531 0.03191304 -0.05089086 0.02392691 0.01967626 -0.0491777 0.02483838 0.01794755 -0.04970359 0.0172016 0.01461982 -0.0499354 0.01231288 0.009756684 -0.04866427 0.02534013 0.0030061 -0.04874795 0.0253365 -0.002783179 -0.04884195 0.02782791 -0.005758464 -0.04978978 0.01988834 -3.4932e-4 -0.04999017 0.01289355 0.006133258 -0.04959189 0.01478594 0.01135206 -0.04938399 0.01732444 0.01474016 -0.04904836 0.02250534 -0.01060748 -0.0499255 0.02431493 -0.02878922 -0.05382853 0.01642739 -0.01454025 -0.0513336 0.01440632 -0.02080023 -0.05216282 0.0166881 0.03999042 -0.05170643 0.01737147 0.02042192 -0.04845845 0.01648789 0.01392024 -0.04802054 0.01665979 0.01760864 -0.04737132 0.02631556 0.01042681 -0.04709964 0.02601832 0.02535825 -0.04850387 0.02208703 0.03190678 -0.0495823 0.02141404 0.03738558 -0.05050176 0.0237261 0.007278621 -0.04791176 0.01662164 0.003731667 -0.04715305 0.0260002 6.04826e-4 -0.04810231 0.01667833 -0.003374993 -0.04751545 0.02624613 -0.00605607 -0.04860401 0.01652264 -0.01045542 -0.04831266 0.02516311 -0.01146966 -0.04948776 0.01326525 -0.01585245 -0.04934847 0.02188163 -0.01894658 -0.05066025 0.01268464 -0.02129101 -0.05056458 0.01845961 -0.02699398 -0.0521844 0.01311939 -0.03777837 -0.0556268 0.01960307 -0.05195349 -0.04631495 0.03076767 -0.0514208 -0.04627883 0.03205937 -0.06175637 -0.04027611 0.03510731 -0.06071823 -0.04092454 0.03403502 -0.06310957 -0.03977638 0.03472268 -0.06791502 -0.03769403 0.03635603 -0.07124799 -0.03607231 0.03620636 -0.1017403 0.02407771 0.01183187 -0.1027742 0.02380067 0.01183187 -0.1009834 0.02483463 0.01183187 -0.1007063 0.02586859 0.01183187 -0.1009834 0.02690255 0.01183187 -0.1017403 0.02765947 0.01183187 -0.1027742 0.02793651 0.01183187 -0.1038082 0.02765947 0.01183187 -0.1045651 0.02690255 0.01183187 -0.1048422 0.02586859 0.01183187 -0.1045651 0.02483463 0.01183187 -0.1038082 0.02407771 0.01183187 -0.103097 0.03097021 0.02088415 -0.1082811 0.02919101 0.0158652 -0.105264 0.02894049 0.02181911 -0.1098319 0.02857798 0.01167565 -0.1093443 0.02614766 0.01358717 -0.1063588 0.02616125 0.01963657 -0.1030227 0.0294485 0.02299588 -0.1042928 0.0291354 0.01888179 -0.1053216 0.02841591 0.01888179 -0.1060411 0.02738714 0.01888179 -0.1094003 -0.02269744 0.01328468 -0.1087262 -0.02492541 0.01515877 -0.1063532 -0.02273356 0.01998215 -0.1059702 -0.02471297 0.02066999 -0.103502 -0.02626574 0.02346146 -0.1030969 -0.02753257 0.02088415 -0.107594 -0.0262705 0.01613044 -0.1030796 -0.02602052 0.01888179 -0.106041 -0.0239495 0.01888179 -0.1053216 -0.02497833 0.01888179 -0.1042927 -0.02569782 0.01888179 -0.1017403 -0.02064013 0.01183187 -0.1009834 -0.02139699 0.01183187 -0.1007063 -0.02243101 0.01183187 -0.1009834 -0.02346497 0.01183187 -0.1027742 -0.02449893 0.01183187 -0.1048421 -0.02243101 0.01183187 -0.1038082 -0.02064013 0.01183187 -0.1027742 -0.02036303 0.01183187 -0.1017403 -0.02422189 0.01183187 -0.1038082 -0.02422189 0.01183187 -0.1045651 -0.02346497 0.01183187 -0.1045651 -0.02139705 0.01183187 -0.1024689 0.0294581 0.01888179 -0.1010567 0.02903652 0.01899158 -0.09992831 0.02807736 0.01888179 -0.09928113 0.02674949 0.01888179 -0.09922128 0.02527356 0.01888179 -0.09975874 0.02389764 0.01888179 -0.1008033 0.02285307 0.01888179 -0.1021791 0.02231556 0.01888179 -0.1036551 0.02237546 0.01888179 -0.104983 0.02302265 0.01888179 -0.1063638 0.02556329 0.01888179 -0.1063638 -0.02212572 0.01888179 -0.1024689 -0.02602052 0.01888179 -0.101054 -0.02559626 0.01888179 -0.09992831 -0.02463978 0.01888179 -0.09928107 -0.02331191 0.01888179 -0.09922122 -0.02183592 0.01888179 -0.09975874 -0.02046 0.01888179 -0.1008033 -0.01941549 0.01888179 -0.1021791 -0.01887798 0.01888179 -0.1036551 -0.01893788 0.01888179 -0.104983 -0.01958507 0.01888179 -0.1024459 -0.02769345 0.02152669 -0.1024181 -0.0262528 0.02402567 -0.09130913 -0.03199934 0.01567977 -0.08587259 -0.03334927 0.02096825 -0.07558733 -0.03569895 0.0331856 -0.08019119 -0.03528118 0.0208522 -0.0757597 -0.03734737 0.01470535 -0.08833312 -0.03525018 0.01143831 -0.08767175 -0.0382784 0.01493674 -0.0778824 -0.03823649 0.01704263 -0.08066129 -0.03820735 0.01892274 -0.08532291 -0.03821665 0.01851695 -0.07664108 -0.03751498 0.01518893 -0.03806632 -0.05714786 0.02006191 -0.04012554 -0.05574965 0.02218341 -0.06146538 -0.04221862 0.03416574 -0.0635882 -0.04119187 0.03485339 -0.08974111 -0.03370624 0.02014923 -0.09504824 -0.03128838 0.02689772 -0.1058392 -0.02852487 0.01730984 -0.09226167 -0.03325206 0.01583808 -0.08326375 -0.03568208 0.02247214 -0.07511711 -0.03897666 0.01662695 -0.06944119 -0.03919738 0.03501915 -0.07509064 -0.03973627 0.008488714 -0.07893711 -0.03969591 0.01968133 -0.08285373 -0.03967088 0.02060192 -0.08900624 -0.03973835 0.01682001 -0.08923304 -0.03696191 0.01572591 -0.09081679 -0.03432291 0.01394373 -0.09964174 -0.02954232 0.02614623 -0.1051177 -0.02822995 0.02112853 -0.1015819 -0.02701115 0.02643018 -0.1098639 -0.02683627 0.01466512 -0.09693354 -0.02906328 0.02901822 -0.03737032 0.06063097 0.01895749 -0.0459153 0.05487447 0.02938085 -0.05558657 0.04894614 0.03361326 -0.0555092 -0.03278219 0.04114437 -0.06164318 -0.04150027 0.03634166 -0.06819605 -0.03830301 0.03781527 -0.06137788 -0.04007709 0.03806018 -0.06882423 -0.03898918 0.03654706 -0.05664545 -0.04421597 0.03523528 -0.04969048 -0.04919767 0.03110593 -0.09719485 -0.02854228 0.027058 -0.08615928 -0.03202545 0.03146272 -0.07614773 -0.03535401 0.03382349 -0.09941279 0.02836871 0.02649462 -0.09905964 0.02747189 0.02673953 -0.09886717 0.02586859 0.02684962 -0.1007316 0.02248233 0.02569442 -0.09934741 -0.02486354 0.02647936 -0.08460474 -0.03622108 0.01890742 -0.08366423 -0.03467917 0.02014774 -0.0842837 -0.03410637 0.02068001 -0.08424019 -0.03509217 0.01948028 -0.08796668 -0.03445029 0.01626271 -0.08769929 -0.0360887 0.01851439 -0.08446377 -0.03742706 0.02047914 -0.07911998 -0.03785276 0.02036291 -0.08429479 -0.03582143 0.02147966 -0.08883708 -0.03080844 0.03281605 -0.07714247 -0.03382414 0.03654867 -0.08960407 -0.03246277 0.03090834 -0.0844928 -0.03348153 0.03336769 -0.07970732 -0.03576898 0.03330445 -0.07605797 -0.03654211 0.03516614 -0.07759165 -0.03510987 0.03581917 -0.1021819 0.02436888 0.02418082 -0.1034237 0.02436554 0.02307558 -0.1042622 0.02513819 0.02227097 -0.1042566 0.0266149 0.02225118 -0.1013033 0.02515292 0.02490997 -0.1013069 0.02659392 0.02488625 -0.1021921 0.02737104 0.02417343 -0.1034134 0.02737414 0.02308231 -0.1021817 -0.0209313 0.02418094 -0.1013032 -0.02171546 0.02491009 -0.1013067 -0.02315616 0.02488631 -0.1021921 -0.02393352 0.02417337 -0.1034134 -0.02393651 0.02308219 -0.1042566 -0.02317726 0.02225112 -0.1042622 -0.02170062 0.02227085 -0.1034237 -0.02092796 0.02307558 -0.03278416 0.00425595 0.04016178 -0.03313398 0.007152915 0.04022681 -0.03433704 0.009825944 0.04004883 -0.03454834 0.008688628 0.04001545 -0.0590803 -0.01066225 0.03649431 -0.05854904 -0.01015251 0.03656911 -0.05431109 -0.01316493 0.03706908 -0.05908054 0.01410055 0.03649425 -0.05431139 0.01660335 0.03706902 -0.03454822 -0.005249857 0.04001545 -0.03433692 -0.006387114 0.04004883 -0.03313386 -0.003714025 0.04022681 -0.0327841 -8.1711e-4 0.04016178 0.001698851 -0.04111629 -0.02098447 0.004628896 -0.04154372 -0.02126103 0.004410445 -0.04195308 -0.01932883 0.003262996 -0.0384714 -0.01935952 0.003277719 -0.03593218 -0.02118372 -6.86286e-4 -0.03846633 -0.02125573 0.001681923 -0.03644931 -0.01924908 -0.001287758 -0.0400148 -0.01925969 -5.83037e-4 -0.04236268 -0.02125531 0.001904428 -0.04469758 -0.01929694 0.001676023 -0.04442876 -0.02126115 0.004879415 -0.04442876 -0.02126115 0.005592167 -0.04406696 -0.01927179 0.00713855 -0.04236263 -0.02125531 0.007687151 -0.04084879 -0.01925498 0.007241785 -0.03846633 -0.02125573 0.005666732 -0.03673642 -0.01924413 0.003469169 -0.03837007 -0.02125436 0.004739701 0.04261535 -0.02163606 0.001723945 0.04501157 -0.02123415 9.2864e-4 0.04738193 -0.02126961 1.38944e-4 0.04708582 -0.01926422 0.003758251 0.04815608 -0.02117824 -8.70595e-4 0.04495704 -0.02125531 -8.70598e-4 0.04259645 -0.01925516 -5.83075e-4 0.04185426 -0.02125531 0.001904368 0.0395193 -0.01929694 0.001676023 0.03978818 -0.02126115 0.004879355 0.03978818 -0.02126115 0.005592107 0.04014998 -0.01927179 0.00713849 0.04185426 -0.02125531 0.007687151 0.04336816 -0.01925498 0.007241785 0.04575061 -0.02125573 0.005666732 0.04748052 -0.01924413 0.00175023 0.04261088 -0.02065449 0.005108416 0.04434287 -0.02032977 0.004540085 0.04198724 -0.0193243 0.001697778 0.04524666 -0.01937192 0.08336704 0.00163865 -0.02105981 0.08072692 0.003281772 -0.02141261 0.08029145 4.17251e-4 -0.02187615 0.08333909 -8.55165e-5 -0.01931357 0.08148121 -1.54207e-4 -0.02055013 0.07796144 0.003737986 -0.01926046 0.08120548 0.006094098 -0.02117609 0.07773542 0.003692805 -0.02125573 0.08010363 0.005709767 -0.01924908 0.07755112 5.38659e-4 -0.01925516 0.07783865 -2.03509e-4 -0.02125531 0.08032613 -0.002538442 -0.01929694 0.08009773 -0.002269566 -0.02126115 0.08330112 -0.002269566 -0.02126115 0.08401387 -0.001907765 -0.01927179 0.08610886 0.001310348 -0.01925498 0.08584779 0.002899229 -0.02125531 0.08408844 0.005422711 -0.01924413 0.08403664 0.00533235 -0.02126836 0.081797 0.003651142 -0.02017122 0.08231556 -0.00174129 -0.02259922 0.06830132 0.001084208 -0.0212019 0.06586569 0.003378629 -0.02134454 0.06531786 6.34212e-4 -0.02126526 0.06621915 0.00609821 -0.02117824 0.06273561 0.003692805 -0.02125567 0.06510382 0.005709767 -0.01924908 0.06213408 0.002144336 -0.01925969 0.06283885 -2.03529e-4 -0.02125531 0.06532633 -0.002538442 -0.01929694 0.06509798 -0.002269566 -0.02126115 0.06830137 -0.002269566 -0.02126115 0.06901401 -0.001907765 -0.01927179 0.07056051 -2.03482e-4 -0.02125531 0.07110905 0.001310288 -0.01925498 0.07084798 0.002899229 -0.02125531 0.06908863 0.005422711 -0.01924413 0.0690487 0.005324125 -0.02126961 0.06648939 0.003746092 -0.01936179 0.06517434 1.16954e-4 -0.01924264 0.06838589 6.36091e-4 -0.01934868 0.06341421 0.003402352 -0.02152049 0.06758511 -0.001572847 -0.02249729 0.06492578 -0.001046657 -0.02253872 -0.08327931 -0.06679415 0.01430606 -0.08500599 -0.0671457 0.01431864 -0.08483952 -0.06633949 0.01515144 -0.07973349 -0.06706887 0.01316708 -0.08131748 -0.06680095 0.01391744 -0.07953476 -0.06645512 0.01416206 -0.08182275 -0.0648458 0.01133251 -0.08081215 -0.06475675 0.01643252 -0.08378523 -0.06484025 0.01171815 -0.08277398 -0.06474995 0.0168212 -0.08279031 -0.06833726 0.01680135 -0.08353757 -0.06985247 0.0130558 -0.08180934 -0.06831061 0.0114609 -0.08143281 -0.06982612 0.01338779 -0.0808463 -0.06876206 0.01632988 -0.07946115 -0.06974017 0.01459103 -0.07914572 -0.06784099 0.01615023 -0.08014845 -0.06865614 0.01110255 -0.08505785 -0.06979453 0.0141285 -0.08544933 -0.06822258 0.01212495 -0.08444827 -0.06854999 0.01718401 -0.08545219 -0.06183373 0.01199918 -0.08015519 -0.06185203 0.01094985 -0.07914459 -0.06176298 0.01604986 -0.08444154 -0.06174468 0.0170992 -0.08157229 -0.06188029 0.009331107 -0.08322155 -0.06187969 0.009365856 -0.08001059 -0.06187099 0.009862482 -0.07872486 -0.06185299 0.01089578 -0.07787013 -0.06182837 0.01230651 -0.07754951 -0.06180012 0.01392447 -0.0778017 -0.06177169 0.01555448 -0.07859623 -0.06174641 0.01699995 -0.07983732 -0.06172746 0.01808649 -0.08137518 -0.06171703 0.01868313 -0.0830245 -0.06171643 0.01871788 -0.0845862 -0.06172573 0.01818656 -0.08587193 -0.06174379 0.0171532 -0.08672666 -0.06176841 0.01574248 -0.08704727 -0.0617966 0.01412457 -0.08679509 -0.06182509 0.01249456 -0.08600056 -0.0618503 0.01104909 -0.08475947 -0.06186926 0.009962499 -0.08157229 -0.05038219 0.009130418 -0.08322179 -0.05037271 0.009165048 -0.08001059 -0.05037289 0.009661734 -0.07872682 -0.05034321 0.01069235 -0.07786983 -0.05032604 0.01210689 -0.07754963 -0.05030524 0.01372593 -0.0778017 -0.05027353 0.01535373 -0.07859623 -0.05024832 0.01679921 -0.07983732 -0.05022937 0.0178858 -0.081375 -0.05021005 0.01848226 -0.08302593 -0.0501272 0.01851433 -0.0845862 -0.05022764 0.01798588 -0.08587193 -0.05024564 0.01695251 -0.08674496 -0.05025666 0.0155099 -0.08704715 -0.05030149 0.01392263 -0.08679509 -0.050327 0.01229387 -0.08600056 -0.05035221 0.0108484 -0.08475947 -0.05037117 0.00976181 -0.08576112 -0.04984247 0.01022648 -0.08492529 -0.04606419 0.009502887 -0.08376026 -0.04964798 0.009008705 -0.08709144 -0.04972529 0.01231372 -0.08644706 -0.04934912 0.01101607 -0.08731752 -0.042831 0.01362848 -0.08571368 -0.04963982 0.01751023 -0.08421194 -0.04901814 0.01845121 -0.08186972 -0.04920393 0.01879566 -0.08644521 -0.04857295 0.01642298 -0.07923126 -0.04128152 0.01746147 -0.07923388 -0.04813915 0.01757103 -0.07857006 -0.04272902 0.01695477 -0.08145129 -0.04129117 0.01847046 -0.08336192 -0.04127174 0.01853567 -0.08368599 -0.04146075 0.008921682 -0.08575534 -0.04242497 0.01004195 -0.0868768 -0.04135638 0.01543599 -0.08613473 -0.04225337 0.01670819 -0.08036881 -0.04902756 0.01829594 -0.07753425 -0.04256123 0.01494556 -0.07769095 -0.04961597 0.01567769 -0.07740283 -0.0464605 0.01392805 -0.07738679 -0.04141211 0.01345998 -0.07786899 -0.04941713 0.01153117 -0.07903641 -0.04133373 0.01046919 -0.07815581 -0.04231488 0.010854 -0.07932603 -0.04523861 0.009786963 -0.08193683 -0.04264956 0.008737623 -0.08006936 -0.04256486 0.009322941 -0.08094859 -0.05007958 0.009089767 -0.08244299 -0.04938346 0.008931398 -0.07850348 -0.05000841 0.01666301 -0.0863589 -0.04139149 0.0111407 -0.08427476 -0.04135137 0.01067948 -0.08550566 -0.04151809 0.01530468 -0.08080881 -0.04125612 0.01694214 -0.08290761 -0.04822874 0.01679396 -0.08344823 -0.04816043 0.01685732 -0.08236616 -0.0480867 0.01706391 -0.07974958 -0.04815703 0.01549249 -0.08061414 -0.04781186 0.0163486 -0.07928615 -0.04804152 0.01437801 -0.08341163 -0.04821848 0.01100385 -0.08484786 -0.04820227 0.0120837 -0.08531093 -0.04783171 0.01318991 -0.08486789 -0.04796391 0.01533919 -0.08338391 -0.04689085 0.01693677 -0.08458417 -0.04646128 0.01124656 -0.08123368 -0.04714435 0.01049911 -0.08568513 -0.04567706 0.01441019 -0.08056902 -0.04545366 0.01685345 -0.07872617 -0.04695689 0.01328486 -0.0814628 -0.0451889 0.01028007 -0.07931184 -0.04488188 0.01221823 -0.08548188 -0.04407674 0.01229828 -0.08455169 -0.0442537 0.01627242 -0.08175039 -0.04369276 0.0102986 -0.07894635 -0.04333543 0.0146287 -0.0847193 -0.0426917 0.01141995 -0.08263379 -0.04235631 0.01724421 -0.08017206 -0.042418 0.01117187 -0.07928729 -0.04814916 0.01320242 -0.0797522 -0.04813128 0.01207536 -0.08107149 -0.0439291 0.01715922 -0.08007127 -0.04428482 0.01466059 -0.08377426 -0.0443347 0.01180392 -0.08256727 -0.04426121 0.0160138 -0.08091801 -0.04433357 0.01186627 -0.08442038 -0.04428529 0.01463359 -0.08528023 -0.04829484 0.01411825 -0.08211505 -0.04835283 0.01079499 -0.08086901 -0.04834663 0.01115179 -0.0843175 -0.04828006 0.01491236 -0.08200353 -0.04821217 0.01605671 -0.08428102 -0.0483213 0.01260226 -0.08226191 -0.04834091 0.01147884 -0.08009129 -0.04830825 0.01335167 -0.08060562 -0.04832649 0.01230686 -0.08016836 -0.04828792 0.01451361 -0.08081614 -0.04827105 0.01548135 -0.08655381 -0.06633454 0.01535397 -0.08701485 -0.06639224 0.01460701 -0.08697944 -0.06691533 0.01557815 -0.0870729 -0.06707984 0.01456791 -0.08550548 -0.06736075 0.01472651 -0.07829511 -0.06681114 0.01270705 -0.07786303 -0.06620538 0.01319181 -0.07789099 -0.06661367 0.01284235 -0.07767176 -0.06738728 0.01356273 -0.07823866 -0.06733107 0.01300114 -0.101619 -0.06777274 -0.06303894 -0.1012325 -0.06548011 -0.06267017 -0.1006879 -0.06435 -0.06386131 -0.1006499 -0.06646013 -0.06596451 -0.09812152 -0.06315666 -0.06468415 -0.09711462 -0.06572425 -0.0670368 -0.09918123 -0.0634036 -0.06307429 -0.09573459 -0.0634011 -0.06087815 -0.09527963 -0.06424432 -0.06480431 -0.09427577 -0.06684416 -0.06545519 -0.09347504 -0.06550961 -0.06023591 -0.09668689 -0.06949675 -0.06651687 -0.09703105 -0.07076406 -0.06432026 -0.09946066 -0.07047832 -0.06395226 -0.09450989 -0.06903564 -0.06409972 -0.100687 -0.06964951 -0.06414949 -0.09374058 -0.064296 -0.05723029 -0.09647393 -0.06309717 -0.0567274 -0.09863716 -0.06363642 -0.05732703 -0.1000688 -0.06554645 -0.05687034 -0.09930711 -0.06968325 -0.05716735 -0.09809076 -0.0704047 -0.05633008 -0.0966345 -0.07082122 -0.05765867 -0.09449553 -0.07031369 -0.05731832 -0.09285467 -0.06698447 -0.05846971 -0.09986591 -0.06824165 -0.05554407 -0.09275561 -0.06808668 -0.05732309 -0.09944725 -0.06473064 -0.05535966 -0.09620249 -0.07077652 -0.05579423 -0.09295964 -0.06842893 -0.05585092 -0.09265345 -0.06698608 -0.05591005 -0.09381496 -0.06962025 -0.05568271 -0.09749883 -0.07029527 -0.05495369 -0.09940308 -0.06834042 -0.05457437 -0.09939336 -0.06558513 -0.05457341 -0.09747534 -0.06364351 -0.05495131 -0.09607356 -0.06312441 -0.0549736 -0.09379631 -0.06434398 -0.05568087 -0.09294945 -0.06554114 -0.0558499 -0.09864169 -0.06951099 -0.05472642 -0.09862375 -0.06441992 -0.05472463 -0.0946545 -0.07053619 -0.05526256 -0.09610074 -0.07082426 -0.05497634 -0.09986364 -0.06696128 -0.05422681 -0.0946294 -0.06342244 -0.05526 -0.08581179 -0.06849586 -0.0213834 -0.08551913 -0.06702351 -0.02143979 -0.08663487 -0.06974202 -0.02122163 -0.08786302 -0.07057237 -0.02097922 -0.08930927 -0.07086044 -0.020693 -0.09075343 -0.07056236 -0.0204066 -0.09197568 -0.06972354 -0.02016359 -0.09278994 -0.06847172 -0.02000099 -0.09307223 -0.06699746 -0.01994353 -0.09277957 -0.06552511 -0.01999992 -0.09195649 -0.06427896 -0.02016168 -0.09072834 -0.0634486 -0.0204041 -0.08928209 -0.06316053 -0.02069026 -0.08783793 -0.06345862 -0.02097672 -0.08661568 -0.06429743 -0.02121967 -0.08580142 -0.06554925 -0.02138233 -0.08102518 -0.06542176 -0.001939952 -0.08074992 -0.06704729 -0.001996219 -0.08182924 -0.06399035 -0.001779139 -0.08306509 -0.06292569 -0.00153321 -0.08458369 -0.06235623 -0.001231789 -0.0862019 -0.06235063 -9.11246e-4 -0.08772444 -0.0629096 -6.10215e-4 -0.0889678 -0.06396567 -3.65026e-4 -0.08978193 -0.06539148 -2.05252e-4 -0.09006869 -0.06701505 -1.50165e-4 -0.08979338 -0.06864058 -2.06408e-4 -0.08898937 -0.07007205 -3.67199e-4 -0.08775347 -0.07113665 -6.13143e-4 -0.08185076 -0.07009667 -0.001781344 -0.08103668 -0.06867086 -0.001941084 -0.08309412 -0.07115274 -0.00153613 -0.08461672 -0.07171171 -0.001235127 -0.08623486 -0.07170611 -9.14576e-4 -0.07783865 -0.06722718 0.01271736 -0.08538353 -0.06425172 0.01880329 -0.08595901 -0.0655803 0.01939809 -0.0842638 -0.06321209 0.0190494 -0.08396428 -0.07115685 0.01851487 -0.08235007 -0.07172626 0.0187025 -0.08489429 -0.07028084 0.01895964 -0.08620345 -0.0669853 0.019387 -0.08584058 -0.06876218 0.01915329 -0.08079439 -0.07166588 0.01814305 -0.07797211 -0.07011711 0.01779824 -0.07930493 -0.07117295 0.01759183 -0.08573126 -0.06828457 0.01173198 -0.08427387 -0.06829231 0.01908892 -0.08023816 -0.06830358 0.01064378 -0.07878077 -0.06831133 0.01800072 -0.07716888 -0.06869447 0.0175926 -0.07798349 -0.06406265 0.01783233 -0.07876586 -0.06328815 0.01798808 -0.08022022 -0.06321668 0.01064562 -0.08151996 -0.06253319 0.01090377 -0.08296358 -0.06229418 0.01119005 -0.08440881 -0.06252318 0.01147609 -0.08571332 -0.06319767 0.01173382 -0.07697784 -0.0670675 0.01739001 -0.07718259 -0.065602 0.01717728 -0.09326404 0.02749729 -0.02167838 -0.0954625 0.02610683 -0.02086901 -0.09362864 0.02635329 -0.02148854 -0.09556633 0.02386671 -0.02085006 -0.08960139 0.02715039 -0.02285504 -0.08978974 0.02816802 -0.02285504 -0.0922358 0.02663385 -0.02685123 -0.09366357 0.02614533 -0.02635461 -0.09462445 0.02535033 -0.02599447 -0.09552597 0.02362579 -0.02561593 -0.09656959 0.02353429 -0.02085518 -0.09557121 0.0159133 -0.02085518 -0.0965712 0.0159133 -0.02085518 -0.09343492 0.02750772 -0.02637565 -0.09535342 0.02621912 -0.02570343 -0.09660172 0.02383863 -0.02510505 -0.09552937 0.0158714 -0.02561771 -0.08955484 0.02711659 -0.02764922 -0.08975684 0.02821588 -0.02756428 -0.09660834 0.01587623 -0.02510577 -0.09848684 0.02684676 -0.02401751 -0.1052268 0.02053409 -0.01692837 -0.1033269 0.02634 -0.01960825 -0.1064909 0.02573311 -0.01435083 -0.1071145 0.02035552 -0.01294028 -0.109223 0.0267632 -0.005877912 -0.0964747 0.02854198 -0.02267807 -0.1009184 0.02659183 -0.02212828 -0.09095501 0.02946239 -0.02639824 -0.1066704 0.02801573 -0.008440554 -0.1069821 0.02723145 -0.01102465 -0.08629906 0.02956688 -0.02842533 -0.0834347 0.0296176 -0.02921116 -0.07721555 0.03141802 -0.03064757 -0.06491649 0.03500276 -0.03354609 -0.06283134 0.03677505 -0.03377467 -0.07401841 0.03388088 -0.03083372 -0.06282913 0.03778582 -0.03267866 -0.07283985 0.0350759 -0.02978485 -0.1090931 0.03018927 0.006144404 -0.1097136 0.02799069 -0.001632392 -0.1100406 0.0296328 0.00614345 -0.1107757 0.02821439 0.006074488 -0.1084972 0.01948505 -0.008825063 -0.08029204 0.03062123 -0.03148502 -0.08214062 0.03104978 -0.03093403 -0.06529092 0.03500276 -0.03499859 -0.08795148 0.02844381 -0.02963531 -0.09188067 0.02827018 -0.02852618 -0.08686751 0.03083705 -0.02937072 -0.09546506 0.02923572 -0.02621346 -0.09746658 0.02948224 -0.02416783 -0.08558052 0.03292787 -0.02711814 -0.08062642 0.03409636 -0.02912062 -0.0770688 0.03468322 -0.0307095 -0.06604015 0.03704833 -0.03410661 -0.06282889 0.03619235 -0.03564357 -0.09809482 0.02673292 -0.02600908 -0.1005954 0.02680563 -0.02432197 -0.09593576 0.02642238 -0.02707082 -0.1046495 0.02786093 -0.01883971 -0.1034873 0.02591449 -0.02179878 -0.1063619 0.02610695 -0.01790452 -0.1042016 0.02882719 -0.01641535 -0.1086863 0.02864497 -0.008947134 -0.1081715 0.02519118 -0.01426011 -0.1093837 0.02685683 -0.01047307 -0.1090437 0.02534139 -0.01201009 -0.11041 0.02637183 -0.007449924 -0.1111335 0.02903026 -3.94865e-4 -0.1115769 0.02427488 -0.001821517 -0.1120422 0.02690821 0.001139998 -0.06284821 0.03952723 -0.03242284 -0.0628345 0.03902232 -0.03373903 -0.1110612 0.02620846 0.001468122 -0.1105176 0.02579468 0.006139755 -0.1105108 0.01971864 0.006144404 -0.1106215 0.01960849 -1.69561e-4 -0.1108071 0.02438598 -4.51597e-4 -0.1092211 0.01950675 -0.005996525 -0.1100392 0.01945686 -0.008855342 -0.1110113 0.01952713 -0.004829585 -0.1116038 0.01961314 -9.14391e-4 -0.1094331 0.01971864 0.006144404 -0.1094387 0.02543038 0.006144702 -0.1100392 0.01329541 -0.008855342 -0.1109982 0.01330989 -0.004893004 -0.1166911 0.0137034 0.001073658 -0.1116861 0.01330119 -9.64083e-4 -0.1121152 0.01327335 0.002769112 -0.1165888 0.01362389 0.005750834 -0.112298 0.0132302 0.006144404 -0.1166973 0.01470369 0.001085579 -0.1100392 0.01429539 -0.008855342 -0.1085171 0.0141623 -0.008860886 -0.1084799 0.01626038 -0.008855342 -0.1100393 0.01626038 -0.008855342 -0.1100392 0.0178653 -0.008855342 -0.1105625 0.01778668 1.42821e-4 -0.1105753 0.01641935 2.53112e-4 -0.1084799 0.0178653 -0.008855342 -0.1072456 0.02048736 -0.01626348 -0.1057535 0.0206266 -0.01891058 -0.1017515 0.02076131 -0.0215308 -0.1018344 0.02086478 -0.02350449 -0.09819167 0.0209881 -0.02421653 -0.09810256 0.02099823 -0.02601188 -0.1059756 0.01771873 0.007944405 -0.1072442 0.01729607 -0.01626622 -0.1070728 0.01790136 -0.01298874 -0.09810256 0.01712596 -0.02601188 -0.09951406 0.0171408 -0.02515804 -0.09882259 0.01736581 -0.01227295 -0.1010272 0.01716029 -0.02404254 -0.1028817 0.01718908 -0.02239835 -0.1043061 0.0172165 -0.02082747 -0.1051408 0.0172351 -0.01975864 -0.1062334 0.01726412 -0.018099 -0.09988212 0.01771873 0.007944405 -0.09876298 0.02014243 -0.01341003 -0.1159852 0.01774024 0.005860567 -0.1060729 0.01769471 0.01061308 -0.1151975 0.01778382 4.79118e-4 -0.116222 0.0164448 8.18218e-4 -0.09802484 0.01973801 -0.01281601 -0.09737247 0.02054417 -0.02470368 -0.09803086 0.01627409 -0.01227444 -0.0973711 0.01644468 -0.02470231 -0.0978415 0.01598948 -0.0244559 -0.1004153 0.01602035 -0.02260369 -0.09882259 0.01620072 -0.01227295 -0.1024559 0.01605427 -0.02066457 -0.1025292 0.01620072 -0.01227295 -0.1000124 0.01659703 0.01043027 -0.1033293 0.01620072 -0.01227295 -0.1061754 0.01615184 -0.01507246 -0.1046559 0.01610374 -0.01781916 -0.1033929 0.01607328 -0.01957249 -0.1058328 0.01660722 0.01092612 -0.1101782 0.01651948 0.00597918 -0.1161516 0.01651698 0.005844712 -0.1025233 0.0139693 -0.01306432 -0.1024507 0.01413476 -0.02070796 -0.1032478 0.0136013 -0.01976323 -0.1032987 0.01433491 -0.01295483 -0.1153572 0.01449793 0.006138682 -0.1074799 0.01380866 0.006144404 -0.1071492 0.01411157 -0.01279598 -0.1071492 0.01244789 -0.01279598 -0.1074799 0.01280868 0.006144404 -0.109454 0.01277965 -0.005369484 -0.1106106 0.01302361 0.002780139 -0.1107977 0.01309895 0.006144404 -0.105923 0.0194655 0.008008897 -0.1018539 0.01957136 0.007966339 -0.09981721 0.01762253 0.01044356 -0.100037 0.01724624 0.01089876 -0.1043105 -0.02428787 -0.01374268 -0.09026575 -0.0266202 -0.02552175 -0.09702992 -0.02416712 -0.02443015 -0.1012868 -0.02305132 -0.02176415 -0.09866839 -0.02231776 -0.02390849 -0.1064168 -0.02281743 -0.01447093 -0.09593576 -0.02285301 -0.02542936 -0.1075771 -0.02383905 -0.00954461 -0.108419 -0.02277106 -0.009073197 -0.1075984 -0.02189648 -0.01159763 -0.109224 -0.02378374 -0.005777776 -0.1096614 -0.02655899 0.006144464 -0.1108622 -0.02491378 0.006056308 -0.1043623 -0.02228611 -0.01835423 -0.102903 -0.02446329 -0.02119082 -0.1005082 -0.02587562 -0.02013206 -0.1077232 -0.02449125 -0.01277172 -0.1071116 -0.02277445 -0.01643735 -0.11043 -0.02355206 -0.007360935 -0.1090437 -0.02190357 -0.01201009 -0.1082021 -0.02226555 -0.0141834 -0.09743696 -0.0258221 -0.02458161 -0.112064 -0.02348512 0.001489341 -0.1099851 -0.02559715 -0.004088401 -0.1081852 -0.02647083 -0.004579961 -0.1113138 -0.02403891 -0.003191292 -0.09765112 -0.02481544 -0.02560406 -0.1015889 -0.02259266 -0.02361983 -0.09825277 -0.02293759 -0.02592599 -0.095986 -0.02359902 -0.02704691 -0.1048723 -0.02215313 -0.02013802 -0.1105754 -0.02250528 0.006134331 -0.1105108 -0.01628082 0.006144404 -0.1106352 -0.0212562 -2.11344e-4 -0.1106223 -0.0161705 -1.76027e-4 -0.1084799 -0.01601898 -0.008855342 -0.1100392 -0.01601898 -0.008855342 -0.1092211 -0.01606887 -0.005996525 -0.1116857 -0.01615303 -0.0011608 -0.1094331 -0.01628082 0.006144404 -0.1094335 -0.0218051 0.006141722 -0.1165884 -0.0101912 0.005752325 -0.1121152 -0.009835481 0.002769112 -0.1167278 -0.01026654 0.001198112 -0.112298 -0.009792327 0.006144404 -0.1116861 -0.009863376 -9.64083e-4 -0.1109982 -0.009872019 -0.004893004 -0.1100392 -0.009857535 -0.008855342 -0.1166883 -0.01126533 0.001069962 -0.1100392 -0.01085752 -0.008855342 -0.1085171 -0.01072448 -0.008860886 -0.1084799 -0.0128225 -0.008855342 -0.1100392 -0.0128225 -0.008855342 -0.1105363 -0.01434791 2.47085e-4 -0.1104273 -0.01295179 -0.001450717 -0.1100457 -0.01442766 -0.008896887 -0.1084799 -0.01442742 -0.008855342 -0.111536 -0.02124613 -8.54444e-4 -0.09810256 -0.01756042 -0.02601188 -0.1011462 -0.01745516 -0.02400898 -0.09819519 -0.01748549 -0.02421659 -0.101682 -0.01732784 -0.02161049 -0.1044898 -0.01727974 -0.02064722 -0.1056141 -0.01704442 -0.01617342 -0.1072317 -0.01705384 -0.01635563 -0.1070738 -0.01687777 -0.0129863 -0.1070728 -0.01446354 -0.01298874 -0.1072569 -0.01385825 -0.01626408 -0.1059756 -0.01428085 0.007944405 -0.1062638 -0.01382666 -0.01807087 -0.1052456 -0.01379996 -0.01960521 -0.1043061 -0.01377862 -0.02082747 -0.09882259 -0.01392793 -0.01227295 -0.1033392 -0.01375943 -0.0219233 -0.1017317 -0.01373261 -0.02346378 -0.09978365 -0.01370644 -0.02496379 -0.09810256 -0.01368814 -0.02601182 -0.09988212 -0.01428085 0.007944405 -0.09876042 -0.01674836 -0.0134449 -0.1159852 -0.01430237 0.005860567 -0.1162092 -0.01432728 8.40523e-4 -0.1060732 -0.01425677 0.01061218 -0.09799343 -0.01638036 -0.01282715 -0.09737062 -0.01699274 -0.02471071 -0.09803175 -0.01283705 -0.01227414 -0.09737122 -0.01304554 -0.02470225 -0.0979436 -0.01255226 -0.02438044 -0.1004211 -0.01258248 -0.02260303 -0.09882259 -0.01276284 -0.01227295 -0.1024559 -0.01261633 -0.0206663 -0.1025292 -0.01276284 -0.01227295 -0.1000124 -0.01315915 0.01043027 -0.1033293 -0.01276284 -0.01227295 -0.1101646 -0.0130819 0.006034076 -0.1112321 -0.01298272 3.21092e-4 -0.1161516 -0.0130791 0.005844712 -0.1151145 -0.0129854 4.74838e-4 -0.1033929 -0.01263546 -0.01957249 -0.104627 -0.01266491 -0.0178712 -0.1067152 -0.01273268 -0.01401162 -0.1026204 -0.01030993 -0.02049219 -0.1025831 -0.01064521 -0.01323395 -0.1032622 -0.01035553 -0.01973426 -0.1033235 -0.01159471 -0.01237541 -0.1153572 -0.01106005 0.006138682 -0.1074799 -0.01037079 0.006144404 -0.1071492 -0.01067376 -0.01279598 -0.1071492 -0.009010016 -0.01279598 -0.1074799 -0.009370803 0.006144404 -0.1094522 -0.009341478 -0.005378127 -0.1106106 -0.009585797 0.002780139 -0.1107977 -0.009661078 0.006144404 -0.1018644 -0.01608544 0.007963538 -0.1059206 -0.01603096 0.00800985 -0.1000282 -0.01412779 0.0107305 -0.10553 -0.01345223 0.01090967 -0.09211742 -0.03249174 0.006144404 -0.09089612 -0.03215181 0.002475202 -0.08496052 -0.03324532 -0.001977324 -0.07879376 -0.03555816 -8.6862e-4 -0.06580632 -0.03949934 -0.003064453 -0.06381058 -0.03980672 -0.004855394 -0.07445663 -0.03846544 0.006149232 -0.06729662 -0.04088497 0.006144404 -0.06187832 -0.03580093 -0.02756136 -0.06282055 -0.03499197 -0.02995097 -0.06282621 -0.03446298 -0.03250813 -0.08652758 -0.03437066 -0.001771569 -0.0846365 -0.0297541 -0.02738678 -0.06430006 -0.04125422 -0.004855394 -0.0662958 -0.04094684 -0.003064453 -0.07632845 -0.0385223 0.001653134 -0.06284874 -0.03608363 -0.03244978 -0.06257498 -0.03653448 -0.03069972 -0.05708914 -0.03848654 -0.03022432 -0.05908846 -0.04301655 -0.004855394 -0.06778609 -0.04233253 0.006144404 -0.07528126 -0.03991556 0.006143867 -0.09153217 -0.03430318 0.006144165 -0.08936399 -0.03406322 0.006143867 -0.08941894 -0.0399146 0.006144404 -0.08808004 -0.03800904 0.006144404 -0.07957917 -0.03099173 -0.0292989 -0.08944284 -0.02762031 -0.02788978 -0.08829498 -0.02583855 -0.02946645 -0.09099757 -0.02619969 -0.02828109 -0.09185552 -0.02395784 -0.02853757 -0.08795148 -0.02500599 -0.02963531 -0.06283539 -0.03555309 -0.03380095 -0.06563192 -0.03386044 -0.03408598 -0.08029204 -0.02718335 -0.03148502 -0.06529092 -0.03156489 -0.03499859 -0.07769769 -0.02962368 -0.0317077 -0.06283485 -0.033526 -0.03536927 -0.06580632 0.04293715 -0.003064453 -0.06381058 0.04324454 -0.004855394 -0.06187832 0.03923851 -0.02756303 -0.06282055 0.03842955 -0.02995246 -0.06729662 0.04432284 0.006144404 -0.06778609 0.04577034 0.006144404 -0.0662958 0.04438471 -0.003064453 -0.06430006 0.04469209 -0.004855394 -0.06257498 0.03997236 -0.03069972 -0.05908846 0.04645437 -0.004855394 -0.05708914 0.04192441 -0.0302242 -0.06282496 0.03361856 -0.03410118 -0.06282496 0.02271866 -0.03410118 -0.06282496 0.02271676 -0.0356571 -0.06265014 0.03963947 -0.02970039 -0.05708849 0.04151159 -0.02726501 -0.09927672 0.00834912 -0.02348476 -0.1035055 0.006295084 -0.01959472 -0.1034919 0.00514388 -0.01944702 -0.1034919 -0.001706004 -0.01944702 -0.1052563 -0.001763701 -0.01691442 -0.1053871 0.005193889 -0.0166186 -0.1036283 0.009388208 -0.01927059 -0.1061604 0.009353995 -0.01534789 -0.106165 0.0108515 -0.01506465 -0.1089028 0.01078712 -0.007690072 -0.1103242 0.01071876 1.44535e-4 -0.110323 0.009718775 1.31958e-4 -0.1103238 -0.006280899 1.38591e-4 -0.1103242 -0.007280945 1.44535e-4 -0.1102215 0.001720726 -6.09665e-4 -0.1102005 -0.001338362 -7.59214e-4 -0.1101387 -0.001811802 -0.001300096 -0.1097977 -0.005020618 -0.003380477 -0.110643 -0.006208598 -0.006432473 -0.1079635 -0.004787087 -0.009997069 -0.107405 -0.006173729 -0.01214087 -0.1089028 -0.007349252 -0.007689595 -0.1061651 -0.007413685 -0.01507031 -0.1061645 -0.005914092 -0.01510918 -0.1036281 -0.005950868 -0.0193268 -0.1035146 -0.00285691 -0.01956117 -0.1049502 -0.004628539 -0.0173223 -0.1061651 -0.004648268 -0.01506191 -0.1049502 -0.003628551 -0.0173223 -0.0915333 -0.02454906 -0.0270763 -0.09445393 -0.0146532 -0.02605694 -0.07267177 0.008841454 -0.03168159 -0.07026767 0.02354526 -0.03223824 -0.06821751 0.009887814 -0.03272795 -0.06368434 0.0168187 -0.03386896 -0.06555455 -3.84881e-4 -0.03338307 -0.06368434 -0.01328086 -0.03386896 -0.06294798 0.01071876 -0.03406751 -0.06304061 -0.007507979 -0.03385382 -0.08023762 -0.02710187 -0.02995842 -0.08459299 -0.01646375 -0.02893239 -0.08797293 -0.02544134 -0.02807682 -0.08057999 0.02036648 -0.02987957 -0.07151407 -0.02043533 -0.03194785 -0.06282496 -0.03018069 -0.03410118 -0.06491649 -0.03156489 -0.03354609 -0.0629431 -0.01928561 -0.03407776 -0.06757777 -0.01551973 -0.0328803 -0.08591413 0.01745945 -0.02860701 -0.1036283 -0.003611564 -0.01927059 -0.107752 -0.002784788 -0.01103496 -0.1074049 -0.003673851 -0.01212829 -0.1061651 -0.003648281 -0.01506191 -0.107405 0.009611606 -0.01213836 -0.1094338 0.009674072 -0.005130052 -0.1081292 0.008000493 -0.01003271 -0.1101517 0.005255579 -0.001201033 -0.1036283 0.007049381 -0.01927059 -0.1049502 0.007066369 -0.0173223 -0.1049502 0.008066356 -0.0173223 -0.1061651 0.008086085 -0.01506191 -0.1061651 0.007086098 -0.01506191 -0.1078262 0.006228327 -0.01102775 -0.1074049 0.007111728 -0.01212829 -0.1073332 0.003097653 -0.01226091 -0.1071922 0.001002132 -0.01236641 -0.1061806 0.002427339 -0.01502943 -0.1071506 -1.96097e-5 -0.01233834 -0.1077433 -0.001503348 -0.01123046 -0.1075885 0.004949212 -0.01132386 -0.1091057 -0.001588463 -0.0118438 -0.1085103 0.005121052 -0.01343053 -0.1095659 -0.004173099 -0.01046288 -0.09695374 -0.01299744 -0.02660775 -0.09697264 0.01663172 -0.02659857 -0.09582686 0.002110481 -0.02711731 -0.09428286 -0.01123189 -0.02772539 -0.0931909 3.11106e-4 -0.0281071 -0.09064924 0.00914812 -0.02889347 -0.09015649 -0.01453363 -0.02903783 -0.1100622 -0.005503118 -0.008722543 -0.109023 0.004787147 -0.01208043 -0.1093885 0.006702125 -0.0109995 -0.1098588 0.008508026 -0.009473562 -0.1104778 0.009435713 -0.007169127 -0.1112449 0.008702099 -0.003586649 -0.1115904 0.005818724 -0.001565694 -0.1117405 0.002520143 -5.74881e-4 -0.1119393 0.001692056 9.99573e-4 -0.1117008 -7.368e-4 -8.48651e-4 -0.1113989 -0.004689991 -0.002783477 -0.1122357 0.001718878 0.004494607 -0.09443598 0.01728498 -0.02766889 -0.08465892 0.02003067 -0.03045982 -0.0721414 0.02240812 -0.03334236 -0.06760668 -0.01780855 -0.03441733 -0.06823271 0.01973998 -0.0342648 -0.06282496 0.01071691 -0.0356571 -0.06282496 -0.007282793 -0.0356571 -0.06282371 -0.01939803 -0.0356599 -0.0719043 -0.02057176 -0.03339719 -0.08411532 -0.01416176 -0.03059071 -0.06272673 0.0170592 -0.03387266 -0.06210577 0.01084625 -0.03349995 -0.06103491 0.02264213 -0.03231686 -0.08002513 -0.02873933 -0.02941375 -0.08968526 -0.02647656 -0.0265693 -0.06283122 -0.03331911 -0.03377825 -0.05950748 -0.01906943 -0.03634262 -0.05822366 -0.01925677 -0.03574478 -0.06194698 -0.007973551 -0.03338086 -0.06061893 0.01073634 -0.0334618 -0.05994963 0.01076871 -0.03197783 -0.05886608 0.01077264 -0.03290402 -0.05748581 0.01071876 -0.03458148 -0.05811303 0.01091879 -0.03548556 -0.1037978 -0.003780961 1.44535e-4 -0.1047975 -0.003783047 3.21686e-4 -0.1037978 -0.005780935 1.44535e-4 -0.1062978 -0.005780935 1.44535e-4 -0.1062978 -0.007280945 1.44535e-4 -0.1072978 -0.006280958 1.44535e-4 -0.1062978 -0.004780948 1.44535e-4 -0.1047978 -0.004780948 1.44535e-4 -0.1062978 -0.003780961 1.44535e-4 -0.1072978 -0.003780961 1.44535e-4 -0.1072978 0.009718775 1.44535e-4 -0.1062978 0.01071876 1.44535e-4 -0.1062978 0.009218811 1.44535e-4 -0.1062978 0.008218824 1.44535e-4 -0.1047978 0.008218824 1.44535e-4 -0.1037978 0.009218811 1.44535e-4 -0.1037978 0.007218837 1.44535e-4 -0.1047968 0.007221817 3.97529e-4 -0.1072978 0.007218837 1.44535e-4 -0.1062996 0.007221221 4.77067e-4 -0.1060375 0.001021325 -0.01263165 -0.103567 -0.001780986 -0.01085531 -0.103567 -0.002780973 -0.01085531 -0.103567 0.00621885 -0.01085531 -0.103567 0.005218863 -0.01085531 -0.1061771 0.002877771 -0.01219928 -0.06131839 0.01682311 -0.03609865 -0.05918371 0.02263838 -0.03648322 -0.05918413 0.01683843 -0.03644555 -0.06111764 -0.01338946 -0.03616005 -0.05914074 -0.01345616 -0.03650689 -0.06102699 0.01662743 -0.03233796 -0.05946016 0.0165916 -0.03170579 -0.05802303 0.01662743 -0.03233796 -0.05727958 0.01091879 -0.03358173 -0.05762672 0.02271866 -0.03537839 -0.05776679 0.01679533 -0.03556257 -0.08859586 -0.03709661 0.002715229 -0.08968627 -0.03441238 0.00178188 -0.08843374 -0.03945159 0.00258845 -0.07839894 -0.03980994 1.77984e-4 -0.08362931 -0.03979104 -9.56219e-4 -0.0770387 -0.03838551 0.004436731 -0.08758741 -0.03838968 0.004345655 -0.07841676 -0.03834724 0.002246916 -0.08371317 -0.03831696 4.8542e-4 -0.08795869 -0.03407013 0.00284332 -0.0626502 -0.03620147 -0.02969819 -0.05708849 -0.03807371 -0.02726501 -0.06094384 -0.01909846 -0.0326544 -0.05784213 -0.007313251 -0.03550571 -0.05729162 -0.007480919 -0.03462922 -0.05776697 -0.01335859 -0.03556275 -0.05946016 -0.01300036 -0.03173452 -0.06015735 -0.007527112 -0.03180205 -0.05776131 -0.01298356 -0.03259086 -0.06128299 -0.0130096 -0.03259676 -0.06067711 -0.007293343 -0.03374558 -0.05963122 -0.007273852 -0.03284949 -0.05848002 -0.007263362 -0.03341275 -0.06048911 0.01673841 -0.03448569 -0.05895256 0.01676476 -0.03496295 -0.05848985 0.01678228 -0.03402674 -0.06056255 -0.01330035 -0.03398579 -0.06009465 -0.01332581 -0.03496527 -0.05896681 -0.01332604 -0.03494185 -0.05853056 -0.013305 -0.03422784 -0.05998885 0.0166862 -0.03304582 -0.08501768 -0.03524017 -0.001423478 -0.08052355 -0.0370422 -9.56763e-4 -0.0860058 -0.0367608 -4.43854e-5 -0.08518534 -0.03394955 -3.05751e-4 -0.08438408 -0.0363996 6.6469e-4 -0.08055979 -0.035806 1.73988e-5 -0.07724201 -0.03732967 0.00323528 -0.05958312 -0.01322782 -0.03303015 -0.1050978 0.005987524 -7.33325e-4 -0.1050978 0.008065104 0.001844167 -0.1060978 0.005140781 6.32882e-4 -0.1060979 0.006246626 -0.001438677 -0.1060977 -0.001857399 1.79715e-4 -0.1050978 -0.001882076 9.3398e-4 -0.1060978 -0.003721892 -6.35455e-4 -0.1050978 -0.002779006 -8.77923e-4 -0.1050978 0.004762172 -0.01085531 -0.1050978 0.004762172 -0.007692217 -0.1025978 0.004762172 -0.01085531 -0.1025978 0.004762172 -0.007692217 -0.1050978 -0.001324295 -0.007692217 -0.1050978 -0.001324295 -0.01085531 -0.1025978 -0.001324295 -0.007692217 -0.1025978 -0.001324295 -0.01085531 -0.1050978 -0.004630982 0.001844465 -0.1050978 0.008068799 -0.01085531 -0.1050978 -0.004630982 -0.01085531 -0.1060978 -7.73194e-4 -0.008734762 -0.1060978 -7.73194e-4 -0.004085958 -0.1070978 -7.73194e-4 -0.008734762 -0.1070978 -7.73194e-4 -0.004085958 -0.1060978 0.004211008 -0.008734762 -0.1070978 0.004211008 -0.008734762 -0.1060978 0.004211008 -0.004085958 -0.1070978 0.004211008 -0.004085958 -0.1060978 -0.004630982 -0.01085531 -0.1060978 -0.004630982 0.001844465 -0.1060978 0.008068799 -0.01085531 -0.1060978 0.008068799 0.001844465 -0.1101953 0.004152894 -0.00107634 -0.1101756 1.48206e-5 2.47402e-4 -0.1083896 0.003869891 -0.001910209 -0.1085957 -6.37763e-4 -7.25749e-4 -0.1102048 -7.083e-4 -0.001155436 -0.1107763 0.004787683 -0.002644181 -0.1085327 -2.17931e-4 -0.002159178 -0.1090103 -4.23984e-4 -0.01063627 -0.1099526 -9.64792e-4 -0.01177918 -0.1052289 -6.5335e-4 -0.01164597 -0.1054092 0.00371319 -0.01224321 -0.1055801 0.003955125 -0.01117873 -0.1078482 -0.00182867 -0.01005691 -0.1090961 0.00412178 -0.01182967 -0.1087568 0.0048967 -0.01030355 -0.1074376 0.002150595 -0.01092994 -0.1102591 -0.00334084 -0.00819534 -0.1073068 -0.004348516 -0.007526934 -0.1074106 0.009629547 -0.006856024 -0.1074049 0.005262732 -0.00239557 -0.107405 0.007577359 -0.002594292 -0.1117863 -0.004135727 -0.003054022 -0.1074048 -0.004311442 -0.002700746 -0.1074053 -0.005151927 -0.006070494 -0.1074081 -0.001846194 -0.002646565 -0.1073906 0.007609724 -0.01021456 -0.1097022 0.006891906 -0.008123636 -0.1111339 0.002815842 -0.008426845 -0.1117702 0.003128945 -0.005094587 -0.1105447 0.006753623 -0.004609942 -0.1109921 -3.67411e-4 -0.002615034 -0.1110959 -0.003189623 -0.004754006 -0.1107192 -0.001786172 -0.003114521 -0.1073593 0.007717609 -0.007498562 -0.107412 0.008482098 -0.006555676 -0.1073856 0.007298111 -0.005421936 -0.1071506 -0.002940237 -0.006511747 -0.1072322 0.006529331 -0.006589531 -0.1109372 -0.003587007 -0.006411671 -0.1109372 -0.004974901 -0.006570756 -0.1114314 0.008356332 -0.006434559 -0.1109372 0.007024884 -0.006570756 -0.1131169 0.003371775 -0.003468036 -0.1118107 0.00268197 -0.01036471 -0.1127994 -0.003198862 -0.00629729 -0.09425675 -2.89051e-4 0.03557509 -0.09492093 7.38167e-4 0.03514403 -0.09664565 0.002490401 0.03446835 -0.09501481 0.00260502 0.03515481 -0.09002864 -0.002138078 0.03455179 -0.08956062 8.47207e-4 0.03539466 -0.09075868 -6.19847e-4 0.03514403 -0.09192585 -0.001056253 0.03514403 -0.09314531 -9.51751e-4 0.03563511 -0.08967739 0.002712309 0.03567981 -0.09142345 0.004381954 0.03555136 -0.09036087 0.003740191 0.03514403 -0.09383517 0.004064977 0.03558534 -0.09267073 0.004493832 0.03514403 -0.0911346 0.006305992 0.03404092 -0.0952847 0.005348265 0.03395456 -0.09654533 -3.3033e-4 0.03382968 -0.09432506 -0.002492308 0.03389 -0.08762329 0.001047074 0.03378564 -0.08922493 0.004105091 0.02486485 -0.08989298 0.004325985 0.02413272 -0.0900554 0.005357086 0.02829462 -0.0912193 0.004768192 0.03121811 -0.09230583 0.006214857 0.02815681 -0.09271687 0.005246281 0.02407711 -0.09205913 0.005036115 0.0253129 -0.0928213 -0.003021657 0.02850997 -0.09261947 -0.002541005 0.0282793 -0.09227955 -0.001685678 0.03120779 -0.09175562 -0.001818716 0.02403736 -0.09123712 -0.002016007 0.02475535 -0.09472471 -8.83395e-4 0.02405977 -0.09489548 -0.001858353 0.02781969 -0.09419423 -0.001043438 0.02529817 -0.09314846 -0.001525521 0.02408272 -0.09478837 -9.6887e-4 0.03123605 -0.09137582 0.004968702 0.02383023 -0.09361386 0.004641234 0.0240522 -0.09338283 0.005464911 0.02404421 -0.09472393 0.004772603 0.02404421 -0.09606993 0.002962708 0.02412515 -0.09548807 0.001066088 0.02393591 -0.09538346 -6.66877e-4 0.02404421 -0.08922815 0.002718567 0.02385121 -0.0885384 0.002754449 0.02404421 -0.08849471 6.58806e-4 0.02398109 -0.08934605 1.73512e-4 0.02369439 -0.08987265 -0.001335024 0.02404421 -0.09605818 6.83118e-4 0.02404421 -0.09109616 -0.001996874 0.03205573 -0.09338283 0.005464911 0.03204411 -0.08921313 0.004104435 0.03204411 -0.09006285 -0.001546263 0.02378314 -0.08832079 0.00144869 0.02346462 -0.09423571 -3.02632e-4 0.02084422 -0.09522318 4.20832e-4 0.02084422 -0.09545177 0.002644777 0.02084201 -0.09580588 0.002984523 0.02248162 -0.09359109 0.004673421 0.02080368 -0.09116727 0.004774868 0.02084422 -0.08920937 6.07298e-4 0.020841 -0.09070169 -0.001054346 0.02084422 -0.09307873 -9.79707e-4 0.02088767 -0.08947861 0.003249883 0.02080762 -0.08949494 0.001829504 0.03039932 -0.08840602 0.00147444 0.03174412 -0.09449172 0.003462612 0.03063982 -0.09008699 2.26735e-5 0.02994328 -0.08961963 8.89776e-4 0.03141397 -0.08963543 8.51154e-4 0.02874279 -0.09509599 0.001605987 0.02874416 -0.09496051 0.00258851 0.02873939 -0.0950694 0.001597106 0.0319308 -0.09495991 0.002572774 0.03125745 -0.08953928 0.001040518 0.02091771 -0.08967566 0.002699434 0.02084422 -0.09036087 0.003740191 0.02084422 -0.09142982 0.004380643 0.02084422 -0.09267073 0.004493832 0.02084422 -0.09383791 0.004057407 0.02084422 -0.09492647 0.00279814 0.02091771 -0.0885384 0.002754449 0.03204411 -0.08990752 0.002117097 0.0276072 -0.09014874 4.43509e-4 0.02761912 -0.08962088 0.002247035 0.03171229 -0.09015095 0.003355503 0.02764415 -0.09015095 0.003355503 0.03789401 -0.08959484 9.5302e-4 0.03791755 -0.09115755 0.004165947 0.03789401 -0.09115755 0.004165947 0.02764415 -0.09242546 0.00441575 0.03789401 -0.09242546 0.00441575 0.02764415 -0.09366422 0.004047751 0.03789401 -0.09366422 0.004047751 0.02764415 -0.09408241 0.003769755 0.03156185 -0.09488779 0.002538442 0.03788113 -0.0949341 0.002578735 0.02762585 -0.0949487 0.001114666 0.03156185 -0.0947749 6.43555e-4 0.02764415 -0.0947749 6.43555e-4 0.03789401 -0.09397894 -3.68571e-4 0.03796899 -0.09399157 -3.84224e-4 0.02764415 -0.09280574 -8.5664e-4 0.03802394 -0.09282028 -9.30224e-4 0.02764415 -0.09155076 -7.97469e-4 0.03802394 -0.09152942 -8.69363e-4 0.02764415 -0.09036386 -2.72224e-4 0.03168362 -0.09451508 0.001254677 0.03120076 -0.09382128 0.003378033 0.03126311 -0.09010887 0.001337468 0.03103572 -0.09017235 0.002314805 0.03199416 -0.09061688 2.22351e-4 0.0310449 -0.09118133 -1.1824e-4 0.03074413 -0.09151232 -2.86884e-4 0.03740805 -0.09441465 0.00237286 0.03754407 -0.09336584 -9.6303e-5 0.0375427 -0.09022563 0.001085519 0.03754335 -0.09145677 0.003754496 0.03754401 -0.09327113 -2.71279e-4 0.0277999 -0.09185385 -3.84727e-4 0.02764415 -0.09274274 0.003822326 0.02764415 -0.09132546 0.003708839 0.02780252 -0.09449851 0.002436637 0.02763193 -0.09443223 0.001626133 0.02004426 -0.09396702 0.003052115 0.02004426 -0.0940048 0.002177298 0.01587152 -0.09016436 0.001811444 0.02004426 -0.09062957 3.85462e-4 0.02004426 -0.09061253 0.001060247 0.01577425 -0.09254604 0.003377377 0.02304422 -0.09254604 0.003377377 0.02684414 -0.09347653 5.25436e-4 0.02304422 -0.09347653 5.25436e-4 0.02684414 -0.09112006 0.002912163 0.02304422 -0.09205055 6.01774e-5 0.02304422 -0.09112006 0.002912163 0.02684414 -0.09205055 6.01774e-5 0.02684414 -0.09033572 0.00265628 0.02784413 -0.09333032 0.00363332 0.02784413 -0.09033572 0.00265628 0.02084422 -0.09333032 0.00363332 0.02084422 -0.09126627 -1.95715e-4 0.02784413 -0.09126627 -1.95715e-4 0.02084422 -0.09426087 7.81328e-4 0.02784413 -0.09426087 7.81328e-4 0.02084422 -0.09056323 0.005350828 0.02005898 -0.09108865 0.005426347 0.02404421 -0.0886901 0.003273546 0.02004295 -0.08882129 0.003485083 0.02404421 -0.08859068 5.09134e-4 0.02004426 -0.09083056 -0.002038419 0.02006077 -0.09403294 -0.00191307 0.02006584 -0.09350794 -0.001988768 0.02404421 -0.09590649 1.64047e-4 0.02004295 -0.09577536 -4.7495e-5 0.02404421 -0.09630477 0.001926898 0.0240426 -0.09600591 0.002928435 0.02004426 -0.09376585 0.005476117 0.02005875 -0.0941838 0.005148172 0.02406257 -0.09208756 0.003361105 0.02003002 -0.09315276 3.06148e-5 0.020024 -0.1431547 0.2175642 -0.018938 -0.142819 0.2160652 -0.01600092 -0.1440423 0.2187593 -0.01601463 -0.1428003 0.2163462 -0.0216698 -0.1438227 0.2149515 -0.02317821 -0.1455141 0.2154375 -0.01600426 -0.145363 0.2153718 -0.02066826 -0.1460275 0.2165742 -0.01820898 -0.1464477 0.2171319 -0.01601362 -0.1438626 0.2150111 -0.01600688 -0.1432887 0.2194018 -0.01641952 -0.1474564 0.2171003 -0.01626819 -0.1479868 0.2167904 -0.01610523 -0.1428507 0.2197818 -0.01611691 -0.143813 0.2187498 -0.01350528 -0.1421983 0.2170529 -0.01350528 -0.1420384 0.2169753 -0.01600521 -0.1423491 0.2153655 -0.01350528 -0.1432423 0.2143148 -0.01600521 -0.1458472 0.2147762 -0.01350528 -0.1460118 0.2149409 -0.01600521 -0.1464733 0.2175456 -0.01350528 -0.1435877 0.2142915 -0.01350528 -0.1340784 0.194122 -0.01817691 -0.1432828 0.2099571 -0.01838362 -0.1475361 0.2140992 -0.01850545 -0.135964 0.1940563 -0.01850521 -0.1441453 0.2115249 -0.01638275 -0.1333445 0.1929191 -0.01660519 -0.1368515 0.1988207 -0.01632916 -0.1334641 0.1925354 -0.01614904 -0.1289749 0.195128 -0.01615208 -0.1293451 0.1951743 -0.01654201 -0.1367407 0.2080484 -0.0181567 -0.1299982 0.1964705 -0.01833492 -0.1267021 0.1918667 -0.0530169 -0.1271291 0.1912174 -0.05340427 -0.1341083 0.2027814 -0.05352115 -0.1331372 0.2030514 -0.0529024 -0.138236 0.2001009 -0.05291444 -0.1373143 0.201156 -0.05346339 -0.1375702 0.2001843 -0.05349004 -0.1317079 0.1889016 -0.05336409 -0.131793 0.1887659 -0.05234962 -0.1302565 0.188775 -0.0523532 -0.1286982 0.1894858 -0.0525434 -0.1295905 0.1897551 -0.05352091 -0.1273189 0.1904773 -0.05232053 -0.1265397 0.1917989 -0.05234962 -0.142973 0.2084119 -0.03414392 -0.1376298 0.1987931 -0.05103558 -0.1336091 0.1918829 -0.04938638 -0.1339649 0.1920958 -0.04437232 -0.1354581 0.1939197 -0.03146868 -0.1345953 0.1933572 -0.04055678 -0.1369125 0.195753 -0.01925832 -0.1437128 0.2080407 -0.02864664 -0.1454886 0.2107355 -0.02100723 -0.1404762 0.2031389 -0.04067033 -0.1387513 0.2003282 -0.04263412 -0.1362813 0.195967 -0.04158872 -0.1419759 0.2057737 -0.03230667 -0.1416867 0.2047054 -0.03062611 -0.13314 0.1914156 -0.03525769 -0.1293685 0.1925961 -0.03677344 -0.1317919 0.192746 -0.02969014 -0.1316876 0.1951653 -0.0184738 -0.1360206 0.2020478 -0.05350589 -0.1336049 0.192772 -0.04998826 -0.1386088 0.200928 -0.04432517 -0.1377962 0.2001174 -0.04330712 -0.1336115 0.1929587 -0.04475104 -0.1291134 0.1953265 -0.05000197 -0.1292185 0.1946009 -0.04924905 -0.1279302 0.1943122 -0.05065417 -0.133427 0.2028033 -0.04328352 -0.1337188 0.203626 -0.04433202 -0.1340529 0.2054248 -0.04210919 -0.1290323 0.1956148 -0.04473334 -0.1282355 0.1952158 -0.0439037 -0.1323007 0.2016997 -0.05063533 -0.1325839 0.2011489 -0.05008691 -0.1368688 0.1985529 -0.04999804 -0.1346346 0.206497 -0.04040664 -0.136268 0.2097411 -0.0332303 -0.1406113 0.2181051 -0.01850521 -0.1372457 0.2116981 -0.02862614 -0.1290359 0.1980562 -0.01850521 -0.130024 0.1997293 -0.01915663 -0.1291185 0.1974716 -0.03124219 -0.1292058 0.1969779 -0.04247713 -0.1351834 0.2079983 -0.03062754 -0.1388694 0.214923 -0.02120596 -0.1293504 0.196339 -0.04079383 -0.1300522 0.1972343 -0.04136478 -0.1298907 0.1977219 -0.03334718 -0.1364184 0.2085545 -0.03160911 -0.136444 0.208723 -0.03254175 -0.1357696 0.2077504 -0.03133904 -0.1346843 0.1944048 -0.04147064 -0.1352499 0.194603 -0.03336477 -0.1411193 0.2049832 -0.0312913 -0.134678 0.2056507 -0.03978198 -0.1396369 0.2029049 -0.03976446 -0.1369557 0.196366 -0.01979357 -0.1371163 0.1972927 -0.02000117 -0.1364755 0.196909 -0.02049195 -0.1441983 0.2105124 -0.02144426 -0.138957 0.2137561 -0.02123463 -0.1443418 0.2099238 -0.02000254 -0.1355578 0.1954001 -0.02913916 -0.1360852 0.1962271 -0.03007996 -0.1307952 0.2002589 -0.01983642 -0.131037 0.2000237 -0.02044433 -0.1315411 0.2003592 -0.02006381 -0.142946 0.2077854 -0.02774804 -0.1384743 0.2132143 -0.02000325 -0.131303 0.1992715 -0.02995806 -0.1304216 0.1991852 -0.03031527 -0.1302679 0.1984362 -0.02921015 -0.1373425 0.2110784 -0.02745771 -0.1371772 0.2104665 -0.02784347 -0.1281611 0.1942902 -0.03525763 -0.1420044 0.2097551 -0.03390187 -0.139039 0.2094333 -0.03751516 -0.1289506 0.1928058 -0.01350528 -0.1314598 0.1913572 -0.01350528 -0.1457989 -0.2125997 -0.01893794 -0.1446684 -0.2115594 -0.01600086 -0.1463621 -0.2134812 -0.01601421 -0.1449215 -0.2116839 -0.02166926 -0.1432021 -0.2118719 -0.0231781 -0.1427774 -0.2135799 -0.01600426 -0.142796 -0.2134164 -0.02066749 -0.143505 -0.2145927 -0.01820898 -0.1450226 -0.2151413 -0.01602041 -0.1432335 -0.2119364 -0.01600688 -0.1473232 -0.2136346 -0.01641958 -0.1432462 -0.2160931 -0.01626819 -0.1427127 -0.2163977 -0.01610523 -0.1478712 -0.2134453 -0.01611697 -0.1462991 -0.2144092 -0.01350528 -0.146246 -0.2119276 -0.01350528 -0.145847 -0.2113385 -0.01600521 -0.1450071 -0.2108536 -0.01350528 -0.1429409 -0.211051 -0.01600521 -0.1421982 -0.2136151 -0.01350528 -0.1420985 -0.2137625 -0.01600521 -0.1427478 -0.2113385 -0.01350528 -0.1435139 -0.2152007 -0.01354491 -0.1300355 -0.1930184 -0.01817685 -0.1391465 -0.2089066 -0.01838362 -0.1406074 -0.2146616 -0.01850545 -0.1290358 -0.1946185 -0.01850521 -0.1400732 -0.2104378 -0.01638281 -0.1293607 -0.1917813 -0.01660519 -0.1327179 -0.1977689 -0.01632916 -0.1289685 -0.191693 -0.01614904 -0.1334584 -0.1891015 -0.01615208 -0.1333134 -0.1894453 -0.01654207 -0.1407649 -0.2022871 -0.0181567 -0.1341094 -0.1906591 -0.01833492 -0.1317704 -0.1855026 -0.0530169 -0.1309946 -0.1855477 -0.05340427 -0.1375199 -0.1973737 -0.05352115 -0.1382392 -0.1966679 -0.0529024 -0.1331346 -0.1996083 -0.05291444 -0.1345092 -0.1993377 -0.05346339 -0.1335397 -0.1990734 -0.05349004 -0.1266997 -0.1883553 -0.05336409 -0.1265396 -0.188361 -0.05234962 -0.1273157 -0.1870349 -0.0523532 -0.1287099 -0.1860411 -0.05254334 -0.1284976 -0.1869482 -0.05352091 -0.1302587 -0.1853421 -0.05232053 -0.1317929 -0.1853281 -0.05234962 -0.1379635 -0.2078663 -0.03414392 -0.1323051 -0.1984296 -0.05103534 -0.1283311 -0.1914923 -0.04938632 -0.1281884 -0.1916833 -0.04415977 -0.129198 -0.1941607 -0.03145587 -0.1300309 -0.1962881 -0.01925826 -0.1372723 -0.2083218 -0.02864676 -0.138718 -0.2112066 -0.02100735 -0.1346454 -0.2030674 -0.04067027 -0.1330736 -0.2001678 -0.04263412 -0.1299349 -0.1945562 -0.04135733 -0.1292809 -0.1935634 -0.04126513 -0.1361774 -0.2056837 -0.03230661 -0.1353967 -0.2048989 -0.03062623 -0.1281609 -0.1908524 -0.03525769 -0.131069 -0.1881765 -0.03677344 -0.129987 -0.1903502 -0.02969014 -0.132134 -0.1914696 -0.01847368 -0.1359284 -0.1986632 -0.05350589 -0.1291031 -0.1919332 -0.04998826 -0.1336644 -0.2003447 -0.04432517 -0.1333687 -0.1992357 -0.04330712 -0.129087 -0.1921281 -0.04475146 -0.133561 -0.1893208 -0.05000197 -0.1328802 -0.1890489 -0.04924905 -0.1332742 -0.1877888 -0.05065447 -0.1378793 -0.1967949 -0.04328352 -0.138446 -0.1974589 -0.04433214 -0.1398319 -0.1986436 -0.04211521 -0.1338514 -0.1893948 -0.04473334 -0.1339042 -0.1885056 -0.04390406 -0.1374869 -0.1952678 -0.05063521 -0.1368683 -0.1952375 -0.05008691 -0.1324775 -0.1976503 -0.04999804 -0.1404743 -0.1996875 -0.0404067 -0.1424672 -0.2027242 -0.0332303 -0.147539 -0.2106675 -0.01850521 -0.1436731 -0.2045493 -0.02862614 -0.1359639 -0.1906185 -0.01850521 -0.1369187 -0.1923107 -0.01915663 -0.1354162 -0.1903977 -0.03124219 -0.1349452 -0.1902268 -0.04247707 -0.1415002 -0.2009136 -0.03062748 -0.1456542 -0.2075679 -0.0212059 -0.1299194 -0.1942435 -0.03336477 -0.1293308 -0.1929754 -0.04049295 -0.1343196 -0.1900321 -0.04079371 -0.1347438 -0.1910877 -0.04136478 -0.1352469 -0.1911916 -0.03334718 -0.1413644 -0.202261 -0.03160911 -0.1414974 -0.2023675 -0.03254175 -0.1409924 -0.2012971 -0.03133904 -0.1359211 -0.2045466 -0.0312913 -0.1397199 -0.1993019 -0.03978198 -0.1348624 -0.2022236 -0.03976446 -0.1305401 -0.1966321 -0.01979362 -0.1312624 -0.1972345 -0.02000117 -0.1312506 -0.1964877 -0.02049195 -0.1391699 -0.2099776 -0.02144426 -0.1445997 -0.2070604 -0.02123463 -0.1385885 -0.2098076 -0.02000254 -0.1304026 -0.1949386 -0.02913933 -0.1308552 -0.1958088 -0.03007996 -0.1369917 -0.1932435 -0.01983642 -0.1366672 -0.1933352 -0.02044433 -0.1367057 -0.1939395 -0.02006381 -0.1374346 -0.2075296 -0.02774804 -0.144372 -0.2063715 -0.02000325 -0.1358827 -0.1931895 -0.02995806 -0.1362487 -0.192383 -0.03031527 -0.1356769 -0.1918754 -0.0292102 -0.1430881 -0.2043233 -0.02745777 -0.1426407 -0.2038741 -0.02784347 -0.1331398 -0.1879778 -0.03525763 -0.139611 -0.207699 -0.03390187 -0.140815 -0.2049699 -0.03751516 -0.1314595 -0.1879194 -0.01350528 -0.1289504 -0.1893681 -0.01350528 0.1307349 0.2336344 -0.0189383 0.1298022 0.2324138 -0.01600092 0.1310799 0.2350827 -0.01601463 0.1300298 0.2325804 -0.0216695 0.128304 0.232467 -0.0231781 0.1275892 0.2340752 -0.01600426 0.1276361 0.2339169 -0.02066868 0.1281298 0.235199 -0.01820892 0.128287 0.2358794 -0.01601362 0.1283239 0.2325359 -0.01600688 0.1320548 0.2349096 -0.0164321 0.1276144 0.2366317 -0.01626819 0.1270361 0.236839 -0.01610523 0.13239 0.234964 -0.01612573 0.1328643 0.234689 -0.01610523 0.1312201 0.2349008 -0.01350528 0.1312919 0.2330504 -0.01350528 0.1310014 0.232401 -0.01600521 0.1302585 0.2317776 -0.01350528 0.1281895 0.2316131 -0.01600521 0.1270127 0.2340094 -0.01350528 0.1268888 0.2341371 -0.01600521 0.1285877 0.2361649 -0.01350528 0.1279495 0.2318627 -0.01350528 0.1186112 0.2116135 -0.01817691 0.1248767 0.228978 -0.01838386 0.1252643 0.2347638 -0.01850545 0.1173489 0.2130157 -0.01850521 0.1254727 0.2305141 -0.01638275 0.1181616 0.210278 -0.01660519 0.1204293 0.2167614 -0.01632905 0.1177907 0.210123 -0.01614904 0.1224619 0.2086676 -0.01654744 0.12285 0.2082911 -0.01611161 0.1275682 0.2226046 -0.0181567 0.1230331 0.2099975 -0.01833492 0.1215969 0.2044155 -0.05292975 0.1208531 0.2044229 -0.05340427 0.1252257 0.2172023 -0.05352115 0.1260566 0.2166323 -0.0529024 0.1205189 0.2186415 -0.05291444 0.1219197 0.2186137 -0.05346339 0.1210108 0.218185 -0.05349004 0.1161359 0.2064419 -0.05336409 0.1159772 0.2064199 -0.05234962 0.116972 0.2052487 -0.0523532 0.1185175 0.2045121 -0.05254352 0.1181508 0.2053685 -0.05352091 0.1201642 0.2040927 -0.05232053 0.1216774 0.2043452 -0.05234962 0.1238406 0.2276125 -0.03414392 0.1169223 0.2091565 -0.05080091 0.1171321 0.2102242 -0.04437232 0.1175487 0.212462 -0.03162312 0.1176931 0.2115179 -0.04055666 0.118039 0.2148328 -0.01925837 0.1230931 0.2279524 -0.02861535 0.1240035 0.2310332 -0.02100741 0.1214062 0.2223104 -0.04067045 0.1203618 0.219182 -0.04263418 0.1186087 0.2144871 -0.04158866 0.1224606 0.225153 -0.03230673 0.1221366 0.22411 -0.03128683 0.1183902 0.2148604 -0.03096657 0.1198258 0.21713 -0.05062204 0.1171413 0.209155 -0.03525769 0.1204699 0.2070247 -0.03677344 0.1190269 0.2089775 -0.02969014 0.1209472 0.2104526 -0.0184738 0.1234343 0.2181959 -0.05350589 0.117962 0.2095804 -0.04938709 0.1178814 0.210383 -0.04998826 0.1208711 0.2194744 -0.04432183 0.1208142 0.2183153 -0.04330712 0.1180203 0.210508 -0.04475104 0.1227254 0.2085843 -0.05000197 0.1221021 0.2081984 -0.04924905 0.122709 0.2070259 -0.05065429 0.1256802 0.2166947 -0.04328352 0.1261229 0.2174471 -0.04433202 0.1272821 0.2188545 -0.04211527 0.1230666 0.2086824 -0.04473239 0.1235403 0.2084316 -0.03999918 0.1241104 0.2101119 -0.04307472 0.1255588 0.2151226 -0.05063527 0.1249549 0.2149854 -0.05008691 0.1205184 0.2164933 -0.05000126 0.127712 0.2199474 -0.04067409 0.1291688 0.2233306 -0.0332303 0.1327841 0.232034 -0.01850521 0.1300382 0.225333 -0.02851676 0.1248663 0.2102795 -0.01850521 0.1255043 0.2121027 -0.01925778 0.1285308 0.2213793 -0.03062766 0.1249966 0.2116805 -0.0312854 0.1314662 0.2286542 -0.02120614 0.1240608 0.2107195 -0.03334718 0.1182356 0.2128171 -0.03336423 0.1232879 0.2092749 -0.04157865 0.1281633 0.2226829 -0.03160911 0.1282756 0.2228109 -0.03254187 0.1279642 0.2216691 -0.03133904 0.1184384 0.2122594 -0.0414707 0.1228836 0.2098607 -0.04102146 0.1271439 0.219613 -0.03947502 0.1268706 0.2190115 -0.03986799 0.1217665 0.2215171 -0.03976446 0.1184808 0.21526 -0.01979362 0.1190874 0.2159788 -0.02000117 0.1192056 0.2152411 -0.02049195 0.1246621 0.2299014 -0.02144426 0.1305158 0.2279713 -0.02123469 0.124119 0.2296329 -0.02000254 0.1186394 0.2135683 -0.02913922 0.1189012 0.2144647 -0.03008878 0.1233781 0.2271891 -0.02774804 0.1303992 0.227257 -0.02000313 0.1252349 0.2130931 -0.02031123 0.1250202 0.2136789 -0.02006381 0.1243399 0.2127974 -0.02995806 0.1240854 0.2118321 -0.02968955 0.1244234 0.2109404 -0.0304889 0.1240091 0.2116915 -0.02877956 0.1295025 0.2250132 -0.02745783 0.1290951 0.2245229 -0.02784132 0.1225438 0.2071887 -0.03525763 0.1254921 0.2277339 -0.03390187 0.1271518 0.2252553 -0.03751516 0.1208992 0.2068394 -0.01350528 0.1181766 0.2078303 -0.01350528 0.1278657 -0.2312411 -0.01893794 0.1275832 -0.229857 -0.01601237 0.1274538 -0.2314567 -0.01601094 0.1277282 -0.2299802 -0.0216695 0.1289774 -0.2287842 -0.0231781 0.1293829 -0.2287828 -0.01600331 0.1304214 -0.2294656 -0.02066791 0.1308669 -0.2307649 -0.01820909 0.1310867 -0.2313408 -0.01601517 0.1292248 -0.232592 -0.01602017 0.1276742 -0.2330662 -0.0164321 0.1321827 -0.2315312 -0.01626819 0.1327589 -0.2313182 -0.01610523 0.1274524 -0.2333233 -0.01612573 0.1269122 -0.2334176 -0.01610523 0.1289303 -0.2327874 -0.01350528 0.1270128 -0.2305715 -0.01350528 0.1277588 -0.2285584 -0.01350528 0.1285164 -0.2280563 -0.01600521 0.1300476 -0.2282413 -0.01350528 0.131135 -0.2291537 -0.01600521 0.1313185 -0.231252 -0.01350528 0.1312921 -0.2296126 -0.01350528 0.1229982 -0.206579 -0.01817691 0.1293605 -0.2239089 -0.01838392 0.1327823 -0.2285896 -0.01850545 0.1248664 -0.2068417 -0.01850521 0.1298907 -0.2254674 -0.01638275 0.1224842 -0.2052669 -0.01660519 0.1249133 -0.2116883 -0.0163291 0.1226686 -0.2049098 -0.01614904 0.1181547 -0.2067974 -0.01654738 0.1176155 -0.2067584 -0.01611161 0.1232016 -0.2207561 -0.0181567 0.1185721 -0.2081833 -0.01833492 0.1160842 -0.202984 -0.05292975 0.1166588 -0.2025117 -0.05340427 0.1215236 -0.215112 -0.05352115 0.1205206 -0.2152093 -0.0529024 0.1260542 -0.213189 -0.05291444 0.1249634 -0.214068 -0.05346339 0.125384 -0.2131555 -0.05349004 0.1215701 -0.2010262 -0.05336409 0.1216775 -0.2009074 -0.05234962 0.1201627 -0.2006494 -0.0523532 0.1185047 -0.2010789 -0.0525434 0.1193366 -0.2014991 -0.05352091 0.1169742 -0.201816 -0.05232053 0.1159774 -0.202982 -0.05234962 0.1292762 -0.2221963 -0.03414392 0.1227127 -0.2036112 -0.05080109 0.1232382 -0.204564 -0.04437226 0.1241179 -0.2060685 -0.0338695 0.12364 -0.2059155 -0.0405566 0.1255058 -0.2086773 -0.01925843 0.1246466 -0.2073668 -0.02984172 0.1252546 -0.2089244 -0.03096652 0.1300674 -0.2219763 -0.02861541 0.13135 -0.2249214 -0.02100735 0.1277329 -0.2165698 -0.04067033 0.1265224 -0.2135025 -0.04263412 0.1248469 -0.208778 -0.04158872 0.1287523 -0.2194252 -0.03230667 0.1284219 -0.217931 -0.03088968 0.1256137 -0.2115856 -0.05062216 0.1225438 -0.2037507 -0.03525769 0.1186248 -0.2042584 -0.03677344 0.1209853 -0.2048268 -0.02969014 0.1204626 -0.2071912 -0.0184738 0.1235345 -0.2147216 -0.05350589 0.1221886 -0.2046041 -0.04938703 0.1227662 -0.2051673 -0.04998826 0.12632 -0.2140533 -0.04432183 0.1256184 -0.2131288 -0.04330712 0.1227402 -0.2053522 -0.04475104 0.1178994 -0.2069031 -0.05000197 0.1181288 -0.2062067 -0.04924905 0.1169102 -0.2056986 -0.05065423 0.1208491 -0.2150152 -0.04328352 0.1209937 -0.2158761 -0.0443319 0.1210102 -0.2177056 -0.04210907 0.1177695 -0.2071729 -0.04473328 0.1170541 -0.2066416 -0.0439037 0.1199315 -0.2137327 -0.05063539 0.120306 -0.2132396 -0.05008691 0.1246739 -0.211543 -0.05000126 0.1213835 -0.2188129 -0.0406742 0.1224422 -0.2223411 -0.0332303 0.125267 -0.2313322 -0.01850521 0.1230634 -0.2244338 -0.02851682 0.117349 -0.2095779 -0.01850521 0.1180322 -0.2113844 -0.0192579 0.1175319 -0.2090163 -0.03124219 0.1177654 -0.2086298 -0.04205065 0.1216766 -0.2204363 -0.03062736 0.1241042 -0.2278959 -0.02120596 0.1240354 -0.207194 -0.03370946 0.1244705 -0.2076027 -0.03292733 0.123973 -0.2080318 -0.0332418 0.1179569 -0.2079413 -0.04079377 0.1189092 -0.2089496 -0.04134243 0.1182489 -0.209397 -0.03334712 0.1227962 -0.2211986 -0.03160911 0.1227922 -0.2213689 -0.03254181 0.1222969 -0.2202939 -0.03133904 0.1235457 -0.2069627 -0.04147064 0.127633 -0.2183575 -0.03133839 0.1215782 -0.2180393 -0.03978234 0.1269471 -0.2161936 -0.03976446 0.1301181 -0.2244777 -0.02144426 0.1243932 -0.2267619 -0.02123469 0.1303616 -0.2239229 -0.02000254 0.1254392 -0.210229 -0.02000117 0.1252802 -0.2096363 -0.02029007 0.1239839 -0.2081283 -0.02941143 0.124714 -0.2092371 -0.03003597 0.1293584 -0.2215747 -0.02774804 0.1239833 -0.2261561 -0.02000355 0.1187186 -0.2120465 -0.01983416 0.1193743 -0.2121533 -0.02006435 0.1193706 -0.2111682 -0.02995806 0.1187193 -0.210033 -0.02946817 0.1180046 -0.2098184 -0.03058195 0.1232681 -0.2238445 -0.02745777 0.1232649 -0.223207 -0.02784132 0.1171414 -0.2057171 -0.03525763 0.128089 -0.2233509 -0.03390187 0.1252245 -0.222519 -0.03751516 0.1181766 -0.2043924 -0.01350528 0.1208993 -0.2034015 -0.01350528 -0.0394777 0.05364036 0.002972543 -0.03806185 0.05537784 0.003030896 -0.03986907 0.05678933 0.002994477 -0.04124933 0.05506002 0.003035783 -0.03963512 0.05218148 0.007727563 -0.03715556 0.05353647 0.007829189 -0.04226505 0.05394601 0.007735311 -0.04241019 0.05648684 0.008073508 -0.03964346 0.05824154 0.007726192 -0.03718948 0.05695277 0.007832765 -0.04090636 0.05274736 0.00905013 -0.04026269 0.05451512 0.007883548 -0.03943955 0.05713719 0.009431421 -0.03787803 0.05456846 0.009526014 0.06860619 -0.03484618 0.003010571 0.06972384 -0.03325074 0.003034472 0.06800276 -0.03181523 0.003013253 0.06659179 -0.03306269 0.00304085 0.06709897 -0.03453946 0.003036916 0.06812298 -0.03642314 0.007736146 0.07031929 -0.03477555 0.008421301 0.0705623 -0.03164345 0.007833302 0.06812161 -0.03036141 0.007730185 0.06549406 -0.03466081 0.007732689 0.0653451 -0.03212273 0.0080778 0.06685173 -0.03585606 0.00905013 0.06726133 -0.03414744 0.008208036 0.06776374 -0.03143912 0.009390354 0.06986576 -0.03279489 0.009408652 0.05525678 -0.05441659 0.003038704 0.05386471 -0.05490726 0.003036379 0.05560082 -0.05290192 0.00304073 0.05448424 -0.05190891 0.003044664 0.05296736 -0.05235302 0.003038823 0.05262851 -0.0538659 0.003040492 0.05648761 -0.05525565 0.007726073 0.05378502 -0.05635714 0.008115231 0.05656319 -0.05164647 0.007832765 0.05411618 -0.05035722 0.007730185 0.05179584 -0.05463361 0.008367955 0.05133455 -0.05211347 0.008064985 0.05346649 -0.05279123 0.007774651 0.05415588 -0.05139923 0.009497046 0.05589526 -0.05440324 0.009422183 0.04946267 -0.04183113 0.003002464 0.05083334 -0.04053592 0.003037512 0.05038362 -0.03913605 0.003039956 0.04890888 -0.0387547 0.002969145 0.04774796 -0.0403909 0.003030955 0.04932934 -0.04326349 0.007736146 0.05228191 -0.04089385 0.007735371 0.05148983 -0.03813946 0.007812201 0.04887831 -0.03722882 0.00802946 0.0466994 -0.0414977 0.007735311 0.04656231 -0.03896158 0.008097767 0.04805809 -0.04269635 0.00905013 0.04810458 -0.04086863 0.009015917 0.04919612 -0.03861314 0.009364426 0.05121016 -0.04116797 0.009490668 0.05010527 -0.04067814 0.007716476 0.0665276 0.03684842 0.003014147 0.06764441 0.03537249 0.003038525 0.06914037 0.03568774 0.003038406 0.06961524 0.03714078 0.003034651 0.06814193 0.03841829 0.003035783 0.06513476 0.03793114 0.007742047 0.06612426 0.03458976 0.007829666 0.0695306 0.03417551 0.007830977 0.07128494 0.03756481 0.007982134 0.06925112 0.03965699 0.008094966 0.06657093 0.03825908 0.009454071 0.06974375 0.0366829 0.00930041 0.06733584 0.03518509 0.009071052 -0.03163307 -0.04093366 0.003041326 -0.03130435 -0.03874921 0.003038704 -0.03310877 -0.03818678 0.003035366 -0.03416633 -0.03932851 0.00304085 -0.03361648 -0.04084849 0.003038167 -0.03015387 -0.04133313 0.007827341 -0.03264236 -0.04268842 0.007731676 -0.03018492 -0.03790676 0.0078125 -0.03264385 -0.03662633 0.007733881 -0.03526407 -0.04092663 0.007732689 -0.03541302 -0.03838849 0.0080778 -0.03390645 -0.04212182 0.00905013 -0.03372627 -0.04001533 0.008207917 -0.03243964 -0.037732 0.009431421 -0.03096419 -0.04050004 0.009388327 -0.05548411 -0.04244554 0.00303477 -0.05720818 -0.04330152 0.003036379 -0.05590105 -0.04068589 0.003039956 -0.05790203 -0.04046225 0.003027379 -0.05841851 -0.04226511 0.003037691 -0.05416083 -0.04321414 0.007768452 -0.05844557 -0.04453605 0.008252978 -0.0547949 -0.0396893 0.007812201 -0.05829888 -0.03905481 0.00773096 -0.0598545 -0.0407148 0.008116602 -0.0579304 -0.04220187 0.007947266 -0.05675983 -0.03985631 0.009431421 -0.05562162 -0.04291212 0.009488582 -0.03143298 0.04208254 0.003049314 -0.03288805 0.0415678 0.003036379 -0.03127974 0.04394036 0.00303322 -0.03312563 0.04454982 0.003010571 -0.03424328 0.04295438 0.003034472 -0.03026169 0.04122591 0.00773096 -0.03463006 0.04062944 0.007739841 -0.03018492 0.04483824 0.0078125 -0.0326336 0.04611593 0.00774151 -0.03538608 0.04434776 0.008129596 -0.03390645 0.04062312 0.00905013 -0.03395766 0.04260653 0.00888741 -0.03259688 0.04507583 0.009497046 -0.03075438 0.04215157 0.009490668 -0.03199666 0.04309141 0.00752747 -0.04941725 0.03161376 0.003126442 -0.04845291 0.03276836 0.003038704 -0.04920649 0.0345062 0.003027737 -0.0514068 0.03373944 0.003027319 -0.05093681 0.03189665 0.003038167 -0.05006742 0.03001379 0.00796616 -0.0470817 0.03192651 0.007787764 -0.0487082 0.03609305 0.007793903 -0.05226111 0.03184247 0.008399784 -0.05272477 0.0343576 0.008087396 -0.0506066 0.03249877 0.007774591 -0.04962956 0.03499883 0.009369969 -0.04819846 0.03244441 0.009526014 -0.0564745 0.04372805 0.003097534 -0.05535453 0.04535281 0.003034472 -0.05707561 0.04678833 0.003013253 -0.05848658 0.0455408 0.00304085 -0.05793672 0.04402083 0.003038167 -0.05706727 0.04213798 0.00796616 -0.05448192 0.04352939 0.007829546 -0.05451607 0.04696011 0.007833302 -0.05713748 0.04828923 0.007947981 -0.05926102 0.04396665 0.008399784 -0.05973327 0.04648083 0.0080778 -0.05805069 0.04613345 0.008945167 -0.05514878 0.04527103 0.009515881 -0.05695897 0.04431563 0.007716476 -0.04990088 -0.0312224 0.00297755 -0.04835629 -0.02944737 0.00303632 -0.04968851 -0.02810454 0.003065347 -0.05111992 -0.02860695 0.003045737 -0.0514186 -0.03014093 0.003037691 -0.04815375 -0.03217446 0.007789134 -0.04718947 -0.02815276 0.007775902 -0.051301 -0.02693158 0.007731616 -0.051454 -0.03236573 0.008342742 -0.05285459 -0.02859055 0.008116602 -0.05106204 -0.03050953 0.008806645 -0.05005735 -0.0276156 0.009403407 -0.04819846 -0.03030085 0.009526014 -0.04910975 -0.02925264 0.00775361 -0.03809016 -0.05204868 0.003042519 -0.03857243 -0.05067837 0.003034293 -0.04005175 -0.050314 0.00305444 -0.0411663 -0.05145269 0.00304085 -0.04061645 -0.05297267 0.003038167 -0.03715127 -0.05346256 0.007809162 -0.03963518 -0.05481195 0.007727563 -0.03728169 -0.04987341 0.007722914 -0.04007232 -0.04880475 0.008077263 -0.04226404 -0.05305081 0.007732689 -0.04241299 -0.05051273 0.0080778 -0.04090636 -0.05424606 0.00905013 -0.04087322 -0.05249005 0.008690714 -0.03959989 -0.05038446 0.008711934 -0.03762137 -0.05070716 0.009371519 -0.03846853 -0.05263513 0.008830428 0.04910844 0.04517418 0.003064692 0.047912 0.04423242 0.003039836 0.0481283 0.04272484 0.003040373 0.04954302 0.04215776 0.003064692 0.0507394 0.04309952 0.003039836 0.05052316 0.04460704 0.003040373 0.04723417 0.04581224 0.007828891 0.05063652 0.04656636 0.007741808 0.04658323 0.04244226 0.007828891 0.04880344 0.04069846 0.008081138 0.05167901 0.04164993 0.008114457 0.0521869 0.04309427 0.007732629 0.05037057 0.04550838 0.009538948 0.05004185 0.0429039 0.008013665 0.04889094 0.04214304 0.009529113 0.04754668 0.04402166 0.009405076 0.05453026 0.05535882 0.003058552 0.05559921 0.0564478 0.003035724 0.05517184 0.05791354 0.003039956 0.05364394 0.05828827 0.003035366 0.05258637 0.05714654 0.00304085 0.05309355 0.05566984 0.003036916 0.05630886 0.05476832 0.007804512 0.05212271 0.05435949 0.007739841 0.05712634 0.05685734 0.007992446 0.05536788 0.05982387 0.007788658 0.05133968 0.05808657 0.0080778 0.05284631 0.05435317 0.00905013 0.05302643 0.05645972 0.008207917 0.05431306 0.05874305 0.009431421 0.05534672 0.05580824 0.009211361 0.07344943 0.04850339 0.003126382 0.07441377 0.04965794 0.003038704 0.07394057 0.05112397 0.003038704 0.07243752 0.05144792 0.003035366 0.07137995 0.05030626 0.00304085 0.07192981 0.04878628 0.003038167 0.07578498 0.04881614 0.007787764 0.07291114 0.046947 0.007727563 0.07506936 0.05207395 0.007811188 0.07246011 0.05298042 0.00802946 0.07028222 0.04870814 0.007732689 0.07013332 0.05124622 0.0080778 0.07163989 0.04751288 0.00905013 0.07229387 0.04920834 0.007934033 0.07321947 0.0515592 0.009261667 0.07466816 0.04933404 0.009526014 0.07345354 -0.04798722 0.003030896 0.07441377 -0.04686647 0.003038704 0.07397383 -0.04544389 0.003034293 0.07174676 -0.04549652 0.003045737 0.07158654 -0.04746419 0.003033876 0.07424527 -0.04925686 0.007741212 0.0758996 -0.04746043 0.008038222 0.07506155 -0.04444336 0.007808685 0.07156562 -0.04382115 0.007731616 0.07142341 -0.0492447 0.008362531 0.07001203 -0.04548019 0.008116602 0.07197511 -0.04707872 0.008058726 0.07255196 -0.0445947 0.009390354 0.07439374 -0.04595798 0.009172558 0.07303172 -0.0481255 0.009540796 -0.0321663 -0.03818726 -0.01716524 -0.03133976 -0.03890359 -0.01716196 -0.03117245 -0.04012608 -0.01716208 -0.03188878 -0.04095256 -0.01716196 -0.03311127 -0.04111987 -0.01716518 -0.03414487 -0.03997749 -0.01716208 -0.03367239 -0.03851121 -0.01716214 -0.03263866 -0.03850096 -0.02923595 -0.0337305 -0.04057127 -0.03006833 -0.04948657 -0.02818739 -0.01716524 -0.04845297 -0.02932971 -0.01716208 -0.04892545 -0.03079605 -0.01716214 -0.0504316 -0.03112 -0.01716518 -0.05146521 -0.02997761 -0.01716208 -0.05099266 -0.02851134 -0.01716214 -0.05063229 -0.02849024 -0.02992182 -0.05128628 -0.03066408 -0.03068125 -0.04983913 -0.03070676 -0.02907121 -0.04868882 -0.02884972 -0.03043657 -0.0321663 0.04455775 -0.01716518 -0.03113269 0.04341536 -0.01716208 -0.03160518 0.04194909 -0.01716214 -0.03311127 0.04162514 -0.01716518 -0.03414493 0.04276746 -0.01716208 -0.03367239 0.04423379 -0.01716214 -0.03274613 0.04505354 -0.0304923 -0.03413289 0.04229682 -0.03023266 -0.03164982 0.0421819 -0.02978581 0.04979819 0.04513233 -0.01716524 0.05083185 0.04398995 -0.01716208 0.0503593 0.04252362 -0.01716214 0.04885321 0.04219967 -0.01716524 0.04781961 0.04334205 -0.01716208 0.0482921 0.04480832 -0.01716214 0.04801273 0.04455733 -0.03073346 0.04845911 0.0434814 -0.02895337 0.05095428 0.04364061 -0.03052812 0.04979825 -0.03876173 -0.01716524 0.05062478 -0.03947806 -0.01716196 0.05079203 -0.04070055 -0.01716208 0.0500757 -0.04152709 -0.01716196 0.04885327 -0.0416944 -0.01716518 0.04781961 -0.04055202 -0.01716208 0.04829216 -0.03908568 -0.01716214 0.04825717 -0.04140532 -0.03045326 0.05029827 -0.04065239 -0.02907258 0.04931271 -0.03858059 -0.03059345 0.06859183 0.03829199 -0.01716524 0.06941837 0.03757566 -0.01716196 0.06958562 0.03635317 -0.01716208 0.06886935 0.03552669 -0.01716196 0.0676468 0.03535938 -0.01716518 0.06661319 0.03650176 -0.01716208 0.06708574 0.03796803 -0.01716214 0.06701642 0.03768151 -0.02992981 0.06568461 0.03714907 -0.03030145 0.06802797 0.03500491 -0.02987325 0.07009148 0.0368278 -0.03068488 0.06941813 -0.03254693 -0.01715916 0.06949692 -0.03409212 -0.01716184 0.06819814 -0.03493297 -0.01716178 0.06682056 -0.03422862 -0.01715916 0.06674176 -0.03268343 -0.01716184 0.06804054 -0.03184258 -0.01716178 0.07091307 -0.03222054 -0.02885723 0.07097208 -0.03465139 -0.02915626 0.06837111 -0.03638255 -0.02893263 0.06544524 -0.03502321 -0.02905505 0.06879132 -0.03033584 -0.0293951 0.06520724 -0.03227609 -0.02916371 0.06755316 -0.03263914 -0.0290066 0.06716996 -0.03465539 -0.03065228 0.06964349 -0.03387796 -0.03042036 -0.04954445 0.03456521 -0.01698648 -0.04866003 0.03384155 -0.01716196 -0.04847103 0.03261178 -0.01716709 -0.04920911 0.03179252 -0.01716196 -0.04995906 0.03159159 -0.01716196 -0.05110484 0.03205978 -0.01716232 -0.05144512 0.03357285 -0.01716643 -0.05070906 0.03439056 -0.01716196 -0.04998099 0.03463619 -0.03055495 -0.05138152 0.0323497 -0.03059685 -0.04850238 0.03225094 -0.03053075 -0.05036073 0.03368383 -0.028692 0.08376342 0.04215687 0.010827 0.08193492 0.04263913 0.01084297 0.08403408 0.04060834 0.01083451 0.08244448 0.03953999 0.01083993 0.08102995 0.04082298 0.01083546 0.0808677 0.04011398 0.004387795 0.08096641 0.04316616 0.004761934 0.08430367 0.04043143 0.004369139 0.08375865 0.04273545 0.004343509 0.0819326 0.0419647 0.005797445 0.08258748 -0.03611254 0.01086854 0.08415633 -0.03774029 0.01084125 0.08252763 -0.03930771 0.01086854 0.08095878 -0.03768002 0.01084125 0.08088433 -0.03920996 0.004376947 0.08088642 -0.03655111 0.004467964 0.08392864 -0.03929001 0.004335761 0.08426314 -0.0362575 0.004367291 0.08356392 -0.03804653 0.005926966 -0.120333 0.1504606 -0.001932799 -0.1205295 0.1506347 -0.003543376 -0.1042975 0.1551409 -0.009370326 -0.1043468 0.1548511 -0.005163729 -0.1032232 0.1533153 -0.008998632 -0.1026527 0.1517232 -0.007447659 -0.1057386 0.1542344 -0.005508124 -0.105412 0.1516249 -0.00580269 -0.1091552 0.1601218 -0.005803227 -0.1075505 0.1573753 -0.00548917 -0.1086826 0.1605322 -0.005283236 -0.1109083 0.1510612 -0.0052616 -0.1111302 0.1511232 -0.009383201 -0.1098061 0.1488119 -0.00819993 -0.1089044 0.1480455 -0.00758171 -0.1155478 0.1742681 -0.005197107 -0.1153129 0.1742045 -0.009413123 -0.1165718 0.1763759 -0.008198678 -0.1148884 0.170164 -0.00529325 -0.1133928 0.1674616 -0.005803227 -0.1127961 0.1676709 -0.005278348 -0.1147735 0.1703525 -0.005803227 -0.1221479 0.1701914 -0.009383797 -0.1221002 0.1704466 -0.005208253 -0.1231925 0.1719724 -0.008951127 -0.1237823 0.1735914 -0.007376611 -0.1179473 0.164837 -0.00559175 -0.1188868 0.1679777 -0.005803227 -0.1186215 0.167362 -0.005290091 -0.1185805 0.1542716 -0.006913304 -0.1197297 0.1524264 -0.005058526 -0.1164773 0.1541457 -0.00833863 -0.1215828 0.164097 -0.009128153 -0.1231326 0.1622272 -0.007083475 -0.1252162 0.1619656 -0.005015134 -0.1253296 0.1625853 -0.005044162 -0.1159254 0.1547828 -0.009154856 -0.1148109 0.1551483 -0.009144067 -0.1205277 0.1650503 -0.009144067 -0.1005339 0.1619952 -0.00473833 -0.1006403 0.1610771 -0.005658805 -0.09821516 0.1583703 -0.004930555 -0.1040182 0.1592978 -0.009064614 -0.1011555 0.1551001 -0.009078145 -0.09945911 0.1540548 -0.007970333 -0.1125398 0.1463818 -0.008035361 -0.1101152 0.1519795 -0.009383201 -0.1116001 0.1545653 -0.009383201 -0.1149175 0.1526496 -0.009238123 -0.1125224 0.1485664 -0.00917977 -0.1070177 0.157211 -0.009383201 -0.1055177 0.1546338 -0.009383201 -0.1269699 0.1714127 -0.0080446 -0.1163177 0.1780034 -0.007656812 -0.113212 0.178767 -0.007699131 -0.1137958 0.1767608 -0.009167432 -0.1108628 0.1727381 -0.00833863 -0.1078709 0.1742902 -0.005019843 -0.1094514 0.1777769 -0.004992127 -0.1170052 0.1475576 -0.004944622 -0.1183866 0.1508475 -0.00539422 -0.1163299 0.1733539 -0.009383201 -0.1147201 0.1705518 -0.009144067 -0.11205 0.17238 -0.009360611 -0.1194272 0.1681225 -0.009383201 -0.1223927 0.1662091 -0.009257197 -0.1209272 0.1706997 -0.009383201 -0.1252046 0.1703196 -0.009164273 -0.1024248 0.1687837 -0.00166589 -0.1029891 0.1696313 -0.003532886 -0.1062543 0.1751945 -0.001859545 -0.1056176 0.1750525 -0.003558576 -0.1020814 0.1701395 -0.002980113 -0.1046524 0.1747477 -0.002913951 -0.1044719 0.174543 -0.001881361 -0.1289845 0.1631432 -0.002107679 -0.1273052 0.1623699 -0.003532886 -0.1263082 0.1612239 -0.001679003 -0.1247441 0.1570829 -0.00370121 -0.1239256 0.156432 -0.001655936 -0.1279719 0.1612871 -0.002898871 -0.1253258 0.1566852 -0.00281006 -0.1247638 0.1555562 -0.001654744 -0.1013107 0.1695648 -0.001644313 -0.09678781 0.1645892 -0.001649558 -0.1028826 0.1751502 -0.001646816 -0.09805309 0.1639369 -0.001668095 -0.1062943 0.1724179 -0.001628279 -0.1012274 0.163745 -0.001659154 -0.10339 0.1632624 -0.002964615 -0.1078104 0.1752375 -0.002118885 -0.09911221 0.1623726 -0.001673042 -0.1049653 0.1766241 -0.001986086 -0.09702575 0.1629102 -0.001962721 -0.09922122 0.1602821 -0.00286436 -0.1236301 0.1610471 -0.001652896 -0.1297014 0.1608425 -0.00165373 -0.1235624 0.1501832 -0.001646816 -0.1212134 0.148741 -0.001754462 -0.1200835 0.1526927 -0.001637756 -0.1186941 0.1500959 -0.002093911 -0.1232714 0.1620005 -0.002528667 -0.1186512 0.1546259 -0.002953827 -0.119323 0.1517273 -0.004855811 -0.1010715 0.1631464 -0.005057692 -0.1108775 0.1483358 -0.01138317 -0.1244611 0.171863 -0.01138317 -0.101984 0.1534703 -0.01138317 -0.1155675 0.1769977 -0.01138317 -0.1109286 0.1471806 -0.0107274 -0.1009983 0.1529178 -0.01076018 -0.1131349 0.1467391 -0.01031112 -0.1229382 0.1493314 -0.00297743 -0.1296285 0.16092 -0.00296086 -0.128223 0.1669787 -0.004984319 -0.1271182 0.1702912 -0.009816467 -0.1257257 0.1722477 -0.01076376 -0.1154881 0.1781582 -0.01074534 -0.1133099 0.1785943 -0.01031112 -0.1035091 0.1760054 -0.002957165 -0.09681427 0.164412 -0.002945423 -0.09966731 0.1538532 -0.01083946 -0.1236739 0.1664997 -0.01096576 -0.1115378 0.1474331 -0.01127725 -0.1152374 0.1519954 -0.01098895 -0.1255716 0.1717366 -0.01127678 -0.125449 0.1680105 -0.01061946 -0.1153755 0.1499782 -0.01046544 -0.1145467 0.1475881 -0.009902834 -0.1258651 0.1634109 -0.008012473 -0.1269376 0.1690816 -0.009918689 -0.1289975 0.161394 -0.004290938 -0.1254665 0.1620368 -0.00744754 -0.1198669 0.1523075 -0.007651388 -0.1230257 0.1498618 -0.003696501 -0.1172741 0.1504905 -0.008535087 -0.1008549 0.1631119 -0.00765556 -0.1067609 0.1733442 -0.007652103 -0.1035974 0.1755213 -0.003826022 -0.1118966 0.1777448 -0.009901642 -0.0994997 0.156284 -0.00989592 -0.1009334 0.1585411 -0.01011842 -0.1009885 0.1594463 -0.008869409 -0.097247 0.1646956 -0.003739058 -0.1115649 0.1739971 -0.01099169 -0.1149073 0.1779003 -0.01127725 -0.1029735 0.159076 -0.01098895 -0.1008737 0.1535967 -0.01127684 -0.1067417 0.1729483 -0.005054712 -0.1096898 0.1710599 -0.008504509 -0.1078871 0.1710714 -0.006936371 -0.1033484 0.1631813 -0.006952106 -0.1041874 0.1615296 -0.008504509 -0.1268557 0.1643475 -0.002215206 -0.1257036 0.164017 -0.005296289 -0.1235509 0.1658627 -0.01014292 -0.1248638 0.1665738 -0.009786486 -0.1153207 0.1510431 -0.009775936 -0.123755 0.1623134 -0.008463263 -0.1227613 0.1618067 -0.009063005 -0.1185476 0.1543228 -0.00888288 -0.1110056 0.1743866 -0.01013839 -0.1110181 0.1735826 -0.01009041 -0.1103978 0.1747718 -0.009233832 -0.1018574 0.1587471 -0.009952127 -0.1025604 0.1588983 -0.01010572 -0.1033898 0.1630727 -0.008888185 -0.1079651 0.1710245 -0.00891757 -0.1078281 0.1707868 -0.002982854 -0.1068172 0.1600519 -0.009383201 -0.1059172 0.1602831 -0.009144067 -0.1081808 0.1622694 -0.009379982 -0.1107301 0.1704206 -0.009278774 -0.1110721 0.167078 -0.009138941 -0.1122843 0.1695213 -0.009383201 -0.1174827 0.163064 -0.009383201 -0.1183707 0.163168 -0.009383201 -0.1156085 0.1584361 -0.009382843 -0.1141607 0.1558122 -0.009383201 -0.1197527 0.1654978 -0.009144067 -0.1050433 0.1610655 -0.009154856 -0.1234558 0.1557021 -0.003532886 -0.1243593 0.1555306 -0.00292313 -0.121758 0.1506716 -0.003078103 -0.09877002 0.1631764 -0.00369656 -0.1020733 0.1680448 -0.003535807 -0.09847307 0.1640464 -0.002898871 -0.1011309 0.168649 -0.002862632 -0.1193531 0.1656241 -0.005492925 -0.1186696 0.1643888 -0.006522655 -0.1178563 0.1633051 -0.006521224 -0.1119939 0.1682501 -0.006522059 -0.1114018 0.167032 -0.006521999 -0.112765 0.1694968 -0.005147516 -0.1070792 0.159671 -0.005285382 -0.1077705 0.1609399 -0.006521821 -0.1085247 0.1620496 -0.006519377 -0.1144577 0.1570857 -0.006522536 -0.1150314 0.158301 -0.00652337 -0.1137015 0.1558465 -0.005293011 -0.1133204 0.157763 -0.005579829 -0.11166 0.1550219 -0.005460023 -0.1076567 0.1503961 -0.005790472 -0.1096441 0.1519438 -0.005481958 -0.1188052 0.1749614 -0.005772531 -0.1168006 0.1733895 -0.005485475 -0.1210491 0.1737337 -0.005771994 -0.1207166 0.1711202 -0.005482196 -0.1147447 0.1679207 -0.005811572 -0.1170292 0.166635 -0.005806207 -0.109408 0.1586852 -0.005805492 -0.1116673 0.1574872 -0.005806446 -0.1149909 0.1679648 -0.009245157 -0.1185821 0.1742496 -0.008909344 -0.1207053 0.1733821 -0.009333729 -0.1169715 0.1669417 -0.009376645 -0.1192617 0.174391 -0.009323298 -0.1076876 0.1508316 -0.009332954 -0.1056871 0.1518611 -0.009322226 -0.1114096 0.1572668 -0.009291946 -0.1095234 0.1584607 -0.009349822 -0.120799 0.1663513 -0.004900813 -0.1074323 -0.1759613 -0.00305438 -0.1082149 -0.1761175 -0.003541588 -0.1181023 -0.1752853 -0.005244493 -0.1200771 -0.1782912 -0.007423043 -0.1179301 -0.1753792 -0.009404718 -0.1105173 -0.1753039 -0.005059778 -0.1093341 -0.1739852 -0.005034148 -0.1153571 -0.1717094 -0.004977524 -0.115979 -0.1685034 -0.005803227 -0.1175544 -0.1712659 -0.005497395 -0.1153872 -0.1687073 -0.005283296 -0.124667 -0.1715647 -0.005245447 -0.1247553 -0.1712876 -0.009413123 -0.1258099 -0.1730528 -0.009082615 -0.1274712 -0.1740884 -0.007867276 -0.121494 -0.1688852 -0.00526154 -0.1216893 -0.1688945 -0.005803227 -0.1201043 -0.1660756 -0.005579769 -0.1254129 -0.1744939 -0.005943536 -0.1232399 -0.1720798 -0.005803227 -0.1069166 -0.155896 -0.005207538 -0.10667 -0.1558905 -0.009438157 -0.105219 -0.1527073 -0.007590413 -0.1103488 -0.158759 -0.005116641 -0.1117412 -0.1611635 -0.005803227 -0.1112374 -0.1615694 -0.005248725 -0.109928 -0.1585223 -0.005803227 -0.1215482 -0.1521262 -0.004812955 -0.1220459 -0.1535757 -0.005311191 -0.1162897 -0.1569083 -0.005283355 -0.1135134 -0.152132 -0.005247831 -0.1115701 -0.1491321 -0.007391929 -0.1136591 -0.1519908 -0.009385049 -0.1257177 -0.1632113 -0.006932854 -0.1280845 -0.1634828 -0.005012094 -0.1248437 -0.1648455 -0.008504509 -0.1193413 -0.1553153 -0.008504509 -0.1211529 -0.1553061 -0.006929457 -0.1224343 -0.1536962 -0.005022943 -0.1239877 -0.1653096 -0.009154856 -0.1184174 -0.1558768 -0.009204745 -0.1231139 -0.166092 -0.009144067 -0.1120373 -0.1788543 -0.004972934 -0.1154882 -0.178733 -0.008015036 -0.1164149 -0.1799291 -0.00804162 -0.114136 -0.173423 -0.009108662 -0.1295911 -0.1721104 -0.008044779 -0.1169463 -0.1777725 -0.009252369 -0.1235104 -0.1717432 -0.009383201 -0.1218885 -0.1689479 -0.009144067 -0.1252697 -0.1672992 -0.009285926 -0.1270517 -0.1722245 -0.009299695 -0.1173061 -0.1715934 -0.009144067 -0.1190348 -0.1742418 -0.009313762 -0.1144093 -0.1476354 -0.007994353 -0.1027702 -0.1564177 -0.008124589 -0.1020439 -0.1549789 -0.008062541 -0.1063733 -0.1601166 -0.009310185 -0.103192 -0.162141 -0.005619466 -0.1008381 -0.1594045 -0.004952371 -0.1285017 -0.1641648 -0.004720985 -0.1307675 -0.1680541 -0.004983901 -0.1283909 -0.1652981 -0.005658805 -0.1149502 -0.149643 -0.009213626 -0.1043591 -0.155589 -0.009303271 -0.1081069 -0.1556738 -0.009383201 -0.1098201 -0.1581277 -0.009144067 -0.1141862 -0.1556071 -0.009383201 -0.1176872 -0.1536775 -0.00906217 -0.1127043 -0.1530194 -0.009383201 -0.1047176 -0.1695114 -0.001875042 -0.1046602 -0.1690878 -0.003532826 -0.1024616 -0.1646078 -0.001646816 -0.1011779 -0.164068 -0.003622591 -0.1012762 -0.1636404 -0.001967787 -0.1037449 -0.1697533 -0.002839267 -0.1011359 -0.1653335 -0.001879155 -0.1230659 -0.1511241 -0.002082049 -0.123107 -0.1516603 -0.003532886 -0.1260382 -0.1567383 -0.003537356 -0.1260485 -0.1569742 -0.001664698 -0.1243442 -0.1517134 -0.003078103 -0.1270193 -0.1563274 -0.002983689 -0.1245651 -0.1518463 -0.001884222 -0.1038721 -0.1705768 -0.001644492 -0.1071406 -0.1762441 -0.001650869 -0.1061934 -0.1773798 -0.001636207 -0.09946179 -0.1657648 -0.001651346 -0.1038414 -0.1648292 -0.001635015 -0.108846 -0.1736193 -0.001661419 -0.1055517 -0.1704219 -0.001650393 -0.1103779 -0.1718953 -0.002839565 -0.1021876 -0.1620665 -0.002165019 -0.09969109 -0.1635696 -0.002122223 -0.1105044 -0.1764109 -0.002279222 -0.1227617 -0.1537526 -0.00169593 -0.122415 -0.1555051 -0.001652896 -0.1276565 -0.1566956 -0.001645267 -0.1256284 -0.1503295 -0.001655042 -0.1317896 -0.1609956 -0.001646816 -0.130676 -0.1619313 -0.001646816 -0.1267681 -0.1582046 -0.001653254 -0.1278757 -0.1627392 -0.001672744 -0.1230916 -0.1495047 -0.002445697 -0.1211836 -0.151114 -0.002172887 -0.1296578 -0.1658963 -0.002615869 -0.1319479 -0.163862 -0.00212115 -0.1214097 -0.155346 -0.002508759 -0.1255456 -0.1630286 -0.003017842 -0.1270471 -0.1729047 -0.01138317 -0.1134637 -0.1493774 -0.01138317 -0.1181535 -0.1780394 -0.01138317 -0.1045701 -0.1545122 -0.01138317 -0.1280731 -0.1734378 -0.01072752 -0.1181393 -0.1791693 -0.01076036 -0.1295586 -0.171748 -0.010311 -0.1322152 -0.1619622 -0.00297749 -0.1255261 -0.1503742 -0.002959251 -0.1193703 -0.1484882 -0.00507456 -0.1161535 -0.1478621 -0.009816408 -0.1137629 -0.1480899 -0.01076394 -0.1035255 -0.1540006 -0.01074546 -0.1020586 -0.155669 -0.010311 -0.09940087 -0.1654489 -0.002958655 -0.1060955 -0.1770465 -0.002947211 -0.1148025 -0.1793845 -0.009298741 -0.1219406 -0.1601681 -0.01098895 -0.1141282 -0.1484792 -0.01127684 -0.1281588 -0.1727843 -0.01127725 -0.1163225 -0.1484149 -0.01049685 -0.1181697 -0.1509185 -0.01010066 -0.1278737 -0.1681882 -0.01046538 -0.1295372 -0.1700658 -0.009878337 -0.12185 -0.1526233 -0.007815361 -0.1281762 -0.1632632 -0.00765556 -0.1255797 -0.150895 -0.003720164 -0.1317513 -0.1618089 -0.003832399 -0.1283812 -0.166278 -0.008528411 -0.109249 -0.1742125 -0.007656693 -0.1034007 -0.1640855 -0.007653295 -0.09983241 -0.1657358 -0.003739237 -0.1020931 -0.1572951 -0.009917497 -0.1037777 -0.1592344 -0.01045495 -0.1154316 -0.179049 -0.01058685 -0.1061834 -0.1765627 -0.003826081 -0.1134997 -0.1762704 -0.01031088 -0.1045269 -0.1586279 -0.01075273 -0.1034666 -0.1546307 -0.01127851 -0.1139024 -0.1746761 -0.01096576 -0.1174888 -0.178938 -0.01127678 -0.10589 -0.1641665 -0.006943881 -0.1038455 -0.1644793 -0.005014836 -0.1042752 -0.1635819 -0.005492925 -0.1067736 -0.1625713 -0.008504509 -0.1122759 -0.1721016 -0.008504509 -0.1104339 -0.1720437 -0.006936967 -0.1033647 -0.1632547 -0.004817426 -0.1207231 -0.1520171 -0.005658805 -0.1186597 -0.1515982 -0.00915414 -0.1180715 -0.1519284 -0.01008164 -0.1192426 -0.1550127 -0.01024711 -0.1269304 -0.1676902 -0.009768724 -0.1210899 -0.1552898 -0.008777797 -0.1256389 -0.1633017 -0.008833348 -0.1041598 -0.1594039 -0.009824037 -0.1129158 -0.1758029 -0.009135544 -0.1135206 -0.1755106 -0.009952127 -0.1137482 -0.1748065 -0.01011186 -0.1105263 -0.1721162 -0.008780717 -0.1059734 -0.1641209 -0.008903026 -0.1094077 -0.167404 -0.0100311 -0.1060418 -0.1643013 -0.002982139 -0.1148704 -0.1705629 -0.009383201 -0.1142203 -0.1712267 -0.009144067 -0.1136364 -0.1682662 -0.009381949 -0.1078617 -0.1619773 -0.009286165 -0.1108334 -0.1633628 -0.009379267 -0.1096196 -0.1609688 -0.009144067 -0.1181058 -0.1592183 -0.009382784 -0.1206883 -0.1638197 -0.009383916 -0.1219977 -0.1664481 -0.009144067 -0.1165305 -0.1569787 -0.009144067 -0.1131057 -0.1715924 -0.009154856 -0.1269568 -0.1583284 -0.003532886 -0.1298851 -0.1634002 -0.003541648 -0.1278673 -0.1577776 -0.002918422 -0.1305558 -0.162327 -0.002914071 -0.1055797 -0.1706808 -0.003537893 -0.1046436 -0.1711657 -0.003044784 -0.1160534 -0.1586452 -0.00552392 -0.1170727 -0.1581068 -0.006523013 -0.1176207 -0.1593528 -0.006524205 -0.1103283 -0.1619944 -0.006522953 -0.111116 -0.1631099 -0.006524741 -0.1096806 -0.1607465 -0.005465865 -0.1140632 -0.1561505 -0.005500316 -0.1153308 -0.1705267 -0.005286872 -0.1145781 -0.1692933 -0.006521821 -0.1139912 -0.1680852 -0.006520688 -0.1212853 -0.1654165 -0.006523072 -0.1204864 -0.1643291 -0.006524026 -0.1219539 -0.166703 -0.005293309 -0.1214808 -0.1760214 -0.005775451 -0.1193779 -0.1744262 -0.005475997 -0.1079525 -0.1527263 -0.005772531 -0.1083092 -0.1552498 -0.005482017 -0.1101387 -0.151399 -0.005775213 -0.112236 -0.1529932 -0.005477547 -0.1120197 -0.1597631 -0.005811572 -0.1142754 -0.1584274 -0.00580573 -0.1236361 -0.1746402 -0.005803108 -0.1173495 -0.1690027 -0.005805492 -0.1195166 -0.1676443 -0.005802154 -0.112105 -0.1595142 -0.009358406 -0.1082906 -0.1529203 -0.009353995 -0.1102732 -0.1518709 -0.009343504 -0.1139913 -0.1583293 -0.009300768 -0.1225134 -0.175093 -0.009365379 -0.1231547 -0.1741358 -0.008948385 -0.1195792 -0.1679793 -0.009296119 -0.1176036 -0.1690155 -0.009360909 -0.1211683 -0.1752913 -0.008909344 0.107789 0.1866528 -0.009384393 0.1080119 0.186779 -0.005247831 0.1084978 0.1886507 -0.008998632 0.109433 0.1900824 -0.007423102 0.1070968 0.1797316 -0.005803227 0.1081693 0.1827256 -0.005492925 0.1062557 0.1815367 -0.005315899 0.1151565 0.1842144 -0.005244612 0.1152581 0.1840035 -0.009360253 0.1161044 0.1863341 -0.00822556 0.1124438 0.1810247 -0.005219995 0.1126524 0.1811083 -0.005803227 0.111581 0.178057 -0.005579769 0.1003413 0.1657193 -0.005258023 0.1002557 0.1659542 -0.009421765 0.09953498 0.1640408 -0.009082555 0.09834688 0.1626262 -0.007693469 0.09571874 0.1733312 -0.005038797 0.1005933 0.170751 -0.004912137 0.1030696 0.1688554 -0.005295634 0.104198 0.1717672 -0.005803227 0.1036314 0.1720795 -0.005248725 0.102871 0.1688514 -0.005803227 0.1158878 0.1660364 -0.005316734 0.1096053 0.1669044 -0.005004167 0.1077349 0.1633076 -0.009397983 0.1074727 0.1631669 -0.005189239 0.1070417 0.1613607 -0.008951187 0.1061256 0.1598842 -0.007436335 0.1061125 0.1638265 -0.005512297 0.1043221 0.1618952 -0.005802631 0.1196856 0.1763216 -0.005015671 0.1198526 0.1769118 -0.00488007 0.1176266 0.1762946 -0.006944239 0.1163812 0.1779637 -0.008338689 0.1124467 0.1671534 -0.00833863 0.1144821 0.1676632 -0.006929516 0.1160076 0.1662405 -0.005015492 0.1155385 0.177977 -0.009154856 0.111691 0.1677333 -0.009219527 0.1144566 0.1783611 -0.009383201 0.1014722 0.1892654 -0.005017459 0.1002866 0.1855478 -0.004806816 0.1058391 0.1889018 -0.009165525 0.1055615 0.1911086 -0.008037328 0.1044276 0.1842564 -0.009108662 0.1180467 0.1870086 -0.007905244 0.1199828 0.1854521 -0.00798887 0.1139512 0.1842299 -0.009383201 0.1129248 0.1814302 -0.009383201 0.1162985 0.1799196 -0.009068667 0.1177106 0.1849898 -0.009178757 0.1078673 0.1830052 -0.009144067 0.1089628 0.1860455 -0.009383201 0.1100443 0.1588827 -0.007915318 0.09725755 0.1657118 -0.009032428 0.09942251 0.1698569 -0.009312808 0.09589815 0.1714037 -0.005492925 0.09378564 0.1681073 -0.005024552 0.09513449 0.1716818 -0.005050241 0.09541863 0.1646396 -0.007691919 0.120166 0.1785174 -0.005314171 0.121762 0.1818017 -0.004984259 0.1196252 0.178556 -0.005492925 0.1018952 0.1658669 -0.009144067 0.102684 0.1687642 -0.009144067 0.107336 0.1668052 -0.009144067 0.1108748 0.1656951 -0.009313285 0.1065606 0.1639142 -0.009383201 0.1097031 0.1611629 -0.009174823 0.09600883 0.178484 -0.001652181 0.0958485 0.1783415 -0.003532767 0.09388983 0.172232 -0.001742959 0.09325498 0.1726921 -0.003644466 0.09488528 0.1787505 -0.003078103 0.09480506 0.1791651 -0.001659095 0.1172543 0.1624499 -0.002357721 0.1170436 0.1643894 -0.003540515 0.1194943 0.1706785 -0.001680195 0.1192516 0.1698243 -0.00376749 0.1180408 0.1645154 -0.003229439 0.1200487 0.1695705 -0.003039717 0.1183659 0.1644799 -0.00166136 0.09568524 0.1861959 -0.001647353 0.09155243 0.1748764 -0.001646816 0.09621113 0.1796899 -0.001647174 0.09589701 0.1739379 -0.001634359 0.09923315 0.1834496 -0.00164932 0.09849309 0.1846252 -0.001646876 0.1001001 0.186259 -0.001991093 0.09171652 0.1724452 -0.001927435 0.09447205 0.1702885 -0.002779662 0.09743452 0.1873654 -0.002092599 0.1156929 0.1680278 -0.001646816 0.1162816 0.1663541 -0.00164777 0.1203857 0.1708751 -0.001645445 0.1197409 0.1635044 -0.001645326 0.1239709 0.1750833 -0.001646816 0.1227074 0.175801 -0.001647651 0.1198011 0.1761169 -0.001664876 0.1210621 0.1764118 -0.001646816 0.1209906 0.1793349 -0.002427756 0.1150678 0.16315 -0.002452909 0.1220293 0.177595 -0.002067089 0.1237801 0.1775871 -0.001947641 0.1148304 0.1680288 -0.002507567 0.1174697 0.1760165 -0.003014862 0.09967869 0.1841976 -0.005026519 0.1172326 0.185988 -0.01138317 0.1079409 0.1604594 -0.01138317 0.1075825 0.1895003 -0.01138317 0.0982908 0.1639717 -0.01138317 0.1079232 0.1904364 -0.01047033 0.1059321 0.1907196 -0.01098877 0.1047282 0.1905518 -0.009864747 0.1181503 0.1866912 -0.01072764 0.1242223 0.176109 -0.00297743 0.1204179 0.1842836 -0.009297549 0.1196452 0.1635348 -0.00296092 0.1140498 0.1606937 -0.005018651 0.1108532 0.1594343 -0.009816348 0.1084592 0.1592433 -0.01076382 0.09735083 0.1632866 -0.01074534 0.09561669 0.1646748 -0.01031112 0.09130007 0.1738467 -0.002957224 0.09587943 0.1864283 -0.002946853 0.111599 0.1648205 -0.01098895 0.1183483 0.1860624 -0.01127725 0.1172316 0.1802957 -0.01098895 0.1087513 0.1596901 -0.01127684 0.1116992 0.1620491 -0.0105108 0.1183595 0.1812713 -0.01067799 0.1130143 0.163354 -0.008956193 0.1116821 0.160359 -0.009904265 0.1161188 0.1659738 -0.007655382 0.1196094 0.1640578 -0.003720104 0.1202859 0.1779064 -0.007821321 0.1237921 0.1758775 -0.00383228 0.1198825 0.1843153 -0.01038819 0.09945243 0.1841173 -0.007655858 0.09556901 0.1734481 -0.007655322 0.09172749 0.1740905 -0.003825843 0.09535896 0.1663035 -0.009901642 0.09560698 0.1715589 -0.008099377 0.09711402 0.1686459 -0.01062852 0.1038583 0.1896089 -0.009917497 0.09593862 0.1859137 -0.003739058 0.1032021 0.1870688 -0.0101006 0.09753352 0.1680173 -0.01075273 0.09718352 0.1638969 -0.01127851 0.1039799 0.1854498 -0.01096576 0.106779 0.1903894 -0.01126766 0.09906136 0.1722911 -0.008504509 0.09790754 0.1736776 -0.00706458 0.1030768 0.1828063 -0.00833863 0.1010501 0.1823406 -0.006945729 0.1153158 0.1643465 -0.005073964 0.114551 0.1646146 -0.005492925 0.1120948 0.1653763 -0.01013261 0.1122675 0.1636312 -0.009804546 0.1180047 0.1808295 -0.009780228 0.1143844 0.1676929 -0.009022951 0.1175794 0.1763442 -0.008826434 0.09705871 0.1688208 -0.00981301 0.1028201 0.1864014 -0.009138107 0.103459 0.1862055 -0.009952127 0.1038054 0.1855515 -0.01011186 0.101116 0.1823864 -0.008789122 0.09799784 0.1737186 -0.008885443 0.1008163 0.1775078 -0.0100311 0.1009878 0.1821097 -0.002874314 0.09803736 0.1738513 -0.002977371 0.1058821 0.1814819 -0.009144067 0.1037907 0.1822509 -0.009198307 0.1047294 0.1790139 -0.009388089 0.1009814 0.1713638 -0.009144067 0.1029993 0.1740256 -0.00938338 0.1019077 0.1712926 -0.009383201 0.1107657 0.1709662 -0.009378314 0.112712 0.1762321 -0.009394824 0.1136156 0.1786671 -0.009383201 0.1119769 0.1763548 -0.009146273 0.1098759 0.1683923 -0.009383201 0.09998482 0.1719827 -0.009154856 0.1198278 0.1713097 -0.003547132 0.1216824 0.1771334 -0.003532886 0.1207066 0.1711843 -0.002913951 0.122437 0.1761516 -0.003078103 0.09792602 0.1856239 -0.003627479 0.09607368 0.1802074 -0.00369656 0.09539926 0.1803925 -0.002796769 0.1088312 0.1700755 -0.005543291 0.1094157 0.168348 -0.005285382 0.1099474 0.1696981 -0.006522536 0.1103026 0.1710051 -0.006524205 0.102694 0.1723325 -0.006522059 0.1032737 0.1735718 -0.006523072 0.1022446 0.1709977 -0.005458176 0.1073549 0.1672336 -0.00549215 0.1055476 0.1802836 -0.006522715 0.1052253 0.1789617 -0.006523907 0.112831 0.177621 -0.006522536 0.1122752 0.1763978 -0.006525158 0.1132944 0.1789964 -0.00529474 0.1153552 0.1872593 -0.005927205 0.1136749 0.1846107 -0.005487143 0.1112095 0.1880908 -0.005775451 0.1094175 0.1861531 -0.00547713 0.1019438 0.1628295 -0.005789577 0.1018455 0.1653422 -0.005477547 0.1047154 0.1704366 -0.005811572 0.1071688 0.1695128 -0.00580573 0.1135713 0.1871042 -0.005808413 0.1083598 0.1804612 -0.005805492 0.1107298 0.1795005 -0.005806446 0.1048363 0.1702147 -0.009293913 0.1022295 0.16305 -0.009340107 0.1043635 0.1623571 -0.009316265 0.1068966 0.1693572 -0.009367465 0.113273 0.1868305 -0.0093472 0.1111956 0.187698 -0.009322226 0.1107242 0.1798439 -0.009284615 0.1086037 0.1805163 -0.009334981 0.12515 -0.1790686 -0.001675367 0.1241601 -0.1798586 -0.003576934 0.1174422 -0.1865272 -0.009388148 0.1173438 -0.1868073 -0.005216658 0.1182975 -0.1889035 -0.008324623 0.1184417 -0.19018 -0.00741142 0.1158564 -0.18716 -0.005520761 0.1157395 -0.1898219 -0.005772233 0.1135155 -0.1807718 -0.005803227 0.1146079 -0.1837732 -0.005803227 0.1138265 -0.1804582 -0.005276918 0.1146769 -0.1836637 -0.005291402 0.1023515 -0.1879489 -0.005068004 0.1023172 -0.1866926 -0.004935979 0.1102208 -0.1894087 -0.005230784 0.1100078 -0.1892907 -0.009383201 0.1106579 -0.1911627 -0.009102165 0.1102758 -0.1932172 -0.007914721 0.1096875 -0.1656984 -0.005270898 0.1099032 -0.1658501 -0.009385466 0.10821 -0.1624205 -0.007605135 0.1096577 -0.1698879 -0.005227923 0.1106168 -0.1728076 -0.005803227 0.1112406 -0.1727052 -0.005278348 0.1095244 -0.1698064 -0.005803227 0.1024695 -0.1685996 -0.009384393 0.1026218 -0.1684369 -0.005414724 0.1019144 -0.1663281 -0.005383551 0.1015779 -0.164916 -0.007433295 0.1040467 -0.1679555 -0.005512475 0.104176 -0.165325 -0.005802631 0.1017674 -0.1864991 -0.005027174 0.103241 -0.1848862 -0.006974875 0.1056619 -0.1849047 -0.009067058 0.1013323 -0.1745753 -0.00833863 0.100143 -0.1763823 -0.006825864 0.09792977 -0.1759809 -0.005053818 0.1021751 -0.1745621 -0.009154856 0.1069967 -0.1844529 -0.009383201 0.1031715 -0.1739433 -0.009144067 0.1239772 -0.1844075 -0.004981577 0.1223368 -0.1809165 -0.00496602 0.1220114 -0.1884275 -0.007986724 0.1203747 -0.1869599 -0.009136736 0.1183661 -0.1826412 -0.009259462 0.1072356 -0.1934488 -0.007760047 0.1111562 -0.1886237 -0.009383201 0.1101428 -0.1858192 -0.009383201 0.106965 -0.1869339 -0.009312272 0.1087307 -0.191575 -0.009291946 0.115115 -0.1840096 -0.009383201 0.1158183 -0.1866722 -0.009144067 0.09823465 -0.1680387 -0.008056342 0.0987187 -0.1660447 -0.007882118 0.1109626 -0.16161 -0.007793724 0.1112382 -0.1633977 -0.00919044 0.1141064 -0.1677553 -0.008503496 0.1178888 -0.1677882 -0.004933655 0.1162384 -0.1633066 -0.004983067 0.1036587 -0.1918076 -0.004986822 0.1030818 -0.1882196 -0.005658805 0.1058793 -0.1870679 -0.008338689 0.09991222 -0.1676523 -0.009252309 0.1086038 -0.1666257 -0.009313762 0.1097608 -0.1692993 -0.009383201 0.1127843 -0.1681966 -0.009318292 0.1048742 -0.1713436 -0.009144067 0.101435 -0.1725962 -0.009108662 0.1037591 -0.1683104 -0.009383201 0.1214799 -0.1735237 -0.001649558 0.1215589 -0.1726261 -0.003541588 0.1194548 -0.1678276 -0.001883745 0.1194153 -0.1668187 -0.003485023 0.1221721 -0.1724222 -0.002715647 0.1204406 -0.1672286 -0.003078103 0.1203877 -0.1666331 -0.001888096 0.0957657 -0.1744651 -0.001963734 0.09603118 -0.1754057 -0.003532886 0.098037 -0.1809153 -0.003537356 0.09820193 -0.181066 -0.00166732 0.09527659 -0.1763876 -0.003078103 0.09704333 -0.1812652 -0.003026306 0.0950933 -0.1763573 -0.001649558 0.1229231 -0.1735553 -0.0016492 0.1262373 -0.1779048 -0.001646816 0.1223024 -0.167061 -0.001646816 0.118424 -0.1690722 -0.001626491 0.1220497 -0.1785483 -0.001648247 0.1197383 -0.17868 -0.002964556 0.1173411 -0.165883 -0.002340734 0.1205074 -0.1652479 -0.001986086 0.125952 -0.1801628 -0.001987695 0.09785747 -0.1764484 -0.001698017 0.09942114 -0.1773471 -0.001652896 0.09761422 -0.1825614 -0.001643776 0.093306 -0.176162 -0.001630902 0.09760129 -0.1880576 -0.001646816 0.09923356 -0.1884348 -0.001646995 0.09873086 -0.1823882 -0.001645445 0.09654378 -0.1727903 -0.00279808 0.1025522 -0.1892841 -0.002366662 0.09960627 -0.1899729 -0.002100348 0.1001459 -0.1764617 -0.003031075 0.1031814 -0.1845935 -0.003014922 0.1218881 -0.1789227 -0.005023956 0.1097726 -0.1920798 -0.01138317 0.100481 -0.1665511 -0.01138317 0.1194227 -0.1885674 -0.01138317 0.110131 -0.1630387 -0.01138317 0.1095217 -0.1932083 -0.01072752 0.1202976 -0.1892827 -0.01076036 0.09806811 -0.189005 -0.00297749 0.1062369 -0.1928217 -0.009297549 0.09349179 -0.1764305 -0.00296092 0.09600061 -0.170505 -0.005117177 0.09795242 -0.1669742 -0.01065999 0.09925764 -0.1659704 -0.01077175 0.110663 -0.1618183 -0.01073783 0.112998 -0.1619864 -0.009819746 0.1218338 -0.1661098 -0.002957224 0.1264178 -0.178704 -0.002930641 0.100482 -0.1722434 -0.01098895 0.1089659 -0.1928539 -0.01127725 0.1061701 -0.1880286 -0.01096582 0.09936577 -0.1664828 -0.01127684 0.09845179 -0.1710978 -0.01001781 0.09755396 -0.1688725 -0.009909689 0.1069214 -0.1926044 -0.01059013 0.1054827 -0.1894842 -0.01031231 0.09852606 -0.1719025 -0.009004056 0.0938555 -0.176808 -0.003720223 0.09769481 -0.1758502 -0.00765556 0.1017641 -0.1870303 -0.00765556 0.09824943 -0.1885513 -0.003832757 0.1222147 -0.1792862 -0.007656753 0.1181926 -0.1682302 -0.007655143 0.1216632 -0.1665714 -0.003825843 0.1132365 -0.1626169 -0.01038801 0.1140217 -0.166063 -0.01066595 0.1219452 -0.1871338 -0.01058745 0.126037 -0.1783353 -0.003738999 0.121059 -0.1838653 -0.010311 0.1133117 -0.1656512 -0.01075273 0.1109313 -0.1622698 -0.01127851 0.1195788 -0.1831489 -0.01096576 0.1205384 -0.1886358 -0.01127678 0.1181194 -0.1685598 -0.005041301 0.1148884 -0.169907 -0.008504509 0.1166746 -0.1702155 -0.006928324 0.1196009 -0.1783173 -0.006841719 0.1185715 -0.1805432 -0.00833863 0.1216128 -0.179632 -0.005276978 0.0975815 -0.1742023 -0.004961133 0.1010668 -0.1745421 -0.01025325 0.1059851 -0.1881492 -0.01010572 0.09947329 -0.1717208 -0.01008164 0.1057815 -0.1886303 -0.00971198 0.1026554 -0.1865176 -0.008167922 0.1001999 -0.1762712 -0.008879721 0.1030911 -0.184049 -0.008904159 0.115369 -0.1662537 -0.008937954 0.1142788 -0.1663195 -0.009853601 0.1210762 -0.1831175 -0.009135603 0.1204636 -0.1833928 -0.009952127 0.1197779 -0.1831145 -0.01011186 0.1197879 -0.1789172 -0.008780717 0.1166192 -0.1702607 -0.008855342 0.1168973 -0.1750313 -0.0100311 0.1166726 -0.1704535 -0.00294888 0.1155712 -0.181332 -0.009144067 0.1167322 -0.1811752 -0.009144067 0.1148648 -0.1787125 -0.00938344 0.1128216 -0.170431 -0.009144067 0.1129027 -0.1735255 -0.009380459 0.1118314 -0.1710572 -0.009144067 0.1050621 -0.1763199 -0.009382367 0.1069619 -0.1817765 -0.009386122 0.1075222 -0.1810872 -0.009383141 0.1080724 -0.1840614 -0.009144067 0.1040979 -0.1738719 -0.009383201 0.1177288 -0.1805564 -0.009154856 0.1139827 -0.1702644 -0.009154856 0.09826588 -0.1827912 -0.003699719 0.1006723 -0.188157 -0.003532886 0.09766423 -0.1829476 -0.003078103 0.09946274 -0.1878885 -0.003078281 0.1220676 -0.174123 -0.00376749 0.1245524 -0.1789683 -0.003229439 0.1225769 -0.1736165 -0.00292623 0.10598 -0.1744899 -0.005543291 0.1044252 -0.1735242 -0.005148231 0.1048848 -0.1749177 -0.006522595 0.105431 -0.1761538 -0.006524682 0.1121612 -0.1722595 -0.006522893 0.1125095 -0.1735824 -0.00652498 0.1116075 -0.1709268 -0.005292832 0.117066 -0.1671394 -0.005276978 0.1052843 -0.1713638 -0.00549221 0.1154814 -0.1815765 -0.005283892 0.1150572 -0.180199 -0.006522715 0.1144548 -0.1789858 -0.006521165 0.1077349 -0.1828562 -0.006523013 0.1074125 -0.1815445 -0.00652337 0.1082958 -0.1841915 -0.005293369 0.1089761 -0.1823793 -0.005565643 0.112033 -0.191851 -0.005941212 0.1104058 -0.1852922 -0.005513131 0.1116058 -0.1886578 -0.005721032 0.1065982 -0.16451 -0.005781471 0.1082948 -0.166453 -0.005705952 0.1093661 -0.1721218 -0.005803227 0.106892 -0.1729902 -0.00580573 0.1132947 -0.1905824 -0.005803108 0.113017 -0.1821426 -0.005805969 0.1105835 -0.1829297 -0.005801975 0.1091299 -0.1720286 -0.009293973 0.1065215 -0.1648645 -0.009340107 0.1044414 -0.1657053 -0.009316265 0.1070005 -0.1726962 -0.009367465 0.1133471 -0.1901814 -0.009339988 0.1154964 -0.1895092 -0.009322226 0.1107977 -0.1831747 -0.009220123 0.1128638 -0.1823413 -0.009344816 -0.05983811 -0.01590317 -0.03313004 -0.05932134 -0.01590317 -0.03310072 -0.05884349 -0.0149393 -0.03330737 -0.05854594 0.01409637 -0.03428339 -0.05874723 0.01365894 -0.03475248 -0.05921185 0.01409637 -0.03502947 -0.05857527 0.01409637 -0.03376662 -0.05857527 -0.01090323 -0.03376662 -0.05854594 -0.01090323 -0.03428339 -0.05972862 0.01409637 -0.03505879 -0.05849373 -0.03087568 -0.03402549 -0.06019085 0.01409637 -0.0348258 -0.06046235 0.02908384 -0.03440946 -0.05877894 -0.03090298 -0.03474563 -0.05921185 -0.01090323 -0.03502947 -0.05972862 -0.01090323 -0.03505879 -0.06047469 0.009096443 -0.03439289 -0.06050401 0.01409637 -0.03387612 -0.05951857 -0.03090214 -0.03510671 -0.06030255 0.01364225 -0.03340685 -0.06019085 -0.03090298 -0.0348258 -0.06047469 -0.01090323 -0.03439289 -0.05983811 0.01409637 -0.03313004 -0.06050401 -0.01590317 -0.03387612 -0.05932134 0.01409637 -0.03310072 -0.06047469 -0.03090298 -0.03439289 -0.06027102 -0.01590317 -0.03341388 -0.0588591 0.01409637 -0.03333371 0.1203696 0.2177729 -0.005505383 0.1194111 0.2283868 -0.005505383 0.1188879 0.2182332 -0.005505383 0.1300315 0.2272163 -0.005505383 0.1312314 0.2168606 -0.005505383 0.1312589 0.2268543 -0.005505383 0.132466 0.2165957 -0.005505383 0.1375657 0.2169819 -0.005505383 0.1384491 0.2253869 -0.005505383 0.1321892 0.2281512 -0.005505383 0.1361364 0.2305815 -0.005505383 0.1311361 0.2292906 -0.005505383 0.1319108 0.2343863 -0.005505383 0.1296824 0.2286328 -0.005505383 0.1265029 0.2361434 -0.005505383 0.1197575 0.2298761 -0.005505383 0.1302893 0.2154211 -0.005505383 0.1202126 0.2161849 -0.005505383 0.1208478 0.2095386 -0.005505383 0.1290963 0.209325 -0.005505383 0.1319109 0.214321 -0.005505859 0.1190108 0.215797 -0.005505383 0.1159235 0.2123817 -0.005505383 0.117958 0.2169365 -0.005505383 0.111399 0.2225438 -0.005505383 0.1174339 0.2286874 -0.005505383 0.1160218 0.2329834 -0.005505383 0.1180307 0.2306599 -0.005505561 0.1210507 0.2357626 -0.005505383 0.1125812 0.2169819 -0.005505383 0.1125812 0.2281057 -0.005505383 0.1328538 0.215394 -0.005505383 0.1341251 0.2121042 -0.005505383 0.1218137 0.2360966 -0.006005346 0.115637 0.2326369 -0.006005346 0.1123476 0.2279261 -0.006005346 0.1112586 0.2222849 -0.006005346 0.1125583 0.2166882 -0.006005346 0.1160219 0.2121042 -0.006005346 0.1225389 0.2088369 -0.006005346 0.1295887 0.2094851 -0.006005346 0.1345099 0.2124507 -0.006005346 0.1377993 0.2171613 -0.006005346 0.1388928 0.2243691 -0.006005346 0.1360977 0.2308737 -0.006005346 0.1304024 0.2354243 -0.006005346 0.1239106 0.2351394 -0.006005346 0.1185606 0.2333874 -0.006005346 0.1145008 0.2294877 -0.006005346 0.1123018 0.2229085 -0.006005346 0.1142298 0.2160311 -0.006005346 0.1181296 0.2119709 -0.006005346 0.1234045 0.2100052 -0.006005346 0.1290103 0.2105228 -0.006005346 0.1338361 0.2134214 -0.006005346 0.1369264 0.2181265 -0.006005346 0.1376062 0.2250302 -0.006005346 0.1341962 0.2313061 -0.006005346 0.1294908 0.2343966 -0.006005346 0.1206563 0.2343966 -0.007005333 0.1262364 0.2351394 -0.007005333 0.1159511 0.2313064 -0.007005333 0.1130526 0.2264805 -0.007005333 0.1127032 0.2193463 -0.007005333 0.1163113 0.2134211 -0.007005333 0.1211368 0.2105228 -0.007005333 0.1267426 0.2100052 -0.007005333 0.1320172 0.2119708 -0.007005333 0.1359173 0.216031 -0.007005333 0.1376692 0.2213809 -0.007005333 0.1364222 0.2284139 -0.007005333 0.1315861 0.2333875 -0.007005333 0.1249189 0.2246876 -0.01350528 0.1229298 0.2223891 -0.01350528 0.1236962 0.2240676 -0.01100528 0.1230653 0.2221127 -0.01100528 0.1244427 0.2205891 -0.01100528 0.1252282 0.2204 -0.01350528 0.1264508 0.2210201 -0.01100528 0.1272173 0.2226983 -0.01350528 0.1257046 0.2244985 -0.01100528 0.1270818 0.2229745 -0.01100528 0.1223585 0.2363925 -0.00740391 0.1182615 0.2345644 -0.008022129 0.1183904 0.2346374 -0.007005333 0.1140493 0.2308736 -0.007005333 0.1138989 0.2306604 -0.008031725 0.1112586 0.2228027 -0.007005333 0.1116331 0.2268335 -0.007411122 0.1112665 0.2223739 -0.008032798 0.1123476 0.2171613 -0.007005333 0.1124718 0.2168806 -0.00798583 0.1156371 0.2124506 -0.007005333 0.1157062 0.2123835 -0.008015751 0.1205582 0.2094851 -0.007005333 0.1207522 0.2094235 -0.008027672 0.1262602 0.2087775 -0.007005333 0.1265764 0.2088163 -0.008033871 0.1317566 0.2104503 -0.007005333 0.132124 0.2106715 -0.008032798 0.1360979 0.2142142 -0.007005333 0.1362788 0.2144621 -0.00798583 0.1388884 0.2222849 -0.007005333 0.1384213 0.2179744 -0.007410645 0.1387479 0.2211066 -0.008005321 0.1385967 0.2253618 -0.008027732 0.1377994 0.2279261 -0.007005333 0.1362103 0.2307093 -0.008033931 0.13451 0.2326369 -0.007005333 0.1331554 0.2336676 -0.008005321 0.1267755 0.236256 -0.007005333 0.1306043 0.2355351 -0.007462501 0.1264623 0.2362605 -0.008060693 0.1224215 0.2337337 -0.01100528 0.1250736 0.2340437 -0.01100528 0.1186307 0.2321475 -0.01101177 0.1150557 0.2283278 -0.01100951 0.1137484 0.2245408 -0.01100528 0.1135931 0.2218752 -0.01100528 0.1140568 0.2192456 -0.01100528 0.1151144 0.2167938 -0.01100528 0.1177575 0.2135857 -0.01100772 0.1211403 0.2117375 -0.01100528 0.1237385 0.2111217 -0.01100528 0.1264086 0.2111217 -0.01100528 0.1290067 0.2117375 -0.01100528 0.1334382 0.2146521 -0.01100528 0.1350327 0.2167938 -0.01100528 0.1360903 0.2192456 -0.01100528 0.1365539 0.2218752 -0.01100528 0.1361418 0.2259134 -0.01100635 0.133353 0.2306417 -0.01101154 0.117958 0.2171267 -0.01100528 0.1191807 0.2157136 -0.01100528 0.1190109 0.2182661 -0.01100528 0.1202126 0.2178782 -0.01100528 0.1204774 0.2166436 -0.01100528 0.131136 0.2268214 -0.01100528 0.1321892 0.227961 -0.01100528 0.1309663 0.2293739 -0.01100528 0.1296696 0.228444 -0.01100528 0.1182368 0.2281686 -0.01100528 0.1172931 0.2291637 -0.01100528 0.1299345 0.2272093 -0.01100528 0.1323606 0.2167527 -0.01100528 0.1307726 0.2165957 -0.01100528 0.132821 0.215344 -0.01100528 -0.1432557 0.2014257 -0.005505383 -0.1439068 0.2121362 -0.005505383 -0.1444834 0.2017876 -0.005505383 -0.1333398 0.2107707 -0.005505383 -0.1321396 0.2004151 -0.005505383 -0.1321123 0.2104088 -0.005505383 -0.1309052 0.2001501 -0.005505383 -0.1246232 0.2060982 -0.005505383 -0.1258054 0.2005363 -0.005505383 -0.1311821 0.2117056 -0.005505383 -0.1258054 0.2116601 -0.005505383 -0.1298074 0.2171535 -0.005505383 -0.1336888 0.2121871 -0.005505383 -0.1368683 0.2196978 -0.005505383 -0.1436419 0.213371 -0.005505383 -0.1329866 0.1994782 -0.005505383 -0.1428608 0.200321 -0.005505383 -0.1425234 0.193093 -0.005505383 -0.1325985 0.1982766 -0.005505383 -0.1342749 0.1928794 -0.005505383 -0.1306887 0.1983112 -0.005505383 -0.1443452 0.1992141 -0.005505383 -0.1507899 0.2005363 -0.005505383 -0.14533 0.2008509 -0.005505383 -0.1519722 0.2060982 -0.005505383 -0.1451085 0.2117484 -0.005505383 -0.1507899 0.2116601 -0.005505383 -0.1462154 0.2132328 -0.005505383 -0.1445785 0.2142176 -0.005505383 -0.1473492 0.216538 -0.005505383 -0.1423202 0.2193171 -0.005505383 -0.1474477 0.1959362 -0.005505383 -0.1322351 0.212845 -0.005505383 -0.1292461 0.1956586 -0.005505383 -0.1399998 0.2198103 -0.006005346 -0.146788 0.2171536 -0.006005346 -0.1510235 0.2114807 -0.006005346 -0.1521126 0.2058393 -0.006005346 -0.1508128 0.2002425 -0.006005346 -0.1473491 0.1956584 -0.006005346 -0.1423203 0.1928794 -0.006005346 -0.1350382 0.1925453 -0.006005346 -0.1276944 0.1970498 -0.006005346 -0.1244009 0.2050104 -0.006005346 -0.1264156 0.2133865 -0.006005346 -0.1329689 0.2189788 -0.006005346 -0.1435103 0.2177635 -0.006005346 -0.1366283 0.2186368 -0.006005346 -0.1496464 0.2119682 -0.006005346 -0.1508933 0.2049351 -0.006005346 -0.1491413 0.1995854 -0.006005346 -0.1452417 0.1955254 -0.006005346 -0.1399669 0.1935597 -0.006005346 -0.134361 0.1940772 -0.006005346 -0.1295353 0.1969756 -0.006005346 -0.1259273 0.2029008 -0.006005346 -0.1262767 0.2100349 -0.006005346 -0.1300494 0.2158561 -0.006005346 -0.139967 0.2186368 -0.007005333 -0.1452416 0.216671 -0.007005333 -0.1491413 0.2126111 -0.007005333 -0.1508933 0.2072613 -0.007005333 -0.1501506 0.2016811 -0.007005333 -0.1470601 0.1969756 -0.007005333 -0.1422343 0.1940771 -0.007005333 -0.1366285 0.1935597 -0.007005333 -0.1300497 0.1963402 -0.007005333 -0.1262767 0.2021616 -0.007005333 -0.1257591 0.2077671 -0.007005333 -0.1277249 0.2130421 -0.007005333 -0.1330851 0.2177635 -0.007005333 -0.1384523 0.208242 -0.01350528 -0.1404415 0.2059435 -0.01350528 -0.139675 0.2076219 -0.01100528 -0.1403059 0.2056671 -0.01100528 -0.1389285 0.2041435 -0.01100528 -0.1381431 0.2039545 -0.01350528 -0.1369204 0.2045745 -0.01100528 -0.1361539 0.2062528 -0.01350528 -0.1376667 0.2080529 -0.01100528 -0.1362894 0.206529 -0.01100528 -0.142413 0.2192909 -0.008015751 -0.1423202 0.2193171 -0.007005333 -0.1369009 0.2198432 -0.00798583 -0.146478 0.2175952 -0.007407784 -0.149322 0.2144278 -0.007005333 -0.1485158 0.2152987 -0.008005321 -0.1509374 0.2116604 -0.008033871 -0.1517569 0.2092236 -0.007005333 -0.1521048 0.2059285 -0.008032739 -0.1518645 0.2034794 -0.007005333 -0.1508992 0.2004349 -0.00798583 -0.1496264 0.1981877 -0.007005333 -0.1485158 0.1968978 -0.008005321 -0.1454296 0.1942638 -0.007005333 -0.1453019 0.1941887 -0.008022189 -0.1371111 0.1923319 -0.007005333 -0.1413046 0.19231 -0.007404446 -0.1367948 0.1923707 -0.008033871 -0.1316146 0.1940047 -0.007005333 -0.1312472 0.1942259 -0.008032858 -0.1257826 0.2002425 -0.007005333 -0.1276655 0.1968232 -0.007409095 -0.1256658 0.2005018 -0.007984995 -0.1244828 0.2058393 -0.007005333 -0.1246232 0.204661 -0.008005321 -0.1247665 0.2090142 -0.007962524 -0.1255719 0.2114807 -0.007005333 -0.1271609 0.2142636 -0.008033871 -0.1288612 0.2161913 -0.007005333 -0.1302158 0.217222 -0.008005321 -0.1365957 0.2198103 -0.007005333 -0.1327331 0.219066 -0.007405757 -0.1409497 0.2172881 -0.01100528 -0.1382977 0.217598 -0.01100528 -0.1434588 0.2163749 -0.01100528 -0.1456897 0.2149077 -0.01100528 -0.1483157 0.2118819 -0.01100951 -0.1496229 0.2080951 -0.01100528 -0.149778 0.2054296 -0.01100528 -0.1493145 0.2028 -0.01100528 -0.1482568 0.2003483 -0.01100528 -0.1456134 0.1971399 -0.01100772 -0.1422308 0.1952919 -0.01100528 -0.1396328 0.1946761 -0.01100528 -0.1356818 0.1948274 -0.01100546 -0.1319784 0.1964902 -0.01100528 -0.129933 0.1982066 -0.01100528 -0.1283385 0.2003483 -0.01100528 -0.127281 0.2028 -0.01100528 -0.1273133 0.2096968 -0.01100534 -0.1298463 0.2139979 -0.01100802 -0.1341977 0.2169142 -0.01100647 -0.14533 0.2003211 -0.01100528 -0.1441905 0.1992681 -0.01100528 -0.1446722 0.2017748 -0.01100528 -0.1431586 0.2014326 -0.01100528 -0.1428938 0.2001981 -0.01100528 -0.1322352 0.2103759 -0.01100528 -0.1311821 0.2115154 -0.01100528 -0.1321122 0.2128121 -0.01100528 -0.1335937 0.2123518 -0.01100528 -0.1436418 0.2125952 -0.01100528 -0.1449385 0.2116651 -0.01100528 -0.1461614 0.2130781 -0.01100528 -0.1334367 0.2107638 -0.01100528 -0.1323284 0.2004024 -0.01100528 -0.1308152 0.2000601 -0.01100528 -0.1329408 0.198637 -0.01100528 -0.131487 0.1979789 -0.01100528 -0.1305503 0.1988255 -0.01100528 -0.1439067 0.2138298 -0.01100528 -0.1451084 0.2142176 -0.01100528 -0.1430015 -0.2074313 -0.005505383 -0.1444554 -0.1969773 -0.005505383 -0.1444832 -0.2069711 -0.005505383 -0.1333395 -0.197988 -0.005505383 -0.1328861 -0.2089123 -0.005505383 -0.1321119 -0.1983498 -0.005505383 -0.1314868 -0.2083107 -0.005505383 -0.1246231 -0.2026605 -0.005505383 -0.1258053 -0.2082223 -0.005505383 -0.131182 -0.1970532 -0.005505383 -0.1258053 -0.1970985 -0.005505383 -0.1291475 -0.1924983 -0.005505383 -0.1322348 -0.1959136 -0.005505383 -0.1340718 -0.1896553 -0.005505383 -0.143613 -0.196073 -0.005505383 -0.1442762 -0.1945971 -0.005505144 -0.1336887 -0.1965718 -0.005505383 -0.1431585 -0.2090194 -0.005505383 -0.1397269 -0.21626 -0.005505383 -0.1323004 -0.2107188 -0.005505025 -0.1342742 -0.215879 -0.005505383 -0.1451348 -0.2145029 -0.005505383 -0.1443601 -0.2094073 -0.005505383 -0.1493604 -0.2106981 -0.005505383 -0.1454132 -0.2082678 -0.005505383 -0.1518226 -0.2033634 -0.005505383 -0.14569 -0.1967124 -0.005505383 -0.1507898 -0.1970985 -0.005505383 -0.1460321 -0.195199 -0.005505383 -0.1473488 -0.1922205 -0.005505383 -0.1423202 -0.1894416 -0.005505383 -0.1303799 -0.209795 -0.005505383 -0.1292457 -0.2131 -0.005505383 -0.1430602 -0.1893775 -0.006005346 -0.1505505 -0.1960144 -0.006005346 -0.1521168 -0.2044858 -0.006005346 -0.1493217 -0.2109903 -0.006005346 -0.1449805 -0.2147541 -0.006005346 -0.1394838 -0.2164267 -0.006005346 -0.1337817 -0.2157191 -0.006005346 -0.1276942 -0.211709 -0.006005346 -0.1244007 -0.2037482 -0.006005346 -0.1257824 -0.1968046 -0.006005346 -0.1292462 -0.1922205 -0.006005346 -0.1342748 -0.1894417 -0.006005346 -0.1394605 -0.1900648 -0.006005346 -0.1459754 -0.1924477 -0.006005346 -0.1506679 -0.1994627 -0.006005346 -0.1503186 -0.2065972 -0.006005346 -0.14742 -0.211423 -0.006005346 -0.1427147 -0.2145133 -0.006005346 -0.1358112 -0.2151931 -0.006005346 -0.129535 -0.2117829 -0.006005346 -0.1264447 -0.2070777 -0.006005346 -0.1257649 -0.2001741 -0.006005346 -0.1291751 -0.1938979 -0.006005346 -0.1338804 -0.1908075 -0.006005346 -0.1427148 -0.1908076 -0.007005333 -0.1358112 -0.1901277 -0.007005333 -0.14742 -0.1938979 -0.007005333 -0.1503185 -0.1987237 -0.007005333 -0.1506679 -0.2058582 -0.007005333 -0.1459755 -0.2128732 -0.007005333 -0.1379328 -0.2154322 -0.007005333 -0.1313536 -0.2132332 -0.007005333 -0.1274539 -0.2091733 -0.007005333 -0.1257019 -0.2038234 -0.007005333 -0.1264447 -0.1982432 -0.007005333 -0.129535 -0.193538 -0.007005333 -0.1384522 -0.2005167 -0.01350528 -0.1404413 -0.202815 -0.01350528 -0.139503 -0.200992 -0.01099652 -0.1403058 -0.2030912 -0.01100528 -0.1385805 -0.2047161 -0.01099461 -0.1381429 -0.2048043 -0.01350528 -0.1370848 -0.2043228 -0.01099634 -0.1361538 -0.2025058 -0.01350528 -0.1380515 -0.200605 -0.01099681 -0.1362893 -0.2022294 -0.01100528 -0.1411563 -0.1892111 -0.008005321 -0.1423202 -0.1894416 -0.007005333 -0.1369013 -0.1889155 -0.00798583 -0.1438901 -0.1900994 -0.008005321 -0.1467972 -0.1913968 -0.007391631 -0.1493219 -0.1943309 -0.007005333 -0.1494722 -0.1945441 -0.008031725 -0.1521124 -0.2024015 -0.007005333 -0.1517379 -0.1983708 -0.007411181 -0.1521045 -0.2028304 -0.008032858 -0.1510235 -0.2080428 -0.007005333 -0.1508992 -0.2083234 -0.007985889 -0.147734 -0.2127536 -0.007005333 -0.1476649 -0.2128208 -0.008015751 -0.1428132 -0.2157191 -0.007005333 -0.1426193 -0.2157807 -0.008027672 -0.1371114 -0.2164267 -0.007005333 -0.1367951 -0.2163879 -0.008033871 -0.1316146 -0.2147542 -0.007005333 -0.1312472 -0.214533 -0.008032798 -0.1257824 -0.2085162 -0.007005333 -0.1276652 -0.2119355 -0.007409036 -0.1256657 -0.208257 -0.007984936 -0.1247307 -0.2000417 -0.007005333 -0.1242876 -0.2043234 -0.007410645 -0.1247743 -0.1998428 -0.008027672 -0.1269687 -0.1947499 -0.007005333 -0.1271604 -0.1944954 -0.008033871 -0.1311656 -0.1908259 -0.007005333 -0.1315408 -0.1906184 -0.008032798 -0.136596 -0.1889483 -0.007005333 -0.1409496 -0.1914706 -0.01100528 -0.1382976 -0.1911606 -0.01100528 -0.1456895 -0.1938511 -0.01100528 -0.1483155 -0.1968767 -0.01100951 -0.1496227 -0.2006636 -0.01100528 -0.1497779 -0.2033292 -0.01100528 -0.1493142 -0.2059586 -0.01100528 -0.1482567 -0.2084104 -0.01100528 -0.1456138 -0.2116183 -0.01100772 -0.1422307 -0.2134668 -0.01100528 -0.1396325 -0.2140826 -0.01100528 -0.1369625 -0.2140826 -0.01100528 -0.1343643 -0.2134668 -0.01100528 -0.1319782 -0.2122684 -0.01100528 -0.1299329 -0.2105522 -0.01100528 -0.1283384 -0.2084104 -0.01100528 -0.1272808 -0.2059586 -0.01100528 -0.1268171 -0.2033292 -0.01100528 -0.1272294 -0.1992907 -0.01100635 -0.129846 -0.1947609 -0.01100802 -0.1341973 -0.1918447 -0.01100647 -0.1454132 -0.2080776 -0.01100528 -0.1441903 -0.2094905 -0.01100528 -0.1443603 -0.2069381 -0.01100528 -0.1431586 -0.2073259 -0.01100528 -0.1428937 -0.2085607 -0.01100528 -0.1322348 -0.1983827 -0.01100528 -0.131182 -0.1972433 -0.01100528 -0.1321118 -0.1959466 -0.01100528 -0.1335936 -0.196407 -0.01100528 -0.1445783 -0.1970102 -0.01100528 -0.14578 -0.1966224 -0.01100528 -0.1460449 -0.1953878 -0.01100528 -0.1334365 -0.197995 -0.01100528 -0.1323927 -0.2084122 -0.01100111 -0.130815 -0.2086986 -0.01100528 -0.1305501 -0.2099331 -0.01100528 -0.07910239 -0.005648732 0.007826209 -0.08477324 -0.03139275 0.008374571 -0.07910239 -0.03139448 0.008275628 -0.07844853 -0.01813191 0.03037512 -0.08323633 0.008015573 0.02725839 -0.08406525 0.008457183 0.02708017 -0.08409154 0.006747424 0.02756363 -0.08336859 -0.03413301 0.02041494 -0.08424508 -0.03249961 0.01944881 -0.08340102 -0.03436321 0.01851975 -0.08339005 -0.03257834 0.01916015 -0.0844022 0.006436824 0.00976926 -0.08353501 0.007282912 0.0101583 -0.08433246 0.008313775 0.009721755 -0.08098816 0.009728014 0.01496696 -0.08311152 0.00972861 0.01500403 -0.08098816 0.004228889 0.01506292 -0.08311152 0.004229545 0.0151 -0.08298367 0.009856402 0.02232533 -0.08298367 0.004357337 0.02242136 -0.08086037 0.009855806 0.02228832 -0.08086037 0.004356682 0.02238428 -0.08051633 0.009861588 0.02262043 -0.0833159 0.009862422 0.02266931 -0.08051633 0.004362463 0.02271646 -0.0833159 0.004363358 0.02276527 -0.08065599 0.009721994 0.01462298 -0.08065599 0.004222869 0.01471894 -0.0834555 0.009722828 0.01467186 -0.0834555 0.004223763 0.01476782 -0.08319896 -0.005268096 0.02963334 -0.08357244 -0.00564152 0.008240103 -0.08357548 0.009602844 0.007799029 -0.08319586 0.009982407 0.02954214 -0.08342158 -0.03623557 0.0174179 -0.08319586 -0.03600996 0.0303449 -0.0831989 -0.03101384 0.0300827 -0.08357238 -0.03138726 0.008689522 -0.08356183 -0.03637826 0.009247601 -0.08357548 -0.03638947 0.008601844 -0.08449512 0.009701907 0.01347357 -0.08767747 0.009702861 0.01352912 -0.08449512 0.00490272 0.01355737 -0.087498 0.00988233 0.02380871 -0.08431571 0.009881317 0.02375316 -0.08431571 0.00508213 0.02383691 -0.08111596 -0.03734344 0.01124542 -0.08015841 -0.03732919 0.01206421 -0.07969117 -0.03730875 0.01323413 -0.07982116 -0.03728687 0.01448714 -0.08051872 -0.03726857 0.01553624 -0.08162391 -0.03725802 0.01614105 -0.08288365 -0.03725761 0.01616299 -0.08400934 -0.0372675 0.01559716 -0.08400928 -0.04826569 0.01578909 -0.08474302 -0.03728538 0.01457303 -0.08474302 -0.04828357 0.01476502 -0.08491671 -0.03730714 0.01332533 -0.08491671 -0.04830533 0.01351732 -0.08449059 -0.03732788 0.01213985 -0.08449053 -0.04832601 0.01233178 -0.08356225 -0.03734272 0.01128816 -0.08356219 -0.04834091 0.01148009 -0.08234435 -0.03734833 0.01096534 -0.08473557 -0.03733515 0.01172226 -0.08530771 -0.03731346 0.0129652 -0.08528387 -0.03728955 0.0143333 -0.08466869 -0.03726822 0.0155555 -0.08358401 -0.03725367 0.01638978 -0.08224475 -0.03724879 0.01667094 -0.0809161 -0.03725451 0.01634323 -0.07986122 -0.03726971 0.01547157 -0.07928907 -0.0372914 0.01422864 -0.07931292 -0.03731524 0.01286059 -0.07992815 -0.03733658 0.01163834 -0.0839768 -0.0373696 0.009775638 -0.0863226 -0.03731489 0.01289349 -0.08560776 -0.03726118 0.01595991 -0.08225458 -0.03723353 0.01776015 -0.08018243 -0.03736311 0.01012367 -0.07819217 -0.03637772 0.0127151 -0.07893925 -0.03726226 0.01588833 -0.08026844 -0.03623884 0.01723128 -0.08428812 -0.036242 0.01704889 -0.08440798 -0.03636193 0.0101816 -0.08669966 -0.03630006 0.01365625 -0.08443534 -0.03638923 0.008616864 -0.08405572 -0.03600966 0.03035992 -0.07889968 -0.005269408 0.0295583 -0.07889962 -0.03101515 0.03000766 -0.08405578 0.009982645 0.0295571 -0.08443534 0.009603142 0.007814049 0.1263751 0.2252467 0.03249406 0.1263751 0.2252467 0.02049422 0.1250736 0.2255437 0.03249406 0.127419 0.2244142 0.02049422 0.127419 0.2244142 0.03249406 0.1263751 0.2198409 0.03249406 0.1250736 0.2195438 0.03249406 0.1250736 0.2195438 0.02049422 0.1237719 0.2198409 0.03249406 0.1237719 0.2198409 0.02049422 0.1174545 0.2146274 0.02049428 0.1227281 0.2206734 0.02049422 0.1230322 0.2115277 0.02049428 0.118917 0.213433 0.01949423 0.1305438 0.212831 0.02049428 0.1273718 0.2117908 0.01949423 0.1229776 0.2116365 0.01949411 0.1207236 0.2165224 0.01949417 0.124421 0.2197514 0.01949423 0.1267592 0.2159346 0.01949411 0.1254396 0.2188339 0.01368165 0.1273073 0.213281 0.01374375 0.1273718 0.2117908 0.01549428 0.1274868 0.2106446 0.00979495 0.1276133 0.2090306 0.01119434 0.1296006 0.2095555 0.01121592 0.1299169 0.2125932 0.01546901 0.1298855 0.2126568 0.01949423 0.1313952 0.2103334 0.01119434 0.1294004 0.2134066 0.01368844 0.1302982 0.2119944 0.01119661 0.1302876 0.2120101 0.009794354 0.1313952 0.2103334 0.009794354 0.1335746 0.2117369 0.009794354 0.1354519 0.2135246 0.009794354 0.1261329 0.2202782 0.009794354 0.1364188 0.2187607 0.009795069 0.1238106 0.220385 0.009794354 0.12754 0.2221288 0.009794354 0.1240141 0.2202782 0.01368254 0.1263363 0.220385 0.01368254 0.126851 0.2198637 0.01368242 0.1275677 0.2223568 0.01368254 0.1236094 0.2194237 0.01368153 0.1213977 0.2174564 0.01368296 0.122007 0.2202854 0.01368206 0.1220043 0.2222927 0.01949417 0.1225345 0.2218763 0.01368457 0.1203023 0.2178793 0.01949423 0.1181659 0.2159085 0.01374393 0.1168605 0.2151326 0.01547563 0.1161246 0.2146101 0.009795129 0.1185607 0.212765 0.01123231 0.1193335 0.2141931 0.01368296 0.118917 0.213433 0.01549428 0.1176598 0.2109639 0.01119434 0.1160888 0.2121292 0.01121592 0.1146407 0.2135877 0.01119434 0.1146407 0.2135877 0.009794354 0.1176598 0.2109639 0.009794354 0.1148554 0.2133434 -0.005005359 0.1169915 0.21142 -0.005005359 0.1194809 0.2099828 -0.005005359 0.1191853 0.2168467 -0.005005359 0.1131658 0.2156689 -0.005005359 0.1250736 0.2087939 -0.005005359 0.1186248 0.2290664 -0.005005359 0.1315222 0.2160212 -0.005005359 0.1309618 0.2282409 -0.005005359 0.111399 0.223981 -0.005005359 0.111399 0.2211066 -0.005005359 0.1119966 0.2182949 -0.005005359 0.1222148 0.2090945 -0.005005359 0.119965 0.2097783 0.009794354 0.1224519 0.2090463 0.009794354 0.1185939 0.2128239 0.009794354 0.1250318 0.2087941 0.009794354 0.1276133 0.2090306 0.009794354 0.1279323 0.2090945 -0.005005359 0.1306661 0.2099828 -0.005005359 0.1331554 0.21142 -0.005005359 0.1352916 0.2133434 -0.005005359 0.1369812 0.2156689 -0.005005359 0.1369603 0.2156329 0.009794354 0.1381503 0.2182949 -0.005005359 0.1380462 0.2179867 0.009794354 0.1380462 0.2179867 0.01119434 0.1385853 0.2199705 0.01121592 0.1360419 0.2217675 0.01549428 0.1388089 0.2219133 0.009794354 0.1388089 0.2219133 0.01119434 0.1387479 0.2211066 -0.005005359 0.1355984 0.2191368 0.01547557 0.1347386 0.2195029 0.01368337 0.1355587 0.2191565 0.01949363 0.1360073 0.2216908 0.01949423 0.1359875 0.2212043 0.02049422 0.1279983 0.2218763 0.02049422 0.1348049 0.2175861 0.02049422 0.1356343 0.2262842 0.02049428 0.1355676 0.2261822 0.01949417 0.1317647 0.2312858 0.02049428 0.1279983 0.2232114 0.02049422 0.1332367 0.2299107 0.01949423 0.1298445 0.2272081 0.01949423 0.1312693 0.2317136 0.01546901 0.1332367 0.2299107 0.01549428 0.1338676 0.2303703 0.01119667 0.1340584 0.2329583 0.01121592 0.1325422 0.2293922 0.01368296 0.1355064 0.2315 0.01119434 0.1355064 0.2315 0.009794354 0.1337947 0.2303156 0.009794354 0.1369812 0.2294187 -0.005005359 0.137002 0.2293826 0.009794354 0.1352916 0.2317442 -0.005005359 0.1331554 0.2336676 -0.005005359 0.1306661 0.2351049 -0.005005359 0.1324872 0.2341237 0.009794354 0.130182 0.2353094 0.009794354 0.1315889 0.2323262 0.009794354 0.1324872 0.2341237 0.01119434 0.1310257 0.2312535 0.01318186 0.1287496 0.2276318 0.01368296 0.1294236 0.2285656 0.01949417 0.1312299 0.2316545 0.01949423 0.1257261 0.2253362 0.01949423 0.1271547 0.2335096 0.01949435 0.1220268 0.2331001 0.02049428 0.1270737 0.233425 0.02049428 0.1233728 0.2292 0.01949405 0.1227753 0.2332968 0.01949423 0.1227617 0.2333621 0.01547563 0.1227962 0.2318553 0.01373726 0.1202616 0.2324308 0.01949423 0.1202616 0.2324308 0.01549428 0.122677 0.2342606 0.009795069 0.1225337 0.236057 0.01119434 0.1205465 0.2355322 0.01121592 0.118752 0.2347542 0.01119434 0.1222148 0.2359932 -0.005005359 0.1194809 0.2351049 -0.005005359 0.1225337 0.236057 0.009794354 0.118752 0.2347542 0.009794354 0.1169915 0.2336676 -0.005005359 0.1165724 0.2333508 0.009794354 0.1198957 0.2330152 0.009794354 0.1146951 0.231563 0.009794354 0.1225148 0.2230264 0.009794354 0.1245871 0.2249972 0.009794354 0.1198612 0.2330735 0.01123231 0.1207467 0.2316811 0.01368844 0.1230335 0.2270805 0.01949423 0.1228565 0.2270833 0.01368343 0.1231446 0.2243631 0.01368772 0.1247076 0.2262535 0.01368176 0.1265377 0.2256639 0.01368147 0.1261299 0.2249237 0.01368254 0.1268163 0.2243378 0.009794354 0.1284556 0.2228692 0.01368093 0.1285498 0.2257886 0.01368427 0.1281427 0.2227949 0.01949417 0.1314656 0.2219114 0.01368266 0.1306865 0.2208989 0.01368331 0.135123 0.2217436 0.01368874 0.1374534 0.2218218 0.009797155 0.1386831 0.2245026 0.009794354 0.1380736 0.2270221 0.009794354 0.1381503 0.2267927 -0.005005359 0.1387479 0.223981 -0.005005359 0.1288766 0.2213208 0.01949423 0.1271135 0.2180073 0.01949423 0.1326398 0.2144795 0.01949429 0.1276952 0.2360414 0.009794354 0.1250736 0.2362936 -0.005005359 0.1279323 0.2359932 -0.005005359 0.1251151 0.2362936 0.009794354 0.1212701 0.2237669 0.01949423 0.1194605 0.2241887 0.01368331 0.1186813 0.2231763 0.01368266 0.1154084 0.2255848 0.01368337 0.115024 0.223344 0.01368874 0.1146085 0.225915 0.01949423 0.1146121 0.2259299 0.01549428 0.1137052 0.2263377 0.009795129 0.1133251 0.2232939 0.01119667 0.1140343 0.2233247 0.01546901 0.1134161 0.2232953 0.009794354 0.1113381 0.2231743 0.01119434 0.1113381 0.2231743 0.009794354 0.1115619 0.225118 0.01121586 0.1119966 0.2267927 -0.005005359 0.1121008 0.2271009 0.01119434 0.1121008 0.2271009 0.009794354 0.1131658 0.2294187 -0.005005359 0.1131867 0.2294548 0.009794354 0.1148554 0.2317442 -0.005005359 0.1114639 0.2205851 0.009794354 0.1120734 0.2180655 0.009794354 0.113145 0.215705 0.009794354 0.1141265 0.2233974 0.01949417 0.1143305 0.2251786 0.02049428 0.1227281 0.2244142 0.02049422 0.1221488 0.2218763 0.02049422 0.1145364 0.2188633 0.01949435 0.1175113 0.2306373 0.02049428 0.1221488 0.2232114 0.02049422 0.1147893 0.2188677 0.02049422 0.1166731 0.2298076 0.01949411 0.1221488 0.2218763 0.03249406 0.1221488 0.2232114 0.03249406 0.1227281 0.2244142 0.03249406 0.1237719 0.2252467 0.03249406 0.1237719 0.2252467 0.02049422 0.1227281 0.2206734 0.03249406 0.1250736 0.2255437 0.02049422 0.1169103 0.2151769 0.01949423 0.1279983 0.2232114 0.03249406 0.1279983 0.2218763 0.03249406 0.127419 0.2206734 0.03249406 0.127419 0.2206734 0.02049422 0.1263751 0.2198409 0.02049422 -0.1369959 -0.1999576 0.03249406 -0.1369959 -0.1999576 0.02049422 -0.1382976 -0.1996605 0.03249406 -0.1359521 -0.2007899 0.02049422 -0.1359521 -0.2007899 0.03249406 -0.1369959 -0.2053633 0.03249406 -0.1382976 -0.2056604 0.03249406 -0.1382976 -0.2056604 0.02049422 -0.1395992 -0.2053633 0.02049422 -0.1395992 -0.2053633 0.03249406 -0.140643 -0.2045309 0.02049422 -0.1395992 -0.1999576 0.03249406 -0.140643 -0.2045309 0.03249406 -0.1412222 -0.203328 0.02049422 -0.1412222 -0.203328 0.03249406 -0.140643 -0.2007899 0.03249406 -0.1395992 -0.1999576 0.02049422 -0.1412222 -0.2019929 0.03249406 -0.140643 -0.2007899 0.02049422 -0.1412222 -0.2019929 0.02049422 -0.14586 -0.1945673 0.02049428 -0.1490406 -0.2000258 0.02049428 -0.1492446 -0.2018069 0.01949417 -0.1493368 -0.2018796 0.01546901 -0.1487626 -0.1992893 0.01949423 -0.1488348 -0.2063408 0.01949435 -0.1466981 -0.1953969 0.01949411 -0.1485818 -0.2063366 0.02049422 -0.1459164 -0.210577 0.02049428 -0.1464608 -0.2100273 0.01949423 -0.1403386 -0.2136766 0.02049428 -0.144454 -0.2117712 0.01949423 -0.1465106 -0.2100717 0.01547563 -0.1430685 -0.2073248 0.01949423 -0.145205 -0.2092956 0.01374399 -0.144454 -0.2117712 0.01549428 -0.1472464 -0.2105942 0.009795129 -0.1487304 -0.2116166 0.01119434 -0.1472825 -0.2130749 0.01121586 -0.1457113 -0.2142404 0.009794354 -0.1487304 -0.2116166 0.009794354 -0.1457113 -0.2142404 0.01119434 -0.1485156 -0.2118609 -0.005005359 -0.1463794 -0.2137843 -0.005005359 -0.1438901 -0.2152216 -0.005005359 -0.1441858 -0.2083575 -0.005005359 -0.1447463 -0.1961379 -0.005005359 -0.1318488 -0.209183 -0.005005359 -0.1324092 -0.1969633 -0.005005359 -0.151972 -0.2012231 -0.005005359 -0.151972 -0.2040977 -0.005005359 -0.1513744 -0.2069094 -0.005005359 -0.1411563 -0.2161098 -0.005005359 -0.1502052 -0.2095354 -0.005005359 -0.1382976 -0.2164103 -0.005005359 -0.1357577 -0.2161737 0.009794354 -0.1409192 -0.216158 0.009794354 -0.1383392 -0.2164103 0.009794354 -0.1354388 -0.2161098 -0.005005359 -0.1327049 -0.2152216 -0.005005359 -0.1337715 -0.2156491 0.01121586 -0.1357577 -0.2161737 0.01119434 -0.1319758 -0.2148709 0.009794354 -0.1334542 -0.2126111 0.01546901 -0.1319758 -0.2148709 0.01119434 -0.1359992 -0.2134134 0.01549428 -0.136597 -0.209316 0.01949405 -0.1358841 -0.2145597 0.00979495 -0.1361009 -0.2125527 0.0136829 -0.1359992 -0.2134134 0.01949423 -0.1403934 -0.2135678 0.01949411 -0.1328272 -0.2123733 0.02049428 -0.1285662 -0.2076182 0.02049422 -0.1359521 -0.2045309 0.02049422 -0.1369959 -0.2053633 0.02049422 -0.1334856 -0.2125475 0.01949423 -0.1307318 -0.2107253 0.01949429 -0.134494 -0.2038835 0.01949423 -0.1278124 -0.2060479 0.01949363 -0.1362543 -0.2072218 0.01949423 -0.1339954 -0.211738 0.01368951 -0.13652 -0.2053405 0.01368242 -0.1358034 -0.2028475 0.01368254 -0.1370346 -0.2048193 0.01368254 -0.1326845 -0.2043052 0.01368331 -0.1372385 -0.2072314 0.01368421 -0.1349154 -0.2023352 0.01368087 -0.1352311 -0.2004021 0.01368212 -0.1367267 -0.2007141 0.01368254 -0.1319048 -0.2032929 0.01368266 -0.1352283 -0.2024093 0.01949417 -0.1273637 -0.2035135 0.01949423 -0.1335263 -0.197996 0.01949423 -0.1278037 -0.1990217 0.01949417 -0.1301344 -0.1952936 0.01949423 -0.1277368 -0.1989199 0.02049428 -0.1316066 -0.1939183 0.02049428 -0.1273836 -0.2039999 0.02049422 -0.1353728 -0.2019929 0.02049422 -0.1353728 -0.203328 0.02049422 -0.1353728 -0.2019929 0.03249406 -0.1353728 -0.203328 0.03249406 -0.1359521 -0.2045309 0.03249406 -0.1277728 -0.2060676 0.01547563 -0.1286324 -0.2057014 0.01368337 -0.1273291 -0.2034367 0.01549428 -0.1269522 -0.2064435 0.009795069 -0.1253249 -0.2072175 0.01119434 -0.124786 -0.2052349 0.01121586 -0.1253249 -0.2072175 0.009794354 -0.1245622 -0.2032909 0.009794354 -0.1245622 -0.2032909 0.01119434 -0.1252207 -0.2069094 -0.005005359 -0.1246231 -0.2040977 -0.005005359 -0.1246231 -0.2012231 -0.005005359 -0.1246879 -0.2007017 0.009794354 -0.1252207 -0.1984115 -0.005005359 -0.1252974 -0.1981821 0.009794354 -0.1263898 -0.1957855 -0.005005359 -0.126369 -0.1958217 0.009794354 -0.1280794 -0.1934601 -0.005005359 -0.1278647 -0.1937043 0.009794354 -0.130488 -0.19554 0.0131486 -0.1278647 -0.1937043 0.01119434 -0.1293119 -0.1922465 0.01121586 -0.1295763 -0.1948887 0.009794354 -0.1358311 -0.2030756 0.009794354 -0.1365548 -0.2008664 0.009794354 -0.1317821 -0.192878 0.009794354 -0.1317738 -0.192861 0.01119661 -0.1321017 -0.1934906 0.01546901 -0.1308839 -0.1910805 0.01119434 -0.1325575 -0.1943098 0.01368296 -0.1335967 -0.1981619 0.01368248 -0.1339477 -0.1966391 0.01949417 -0.1360704 -0.1993043 0.01368355 -0.139007 -0.200262 0.01368254 -0.137645 -0.1998681 0.01949423 -0.1386635 -0.1989507 0.01368176 -0.1399832 -0.1960513 0.01949411 -0.1405313 -0.1933977 0.01374375 -0.1402555 -0.2007183 0.0136885 -0.1405146 -0.1981208 0.01368343 -0.1426244 -0.1935231 0.01368844 -0.1403375 -0.198124 0.01949423 -0.1431095 -0.1927734 0.01949423 -0.142101 -0.2014374 0.01949423 -0.1439104 -0.2010157 0.01368331 -0.1479626 -0.1996195 0.01368337 -0.148759 -0.1992744 0.01549428 -0.1496658 -0.1988665 0.009795129 -0.150046 -0.2019104 0.01119661 -0.148347 -0.2018603 0.01368874 -0.14469 -0.202028 0.01368266 -0.1413667 -0.2029116 0.01949417 -0.1416796 -0.2029857 0.01368087 -0.1407639 -0.2030758 0.01368254 -0.1393569 -0.2049261 0.01368254 -0.141364 -0.204919 0.01368206 -0.1419734 -0.2077481 0.01368296 -0.1397617 -0.2057805 0.01368153 -0.1389501 -0.2054528 0.01949423 -0.1426478 -0.2086825 0.01949417 -0.1440375 -0.2110112 0.01368296 -0.1448103 -0.2124392 0.01123237 -0.1447772 -0.2123803 0.009794354 -0.143406 -0.2154261 0.009794354 -0.1395604 -0.2048194 0.009794354 -0.1408563 -0.2021781 0.009794354 -0.137238 -0.2049261 0.009794354 -0.1330835 -0.2131943 0.009794354 -0.1279191 -0.2116796 0.009794354 -0.1297965 -0.2134673 0.009794354 -0.1280794 -0.2118609 -0.005005359 -0.1263898 -0.2095354 -0.005005359 -0.1264107 -0.2095714 0.009794354 -0.1302156 -0.2137843 -0.005005359 -0.1330729 -0.21321 0.01119667 -0.138784 -0.2002071 0.009794354 -0.149955 -0.2019088 0.009794354 -0.1486759 -0.1936413 0.009794354 -0.1434754 -0.192189 0.009794354 -0.1512976 -0.2071388 0.009794354 -0.1519071 -0.2046192 0.009794354 -0.150226 -0.2094992 0.009794354 -0.1520329 -0.20203 0.009794354 -0.1520329 -0.20203 0.01119434 -0.1518093 -0.2000873 0.01121592 -0.1513744 -0.1984115 -0.005005359 -0.1512702 -0.1981034 0.01119434 -0.1512702 -0.1981034 0.009794354 -0.1502052 -0.1957855 -0.005005359 -0.1501843 -0.1957495 0.009794354 -0.1485156 -0.1934601 -0.005005359 -0.1463794 -0.1915366 -0.005005359 -0.1467986 -0.1918536 0.009794354 -0.1446192 -0.19045 0.009794354 -0.1446192 -0.19045 0.01119434 -0.1428235 -0.1896718 0.01121586 -0.1438901 -0.1900994 -0.005005359 -0.1411563 -0.1892111 -0.005005359 -0.1408373 -0.1891472 0.009794354 -0.1382976 -0.1889106 -0.005005359 -0.1354388 -0.1892111 -0.005005359 -0.1356759 -0.1891629 0.009794354 -0.1382558 -0.1889107 0.009794354 -0.1406939 -0.1909436 0.009795069 -0.1408373 -0.1891472 0.01119434 -0.1406093 -0.1918422 0.01547574 -0.1435099 -0.1921308 0.01123231 -0.1431095 -0.1927734 0.01549428 -0.1405958 -0.1919075 0.01949423 -0.1413438 -0.1921041 0.02049428 -0.1362972 -0.1917792 0.02049428 -0.1382976 -0.1996605 0.02049422 -0.1362162 -0.1916947 0.01949435 -0.1321411 -0.1935496 0.01949423 -0.133189 -0.1898948 0.009794354 -0.1327049 -0.1900994 -0.005005359 -0.1308839 -0.1910805 0.009794354 -0.1302156 -0.1915366 -0.005005359 -0.1301344 -0.1952936 0.01549428 -0.1259176 -0.2033824 0.009797155 -0.128248 -0.2034607 0.01368874 0.1263753 -0.2164031 0.03249406 0.1263753 -0.2164031 0.02049422 0.1250737 -0.2161059 0.03249406 0.127419 -0.2172355 0.02049422 0.127419 -0.2172355 0.03249406 0.1263753 -0.2218088 0.03249406 0.1250737 -0.2221059 0.03249406 0.123772 -0.2218088 0.02049422 0.123772 -0.2218088 0.03249406 0.1250737 -0.2221059 0.02049422 0.1263753 -0.2218088 0.02049422 0.1230325 -0.2301221 0.02049428 0.1305437 -0.2288189 0.02049428 0.1326403 -0.2271699 0.01949429 0.1273719 -0.2298589 0.01949423 0.134805 -0.2240637 0.02049422 0.127419 -0.2209764 0.02049422 0.1298855 -0.228993 0.01949423 0.129917 -0.2290567 0.01546901 0.1273719 -0.2298589 0.01549428 0.1304159 -0.2298341 0.009795129 0.1313953 -0.2313163 0.01119434 0.1296007 -0.2320942 0.01121592 0.1293624 -0.2281732 0.01369231 0.1271135 -0.2236424 0.01949423 0.1268511 -0.221786 0.01368242 0.1261326 -0.2236768 0.01368421 0.1272702 -0.2289982 0.0136829 0.1274544 -0.2306351 0.01119667 0.1276134 -0.2326191 0.01119434 0.1276134 -0.2326191 0.009794354 0.1274435 -0.2305447 0.009794354 0.122452 -0.2326036 0.009794354 0.125032 -0.2328556 0.009794354 0.1238107 -0.2212648 0.009794354 0.126133 -0.2213716 0.009794354 0.1364189 -0.222889 0.009795069 0.135452 -0.2281252 0.009794354 0.1275401 -0.2195213 0.009794354 0.1240141 -0.2213716 0.01368254 0.1269243 -0.2209376 0.01368254 0.1284558 -0.2187807 0.01368087 0.127458 -0.2181676 0.01368182 0.1236094 -0.222226 0.01368153 0.1213979 -0.2241934 0.01368296 0.1244211 -0.2218983 0.01949423 0.1220072 -0.2213642 0.01368206 0.1220044 -0.2193571 0.01949417 0.1225345 -0.2197734 0.01368457 0.120303 -0.2237699 0.01949423 0.1181662 -0.2257411 0.01374399 0.1168606 -0.2265172 0.01547563 0.1161248 -0.2270397 0.009795129 0.1185609 -0.2288848 0.01123231 0.1193336 -0.2274567 0.01368296 0.1189171 -0.2282167 0.01549428 0.1207232 -0.2251282 0.01949417 0.1189171 -0.2282167 0.01949423 0.1229777 -0.2300133 0.01949411 0.1267742 -0.2257616 0.01949405 0.1174544 -0.2270221 0.02049428 0.1147894 -0.2227821 0.02049422 0.1227282 -0.2209764 0.02049422 0.1169105 -0.2264728 0.01949423 0.1145364 -0.2227863 0.01949435 0.1141265 -0.2182524 0.01949417 0.1143307 -0.216471 0.02049428 0.1227282 -0.2172355 0.02049422 0.1146085 -0.2157348 0.01949423 0.1140344 -0.2183251 0.01546901 0.1221489 -0.2197735 0.02049422 0.1166731 -0.2118422 0.01949411 0.1175114 -0.2110126 0.02049428 0.1221489 -0.2184383 0.02049422 0.1221489 -0.2197735 0.03249406 0.1221489 -0.2184383 0.03249406 0.1227282 -0.2172355 0.03249406 0.123772 -0.2164031 0.02049422 0.123772 -0.2164031 0.03249406 0.1227282 -0.2209764 0.03249406 0.1250737 -0.2161059 0.02049422 0.1220272 -0.2085496 0.02049428 0.1270739 -0.2082247 0.02049428 0.1271548 -0.2081403 0.01949435 0.1317641 -0.2103635 0.02049428 0.1332368 -0.211739 0.01949423 0.1356345 -0.2153657 0.02049428 0.1312301 -0.2099952 0.01949423 0.1312694 -0.2099362 0.01546901 0.1332368 -0.211739 0.01549428 0.1324874 -0.207526 0.01119434 0.1315973 -0.2093065 0.01119661 0.1308135 -0.2107552 0.01368296 0.1340593 -0.2086921 0.01121586 0.1294241 -0.2130837 0.01949417 0.1287496 -0.2140182 0.01368296 0.1257262 -0.2163136 0.01949423 0.1256821 -0.2165421 0.01368433 0.1247076 -0.2153961 0.01368176 0.1233732 -0.2124506 0.01949405 0.1227964 -0.2097945 0.01373726 0.1227618 -0.2082877 0.01547569 0.1227753 -0.208353 0.01949423 0.1202617 -0.2092189 0.01949423 0.1202617 -0.2092189 0.01549428 0.1226772 -0.207389 0.009795069 0.1225338 -0.2055927 0.01119434 0.1205472 -0.2061174 0.01121586 0.118752 -0.2068955 0.01119434 0.119481 -0.2065449 -0.005005359 0.1222149 -0.2056566 -0.005005359 0.1225338 -0.2055927 0.009794354 0.118752 -0.2068955 0.009794354 0.1198958 -0.2086344 0.009794354 0.1169916 -0.2079821 -0.005005359 0.1165724 -0.2082991 0.009794354 0.1148555 -0.2099055 -0.005005359 0.1146952 -0.2100867 0.009794354 0.1131659 -0.212231 -0.005005359 0.1131868 -0.2121949 0.009794354 0.1225149 -0.2186234 0.009794354 0.1137052 -0.215312 0.009795129 0.1154085 -0.216065 0.01368337 0.1121009 -0.2145489 0.01119434 0.1121009 -0.2145489 0.009794354 0.1134162 -0.2183544 0.009794354 0.1133252 -0.2183558 0.01119667 0.1146121 -0.2157199 0.01549428 0.1115621 -0.2165315 0.01121586 0.1113382 -0.2184754 0.01119434 0.1119967 -0.214857 -0.005005359 0.1113991 -0.2176687 -0.005005359 0.1113382 -0.2184754 0.009794354 0.1113991 -0.2205432 -0.005005359 0.111464 -0.2210647 0.009794354 0.1119967 -0.2233549 -0.005005359 0.1120736 -0.2235842 0.009794354 0.1131451 -0.2259447 0.009794354 0.1131659 -0.2259808 -0.005005359 0.1148555 -0.2283064 -0.005005359 0.1191853 -0.224803 -0.005005359 0.1146407 -0.2280621 0.009794354 0.1146407 -0.2280621 0.01119434 0.1160888 -0.2295205 0.01121592 0.1169916 -0.2302298 -0.005005359 0.1176599 -0.2306859 0.009794354 0.1176599 -0.2306859 0.01119434 0.1185941 -0.2288258 0.009794354 0.1199651 -0.2318716 0.009794354 0.119481 -0.2316671 -0.005005359 0.1222149 -0.2325553 -0.005005359 0.1250737 -0.2328557 -0.005005359 0.1279323 -0.2325553 -0.005005359 0.1315223 -0.2256285 -0.005005359 0.1352917 -0.2283064 -0.005005359 0.1369813 -0.2259808 -0.005005359 0.1381505 -0.2233549 -0.005005359 0.1306662 -0.2316671 -0.005005359 0.1387481 -0.2205432 -0.005005359 0.1309619 -0.2134088 -0.005005359 0.1331555 -0.2302298 -0.005005359 0.1313953 -0.2313163 0.009794354 0.1335747 -0.2299128 0.009794354 0.1381505 -0.214857 -0.005005359 0.1279323 -0.2056566 -0.005005359 0.1369813 -0.212231 -0.005005359 0.1250737 -0.2053561 -0.005005359 0.1352917 -0.2099055 -0.005005359 0.1186249 -0.2125834 -0.005005359 0.1331555 -0.2079821 -0.005005359 0.1387481 -0.2176687 -0.005005359 0.1306662 -0.2065449 -0.005005359 0.1301821 -0.2063403 0.009794354 0.1324874 -0.207526 0.009794354 0.131589 -0.2093235 0.009794354 0.1337949 -0.2113341 0.009794354 0.1276953 -0.2056084 0.009794354 0.1268164 -0.217312 0.009794354 0.1245872 -0.2166525 0.009794354 0.1231448 -0.2172866 0.01368772 0.1212702 -0.2178829 0.01949423 0.1194606 -0.2174611 0.01368331 0.1228565 -0.2145662 0.01368343 0.1230337 -0.2145694 0.01949423 0.1207467 -0.2099686 0.01368844 0.1198614 -0.2085763 0.01123243 0.1186812 -0.2184735 0.01368266 0.1150241 -0.2183058 0.01368874 0.1251153 -0.2053562 0.009794354 0.1355065 -0.2101498 0.009794354 0.1380737 -0.2146276 0.009794354 0.1370021 -0.2122671 0.009794354 0.1328831 -0.2119854 0.01314854 0.1298443 -0.2144419 0.01949423 0.1297745 -0.2146073 0.01368248 0.1355065 -0.2101498 0.01119434 0.1281428 -0.2188548 0.01949417 0.1355676 -0.2154674 0.01949417 0.1360074 -0.219959 0.01949423 0.1351231 -0.2199062 0.01368874 0.136042 -0.2198822 0.01549428 0.1359875 -0.2204454 0.02049422 0.1355984 -0.222513 0.01547569 0.1314663 -0.2197384 0.01368266 0.1306865 -0.2207508 0.01368331 0.1347388 -0.2221468 0.01368337 0.1288769 -0.2203289 0.01949423 0.1355588 -0.2224934 0.01949363 0.1374535 -0.2198279 0.009797155 0.138809 -0.2197364 0.009794354 0.138809 -0.2197364 0.01119434 0.1386832 -0.2171472 0.009794354 0.1385852 -0.2216804 0.01121592 0.1380463 -0.223663 0.01119434 0.1380463 -0.223663 0.009794354 0.1369604 -0.2260169 0.009794354 0.1279983 -0.2197735 0.02049422 0.1279983 -0.2184383 0.03249406 0.1279983 -0.2197735 0.03249406 0.1279983 -0.2184383 0.02049422 0.127419 -0.2209764 0.03249406 + + + + + + + + + + 0.6234599 0.7818554 0 0.2225338 0.974925 0 -3.72675e-6 0 1 0.6234529 0.7818611 0 -5.15751e-6 0 1 2.84375e-6 0 1 0 0 1 0.2225263 -0.9749268 0 -0.2225106 -0.9749304 0 -0.2225105 -0.9749304 0 3.22373e-6 0 1 -0.6235291 -0.7818002 0 -0.6235359 -0.7817948 0 -0.9009652 -0.4338915 0 -0.6234883 0.7818328 0 -0.6234812 0.7818384 0 9.40787e-6 0 1 -0.9009672 0.4338873 0 -0.9009673 0.4338871 0 7.24561e-6 -3.377e-6 1 1.34267e-6 -1.43511e-6 1 7.91334e-6 4.05065e-6 1 -0.9945468 0.1021708 0.02092933 -0.9360353 -0.08459758 0.3415866 -0.9552998 0.291186 -0.05111771 -0.8790841 0.46627 0.09901303 -0.9669913 -0.0703023 0.2449197 -0.8261238 0.4813642 0.29293 3.95568e-6 -9.45903e-6 1 9.06181e-6 0 1 -6.86711e-7 0 1 -1.13459e-6 7.30187e-6 1 -0.8274554 -0.5201187 0.2116461 -0.8301636 -0.5346413 0.1580733 -0.7253282 -0.6882038 0.01657438 2.71976e-6 3.45207e-6 1 4.48582e-6 1.39663e-6 1 -0.4607923 -0.8291867 0.3164172 -0.6337307 -0.7735486 -0.002860784 -0.6171159 0.7868179 -0.009258389 -0.6231172 0.7821281 -9.03215e-4 -0.6370595 -0.7708147 0 -0.5352685 -0.6416251 0.5493677 -0.5974511 0.8018972 0.003643095 -0.5686255 0.8225941 -0.001991748 -0.6062343 -0.5940881 0.5287148 -0.7096412 -0.7045633 0 -0.7102836 -0.7039145 0.001311063 -0.5957288 -0.8031857 0 -0.594514 -0.8040826 0.002066195 -0.4978976 -0.6811976 0.5367197 -0.6691342 -0.7431265 -0.004751861 -0.4999917 -0.8660206 -0.004111409 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -3.42374e-7 0 -1 0.1045332 -0.9945194 -0.002032816 0.09126996 -0.9958263 2.60954e-4 -0.1045333 -0.9945202 -0.001565217 -0.09728956 -0.9952561 -2.67026e-4 0 0 -1 0.2544935 -0.9670736 0.001317381 2.88772e-7 0 -1 0.3090285 -0.9510409 -0.004746139 0.2553721 -0.9668429 0 0.2100761 -0.8173572 0.5364656 0.3977167 -0.9175083 0 0.399092 -0.9169086 0.002067625 0.2562518 -0.7955027 0.5490998 0.3428591 -0.776314 0.5289464 0.3006812 -0.9537247 0 -0.990698 -0.135784 -0.008951902 -0.9895266 -0.1443508 0 -0.9936913 -0.1121234 0.002464652 -0.9966835 -0.08128798 -0.003790199 -0.4382127 0.8987713 0.01341319 1.67203e-4 8.38866e-5 1 -0.1882193 0.8684031 -0.458748 -0.9969507 -0.07803511 0 3.29445e-5 -3.58081e-4 1 -1.20363e-4 1.44028e-5 1 -2.69804e-5 -2.78435e-4 1 3.27371e-6 6.08149e-5 1 -1.48517e-7 0 1 -0.04590946 -0.9986324 -0.02501809 -8.52183e-5 -1.17809e-4 1 -6.11768e-5 4.64894e-5 1 0.7957709 -0.605081 -0.02501749 0.04590946 -0.9986323 0.02501887 -5.3424e-5 0.001159965 -0.9999994 6.27668e-4 -7.7117e-4 -0.9999996 0.8948614 -0.4390953 0.08011585 -1.17968e-4 5.93054e-5 -1 -8.37327e-4 -6.47574e-4 -0.9999995 7.58935e-4 -0.001253902 -0.999999 0.9280201 0.3649662 0.07468932 0.8672855 -0.4615274 -0.1865702 0.2576087 -0.9546081 0.149537 4.35469e-4 -7.3698e-4 -0.9999997 -0.001862883 4.89584e-4 -0.9999982 0.9980576 -0.03226095 0.05329442 -0.001723229 0.001213669 -0.9999978 2.95815e-4 -8.93424e-4 -0.9999997 0.3030601 0.9525458 0.02847766 0.1386804 0.9877977 -0.07087576 2.50624e-6 -1.88017e-5 -1 -1.13167e-5 1.2431e-5 -1 0.9263735 -0.3572522 -0.1191766 0.6697205 -0.7419217 0.03204262 0.6154978 -0.7880693 -0.01045715 0.6231148 -0.7821305 0 -8.44906e-6 2.35715e-5 -1 3.47953e-4 -7.50169e-4 -0.9999998 0.5955976 -0.8032817 0.001529216 -0.5716432 -0.6126797 -0.5457542 0.08864945 -0.1909696 -0.9775848 -0.8458405 0.5332918 0.0124033 -0.657127 0.7524555 -0.04466569 1.70954e-4 -7.30965e-4 -0.9999998 -0.6351952 0.7719287 -0.02556061 0.7614336 0.6474894 -0.03124755 -0.2810954 0.9582749 0.05191183 -5.75698e-4 -0.002684891 -0.9999963 -1.68028e-4 6.96637e-4 -0.9999998 0.7275832 0.6816584 0.07723027 0.2820641 0.9534703 -0.1064624 0.8508136 0.5211996 -0.06683748 -0.00168693 -0.001766502 -0.9999971 0.004833817 0.0127803 -0.9999067 0.9465014 0.3177338 0.05639511 0.9935973 0.1025618 -0.0473873 0.9983783 0.05661904 -0.005922496 0.06497198 -0.8578695 -0.5097437 0.0256375 0.01284998 -0.9995888 0.08636045 -0.8445824 -0.5284151 0.4082074 -0.9116936 0.04670596 -1.91827e-4 -1.11934e-4 1 0.9967 0.08114784 -0.002021133 0.9968286 0.07957935 0 -3.42653e-5 3.71075e-4 1 2.91002e-5 2.95624e-4 1 1.37526e-4 -1.03241e-5 1 -2.25152e-5 -7.71967e-5 1 0.09729522 0.9952555 -2.76129e-4 -0.09126776 0.9958264 2.57914e-4 3.42366e-7 0 -1 0.1045025 0.9945234 -0.001562476 0 0 -1 0 0 -1 -0.1045024 0.9945226 -0.002035915 -0.2544975 0.9670726 0.001313745 -0.3090282 0.9510411 -0.004748642 0 0 -1 -0.4999916 0.8660205 -0.004108667 -0.3991001 0.9169051 0.002065598 -0.8354774 -0.5495249 0 -0.3977236 0.9175053 0 -0.5413972 0.8407627 0.002669095 -0.6691401 0.7431302 -0.003036201 -0.6895994 0.7241898 0.001392722 -2.67429e-4 1.91016e-4 1 1.27045e-4 1.16381e-4 1 -0.809022 0.5877764 -0.001570701 -0.813282 0.5818699 -2.76127e-4 -7.20806e-6 -2.40547e-4 1 -1.51751e-7 0 1 -0.8907473 -0.4370609 -0.1246879 -0.9684737 0.2375218 0.07511425 7.1747e-5 3.51422e-5 1 -0.6827134 0.7179098 -0.1360446 -6.65748e-5 1.40042e-4 1 -0.9719562 -0.2351577 0.001397669 -0.9135478 -0.4067284 -0.001566588 -0.9105592 -0.4133785 -2.6855e-4 -3.04852e-4 -1.37794e-4 1 -0.8167863 -0.5769405 2.63989e-4 -3.41909e-4 -2.41235e-4 1 6.74269e-7 0 1 -0.9988203 -0.04848867 0.002670884 -0.9781416 -0.2079184 -0.003037452 0.05813241 -0.998309 0 -0.9934417 0.1143397 0 -0.9936119 0.1128327 0.002067208 -0.9999917 0 -0.004108905 -0.978134 0.2079215 -0.004752516 -0.9647572 0.2631388 0.001306474 -0.812883 0.2267343 0.536482 -0.9649962 0.262264 0 -0.8437305 0.09124028 0.5289556 -0.8170366 0.1758438 0.5491175 0.4010258 0.9160653 0.001733899 0.4049399 0.9143355 0.003783464 -0.9762818 0.2165043 -5.58929e-5 0.4272177 0.9041429 -0.003287553 -0.001756489 -0.002096354 -0.9999964 1.78743e-4 5.31817e-4 -1 0.3068739 0.9516766 -0.0118373 0.8493698 -0.3045855 -0.4310436 0.8192211 -0.1419119 -0.5556417 0.3255628 0.9449515 -0.03279799 5.74481e-4 2.27443e-4 -0.9999998 0.001152694 9.97955e-4 -0.9999989 -0.04720747 0.9950947 0.08693742 1.09624e-5 -8.75965e-6 -1 -0.859049 0.457132 -0.2303591 -9.58359e-6 -2.42911e-5 -1 2.2815e-5 1.66616e-5 -1 -0.8878157 -0.459962 -0.01477587 -0.9085236 -0.4169286 0.02748584 -0.9939912 -0.1052008 0.03023791 -0.3490411 0.9371075 0 -0.8396052 -0.5431973 0 -0.5812889 0.7952132 -0.1724506 -0.4636891 0.8501469 0.2494853 -0.3531019 0.9355806 -0.002877891 5.95054e-6 -2.24441e-6 1 -0.06403136 0.9948243 0.07889658 -1.46395e-6 -4.91844e-6 1 1.18544e-6 -4.28878e-6 1 -0.2332337 0.9722792 0.0165928 -0.04791611 0.9862673 0.1580536 6.0425e-5 2.77037e-7 -1 -3.12585e-5 1.63396e-5 -1 1.72172e-5 3.80687e-5 -1 0.4116072 0.9042853 0.1133481 -9.12769e-6 2.66401e-5 -1 0.4124129 0.9043526 0.109828 0 -3.24362e-6 1 -6.38902e-6 -1.67814e-7 1 -9.03362e-7 -4.35964e-6 1 0.6809284 0.7323346 -0.004769206 0.7526961 0.5823472 0.3071163 0.5450124 0.8382424 0.01764512 0.9961685 0.06924974 0.05341255 0 -2.95058e-6 1 -1.99061e-6 -7.87222e-7 1 0.8427935 0.5268688 -0.1100389 0.9923458 0.09716063 -0.07622128 -2.14105e-6 0 1 1 0 0 -1.36344e-6 0 1 4.89946e-7 0 1 0.9009594 -0.4339033 0 0.9009652 -0.4338915 0 -1.68614e-6 3.06411e-6 1 2.41148e-6 4.84458e-6 1 0.6235007 -0.7818228 0 0.6235076 -0.7818174 0 0 3.97738e-6 1 0.2225232 -0.9749274 0 2.79486e-6 0 1 -0.2313202 0.9727261 -0.01717704 0.539177 -0.8148157 -0.2129877 0.3097955 -0.950782 0.006353378 0.676384 -0.6061103 0.4184916 -3.03415e-6 2.53937e-6 1 0.153966 -0.8873352 0.4346617 -1.16582e-4 -7.06309e-5 -1 7.71166e-6 -2.07035e-6 -1 8.82488e-6 -4.96435e-7 -1 0.833116 -0.5200018 -0.1884568 -0.3081194 -0.9512556 -0.01324188 -0.3929541 -0.9195579 6.35735e-4 0.9776604 -0.2099193 0.01067703 0.9266343 -0.3028649 0.2227594 -0.3976515 -0.9175307 0.003278017 0.9860644 -0.1662787 0.005334734 0.9936512 -0.1076482 -0.03269928 0.8233036 -0.1427057 0.549369 -0.4281082 -0.9037253 -0.002019464 0.8176261 -0.2278998 0.5287244 0.9650143 -0.2621975 0 0.9647814 -0.2630502 0.001306295 0.993614 -0.1128145 0.002067267 0.9934444 -0.1143172 0 0.8388711 -0.09057307 0.536742 0.9781298 -0.2079415 -0.004747986 0.9999917 0 -0.004107832 -2.10565e-7 0 -1 0 0 -1 0 0 -1 0.9988202 0.04848897 0.002671122 0.9781373 0.2079383 -0.003038108 0 0 -1 0.971958 0.2351507 0.001397252 0.9135427 0.40674 -0.001566588 0 0 -1 0.9105592 0.4133785 -2.70826e-4 0.8167863 0.5769405 2.59438e-4 0.8090264 0.5877687 -0.002038955 0.6691149 0.7431439 -0.004749834 0.7102381 0.7039603 0.00131148 0.5957291 0.8031856 0 0.594527 0.804073 0.002061307 0.6027899 0.5906304 0.53647 0.560828 0.619648 0.5490978 0.5008718 0.6850787 0.5289562 0.7095961 0.7046087 0 0.5675582 -0.8233198 -0.004713058 0.5675825 -0.8233166 0 -0.8945252 0.4470175 0 -0.8927152 0.4505845 -0.005756974 -0.8902123 0.4555347 0.003222465 -0.4856612 -0.806882 -0.3362661 -0.6722816 -0.7375493 0.06370627 -1.33665e-7 0 1 -5.69445e-7 0 1 1.48984e-7 0 1 0.4573794 0.8892678 0.002673208 0.3090324 0.9510468 -0.00303477 0.2823703 0.9593045 0.001401662 0.5000035 0.8660137 -0.004111468 5.53705e-7 0 1 0.5690298 -0.8223133 0.002492845 0.001488089 3.59984e-4 0.9999989 -2.64352e-4 5.68951e-4 0.9999999 0.002056002 9.97821e-5 0.999998 -0.06736809 0.9977282 0 -0.06147551 0.9980921 -0.005747139 -3.00021e-4 -5.83194e-4 0.9999999 -0.8499114 0.1470504 -0.5059909 -0.8571231 0.2900024 -0.4257215 -0.03011232 0.9995445 0.002048134 0.001758277 0.002097964 -0.9999963 0.0458368 0.9989467 0.002107799 -0.06264126 0.9978623 0.01862478 0.9135409 -0.4067417 -0.002045571 1.23342e-7 0 -1 0.9080184 -0.4189304 2.62473e-4 0.8090138 -0.5877876 -0.001566648 0.8132858 -0.5818645 -2.68544e-4 3.51989e-4 -1.62592e-4 1 2.52059e-4 -1.8004e-4 1 0.669121 -0.7431473 -0.003040194 0.6896145 -0.7241753 0.001396894 -1.74612e-7 0 1 0.5414068 -0.8407565 0.002666831 0.5000106 -0.8660095 -0.004111528 -0.429534 -0.9030508 0 -0.3255557 -0.9449542 -0.03278791 -1.76625e-4 -5.29434e-4 -1 0.8484722 0.5292372 -0.001739799 0.8878104 0.4599623 -0.01507782 0.9009615 0.4338991 0 0.9009673 0.4338871 0 -0.8632221 0.5048233 -0.001046359 0.675656 0.7372171 0 -0.8669725 0.4982941 -0.00785917 0.9892486 0.1462407 -9.48855e-4 0 -6.70198e-7 1 0.2225371 0.9749243 0 -0.2225213 0.9749279 0 -0.2225212 0.9749279 0 -0.3409982 0.7717705 0.5367407 -0.8345581 -0.5509003 -0.004661142 -0.8420391 -0.5394122 -0.002222239 -0.2880333 0.7843635 0.5493732 -0.04582995 -0.998947 0.002102375 0.04994398 -0.9986091 0.01690036 0.02504855 -0.9996816 0.003051996 0.9934431 -0.09445691 0.06441259 0.06002289 -0.9981932 -0.002762436 0.06001561 -0.9981936 0.002791702 -0.1385286 -0.9878123 -0.07097101 -0.3194342 -0.9468176 0.03870582 -4.12619e-6 -3.24319e-5 -1 -0.9341267 0.3397072 -0.1095741 -0.9263727 0.3572601 -0.1191596 -1.82427e-5 -7.44437e-7 -1 -9.26068e-4 4.27309e-4 -0.9999995 -0.6697291 0.7419139 0.03204292 -0.001441121 8.95949e-4 -0.9999986 -0.001499831 0.001845359 -0.9999973 -3.62231e-4 7.79023e-4 -0.9999997 0.8449759 -0.5346682 0.01207631 0.6571279 -0.7524536 -0.04468262 0.6637908 -0.7462041 -0.05060869 -9.43523e-5 2.00642e-4 -1 0.8677786 -0.4968838 -0.008175075 0.5330522 0.6383095 -0.5553527 0.8774972 -0.4795783 0.001815557 0.5854474 0.8093642 0.04670315 0.8943342 -0.4473939 0.002305328 0.8943855 -0.4472727 -0.004662752 0.6923883 0.5822319 -0.4261507 0.8936488 -0.448767 0 -6.74262e-7 0 1 1.38424e-7 0 1 2.03815e-4 -1.40439e-4 1 -0.4573818 -0.8892665 0.002671718 -0.3090324 -0.9510468 -0.00303477 -0.2823756 -0.9593029 0.001402258 5.1678e-6 1.30756e-5 -1 -0.4951004 -0.8608331 0.1176516 -0.8504279 -0.5179906 -0.09196913 -4.83691e-5 2.26033e-5 -1 -3.13261e-5 -3.60377e-6 -1 0.03490424 -0.9933302 -0.1098956 -0.4033583 -0.9117754 -0.07725107 2.93285e-5 -4.62655e-5 -1 0.8632252 -0.504819 0 -3.74419e-4 1.73031e-4 1 0.4295612 0.9030379 0 -0.9135419 0.4067396 -0.00204432 -0.9080392 0.4188854 2.5641e-4 0 0 -1 -1.23346e-7 0 -1 -0.7336246 -0.6792685 0.01972877 -0.8346306 -0.5508056 0.002293884 -0.255377 0.9668416 0 -0.2114077 0.8220445 0.5287247 0.9460851 0.3099771 -0.09400743 0.8461593 0.5329297 8.24575e-4 0.004060089 0.001116275 -0.9999912 -0.29981 0.7666481 -0.5677718 -0.9773702 -0.208956 0.03293931 0.8344436 0.5510933 -1.12256e-4 0.8344316 0.5511047 -0.002770841 0.834392 0.5511714 0 -0.8090105 -0.5877907 -0.0020383 -0.5673608 0.8234694 0 -1.7306e-5 1.02866e-5 -1 -1.56514e-6 1.75676e-6 1 -1 0 0 -0.8652089 -0.4995098 -0.04363238 0.4995181 -0.8652053 -0.04360669 -0.4995195 0.8652035 -0.0436272 0 0 -1 -6.88231e-7 0 -1 0.4815452 0.2774597 0.8313426 0.4644477 0.2636201 0.8454542 -0.8789569 -0.4755844 0.03541767 0.2991128 0.0434944 0.953226 -0.4877424 -0.2811602 0.8264722 -0.8706822 -0.4906062 0.03490102 -0.9058157 0.4132574 0.09336167 0.0834766 0.9955065 0.04470556 -0.02142226 -0.007545709 0.999742 0.01854437 0.005320608 -0.9998139 0.03536272 -0.9949883 0.09352988 0.8997605 -0.4333643 0.05124878 0.4316022 0.2260087 -0.8732924 0.4108505 0.2594241 -0.8740143 0.4062597 0.2657766 -0.8742516 0.4160403 0.2847127 -0.8636257 0.4431941 0.2305881 -0.8662611 0.4333462 0.2330601 -0.8705712 0.4376259 0.2486709 -0.864087 0.4330065 0.2449221 -0.8674784 0.4372848 0.2442796 -0.8655112 0.1201551 0.0679906 -0.9904242 0.4336895 0.2552257 -0.8641605 0.4412193 0.2736135 -0.8546702 0.1074956 0.07297676 -0.9915236 0.432383 0.2782172 -0.8576946 0.4104228 0.2640315 -0.8728348 0.3716189 0.2396142 -0.8969306 0.4041587 0.2773844 -0.8716156 0.4201603 0.2795026 -0.863333 0.4502405 0.2880617 -0.8451651 0.4396162 0.2890596 -0.8504012 0.4229937 0.257642 -0.8687329 0.4313442 0.2524741 -0.8661403 0.4310526 0.2530952 -0.8661043 0.1156941 0.0522055 -0.9919121 0.460325 0.2338252 -0.8564035 0.1261899 -0.1934136 -0.9729683 0.001134276 0.001315116 -0.9999985 0.02343714 0.02381241 -0.9994417 -0.04523468 0.01940882 0.9987878 -0.001108586 -6.35975e-4 -0.9999993 0.04553663 0.004847705 -0.998951 -0.002845585 -0.001497805 -0.9999949 0 0 -1 -0.001136124 -7.05692e-4 -0.9999991 0.07857984 0.05855709 -0.9951866 0 0 -1 -0.006815493 -0.003648459 -0.9999701 0.001250863 2.93638e-4 -0.9999992 0.05633205 0.03330135 -0.9978566 0 0 -1 -9.63198e-7 0 -1 0.04986584 0.03602612 -0.998106 6.54804e-4 -3.16458e-4 -0.9999998 0.09652203 0.0533747 -0.9938987 0 0 -1 -4.80843e-7 0 -1 -0.002251684 -0.001398444 -0.9999965 7.88906e-4 -1.63216e-4 -0.9999997 0.1014509 0.0530312 -0.9934262 -1.20208e-7 0 -1 4.14253e-7 0 -1 -3.97268e-5 -1.86376e-5 -1 -7.00279e-4 -4.00589e-4 -0.9999998 2.28533e-4 -6.14266e-5 -1 0.006000757 0.0141021 -0.9998826 7.56475e-7 0 -1 0.002409279 0.001289784 -0.9999963 3.17371e-5 1.40568e-5 -1 -8.21761e-6 -3.47334e-6 -1 1.64261e-6 2.14441e-7 -1 6.44452e-6 4.86551e-6 -1 3.75543e-6 2.37524e-6 -1 0.07848048 0.05612975 -0.9953343 0.02159237 -0.004096627 -0.9997586 -0.8660253 -0.5000004 6.59519e-5 0.266618 -0.4941667 -0.8274746 0.3217155 -0.5562009 -0.7662504 0.9694637 0.1375418 0.2030334 -0.603946 -0.3373301 0.7221202 -0.723925 -0.4304953 0.5390794 0.7728928 0.3359419 0.5383121 -0.2851935 0.4875764 0.8251873 -0.2893049 0.4916641 0.8213216 -0.08874607 -0.9956579 0.02810114 -0.3216926 -0.9468349 -0.004199147 0.005351305 0.003078758 0.9999811 -0.7467944 0.3021682 0.5924463 -0.5338537 0.3014902 0.7900025 0.09169793 0.6797907 0.7276511 5.47089e-4 0.5158458 0.8566814 0.5323445 -0.399746 0.7461987 -0.09507167 -0.6785532 0.7283729 -0.04137253 -0.9983267 0.04040133 -0.8695871 -0.4928962 0.02952563 -0.8616657 -0.5059052 0.03990352 0.01128131 -0.01995253 0.9997373 -0.05046939 0.1182042 0.991706 0.05046981 -0.1182051 0.9917058 0.5217532 0.2900619 0.8022705 -0.2754251 0.6020721 0.7494333 0.867796 0.496203 0.02669906 0.901745 -0.4305329 0.03869831 0.9118927 -0.410421 0.002551972 -0.04548162 -0.9672161 -0.2498492 -0.00269258 0.001669764 0.9999951 -0.07375025 -0.7167205 0.6934499 0.434494 0.2715865 0.8587525 0.04437059 0.9154014 0.4000896 0.1031084 0.9940563 0.03493857 0.8618079 0.5062664 0.03132975 0.8661433 0.4983388 0.0381354 -0.009883642 -0.006516396 0.99993 -0.7920708 -0.436729 0.4264878 -0.5944477 -0.3527193 0.7226486 0.7613872 0.502166 0.4100233 0.6491114 0.4532213 0.6109377 -0.09854054 -0.9944156 0.03778213 -0.4568784 -0.8891466 0.02608537 -0.8654725 -0.4997413 0.03487306 -0.03203439 -0.01408338 0.9993876 9.34493e-4 -7.99322e-4 -0.9999994 -0.8932889 -0.4477598 0.0393213 -0.4560095 0.8855669 0.08846837 -8.6701e-4 -4.01963e-4 -0.9999996 0.8252616 0.5635875 0.03623098 0.8534603 0.5198004 0.03759253 0.5583903 -0.8250546 0.08651804 0.03620153 -0.004865586 -0.9993327 0.01798236 -0.1064544 -0.994155 0.135869 -0.5164703 -0.8454573 0.3075464 -0.5352053 -0.7867467 0.3371308 -0.5380111 -0.7725845 0.3249132 -0.549479 -0.7697431 -0.9556228 0.2943713 0.01142978 0.9850097 -0.1687971 -0.03554838 0.9705278 -0.2384819 0.03467106 0.7179325 -0.6954032 -0.03142142 -0.2771871 0.9607931 -0.00664097 0.6146837 -0.7190986 -0.3241317 -0.702389 0.7045328 0.1014067 0.943912 0.3301934 0.001602768 -0.9687454 0.2382317 0.06912422 -0.4479901 -0.8831373 0.1391883 -0.9916727 0.0913828 -0.09074431 -0.5295008 -0.8216005 0.2111908 -0.2583429 -0.9658135 -0.02152281 0.8657218 0.4985346 -0.0446012 0.8652042 0.4995232 -0.04357045 -0.8651658 -0.4995967 -0.04349029 -2.12224e-4 0 -1 -4.38388e-6 -5.57058e-6 -1 0 2.17661e-7 -1 -7.77363e-6 0 -1 4.97902e-6 2.01112e-6 -1 -0.7987681 0.5045724 -0.3276833 -0.7668988 0.5447477 -0.3392879 -0.4656397 0.8064878 -0.3643587 0.1712681 0.9452882 -0.2776644 -2.55653e-6 0 -1 4.19922e-7 0 -1 0.8660088 0.5000289 4.4677e-6 0.8660253 0.5000004 0 0.8660258 0.4999994 0 -0.9986412 0.01686215 -0.04930973 0.2436313 -0.9698632 -0.003028929 -0.2945013 -0.8886297 -0.3515768 -0.1426315 0.5150332 -0.8452203 -0.2593873 -0.9144827 -0.3105475 -0.8322572 0.5542246 0.01352876 -0.9906371 -0.1352281 -0.01875281 -0.1708362 0.9353127 -0.3098472 -0.7912434 0.4410969 -0.4235181 -0.8660156 -0.5000171 -1.31526e-5 -0.8660474 -0.499962 -3.71457e-6 -0.8525303 -0.5226733 0.002234101 -0.866025 -0.5000007 2.54069e-7 -0.8662376 -0.4996323 -8.58092e-5 0 0 -1 -0.001310288 7.14885e-4 -0.9999989 1.81903e-7 0 -1 -2.52335e-7 0 -1 -0.4998481 0.866113 -4.10604e-4 -0.5000007 0.8660252 0 -0.1151512 0.1698517 -0.9787189 0.65499 0.7554464 0.01699972 -0.1352362 0.9906017 -0.02047824 -0.200355 0.9797234 0 0.1605964 0.7494594 -0.6422768 0.9159014 0.4014036 0 0.9970012 0.07733982 0.002673745 0.917935 -0.3967303 8.41238e-4 0.9659209 0.2588065 -0.004002153 -0.1013371 0.1576222 -0.9822862 0.337242 -0.5665602 -0.7518494 0.3967136 -0.6969746 -0.5973648 0.4779273 -0.8315737 -0.2829682 0.500006 -0.866022 0 0.5000029 -0.8660237 1.91116e-7 0.4999998 -0.8660256 -9.9014e-7 0.5 -0.8660255 0 0.5000078 -0.8660209 0 0.129409 -0.2241423 -0.9659263 0.5078728 -0.8558422 -0.09797596 0.1782914 -0.2212725 -0.9587757 -0.8660228 -0.5000045 0 0.8660251 0.5000006 -1.27553e-6 0.8559609 0.5169063 -0.01178795 1 9.39654e-5 7.15134e-5 -0.4870339 -0.873383 0 -0.4969908 -0.8677519 -0.002639293 -0.5000148 -0.866017 1.09254e-5 -0.6983363 0.1958293 0.6884601 -0.9229969 0.2258288 0.3115737 0.4716756 0.3288131 0.8181712 0.4756568 0.272215 0.8364508 0.3240898 0.201206 0.924382 0.4135348 0.1816208 0.8921899 0.4959334 0.2862858 0.8198114 0.3635755 0.1581427 0.9180435 0.4979397 0.2875731 0.8181429 0.4904524 0.3530038 0.7967715 0.4981334 0.2876487 0.8179984 0.5023072 0.289914 0.8146395 0.4969056 0.2868874 0.8190119 0.5784916 0.2791746 0.7664262 0.4967641 0.2868056 0.8191264 0.4136661 0.2350022 0.8795762 0.4961093 0.2864428 0.8196501 0.432783 0.2465769 0.8671211 0.4527456 0.2638372 0.851711 0.4742485 0.2572581 0.8419659 0.5024815 0.3017396 0.8102256 0.5789982 0.1618301 0.7991072 0.5024896 0.2902175 0.814419 0.3710706 0.4150069 0.8307082 0.4721646 0.2244923 0.8524457 0.5126185 0.397395 0.7611174 0.5042621 0.3267502 0.7993459 0.5001128 0.2893335 0.8161945 0.3946857 0.2942228 0.8704346 0.5649422 0.3190542 0.76095 0.8463555 0.3896322 0.3631379 0.00209254 -0.04371839 0.9990418 -0.6465537 -0.3731066 0.665402 0.4743337 -0.1904762 0.8594919 -0.4987426 0.8421975 0.2048398 0.8002388 -0.1194828 0.5876579 0.2174777 0.06529211 0.973879 -0.7669156 -0.5481269 0.3337625 -0.05553853 -0.01815772 0.9982914 -2.54252e-7 0 1 -0.005190789 0.01084828 0.9999277 0.003156602 -0.01990181 0.999797 -3.47186e-4 -1.77881e-4 1 -3.29247e-4 -1.41432e-4 1 0.003326833 0.002002477 0.9999925 0.006747901 0.004106462 0.9999689 0.003345489 0.001954436 0.9999925 0.004886448 0.002793967 0.9999842 -3.10851e-4 -1.87021e-4 1 -0.008009493 -0.01555693 0.999847 -2.04282e-4 -7.91613e-4 0.9999998 2.60247e-4 1.7805e-4 1 -8.90184e-4 -0.002707123 0.999996 -8.02975e-4 -4.39523e-4 0.9999996 -0.001086711 -3.78997e-4 0.9999994 -0.001540064 -8.6725e-4 0.9999985 -3.23533e-4 -1.81118e-4 1 -1.09392e-4 2.39696e-4 1 -5.22043e-4 -2.8857e-4 0.9999998 -3.18723e-4 -1.71408e-4 1 0.07158255 0.09707641 0.9926995 -0.002649545 -0.001172363 0.9999959 -0.003410518 -0.002012312 0.9999921 0.06536412 -0.02311909 0.9975937 -5.09562e-4 -2.58987e-4 1 0.04306888 0.02086222 0.9988543 0.09756875 -0.1180269 0.9882054 -6.44797e-5 3.09152e-5 1 0.003766 0.001652181 0.9999916 2.13369e-4 4.50505e-4 0.9999999 0.005628585 0.003357052 0.9999786 -0.02578473 0.01634234 0.9995339 -0.1742203 -0.1544502 0.9725186 0.003302872 0.002029418 0.9999926 0.002815246 0.001647174 0.9999947 2.15515e-4 1.37954e-4 1 -3.13629e-4 2.97521e-4 1 3.51921e-4 -3.44503e-4 -0.9999999 0.002157926 9.63097e-4 0.9999973 6.28293e-4 3.70892e-4 0.9999998 1.93842e-4 1.21668e-4 1 -1.23386e-4 7.12213e-4 0.9999998 7.39188e-4 -0.001643478 0.9999985 -0.08460479 -0.1170235 0.9895189 5.76465e-4 3.22203e-4 0.9999999 0.005671501 0.002967536 0.9999796 -9.61876e-4 2.8273e-4 0.9999996 -3.47704e-4 5.97312e-4 0.9999998 -0.1024815 -0.04067414 0.993903 0.003247559 0.001825869 0.9999932 6.62142e-5 2.1731e-5 1 -0.008351385 -0.009572029 0.9999194 -0.0874595 -0.02821397 0.9957686 0.00105226 7.02607e-4 0.9999992 7.40886e-4 0.001213252 0.999999 -1.41632e-4 -4.5835e-4 1 -0.003039538 -0.001737415 0.9999939 0.006551861 -0.0104506 0.999924 -5.70989e-4 -0.001483201 0.9999988 2.54089e-4 7.06131e-6 1 2.05511e-4 1.41417e-4 1 -5.44461e-4 -1.87521e-4 0.9999999 -1.97666e-4 -1.18043e-4 1 0.00238955 0.001284837 0.9999964 0.006551325 -0.01045018 0.999924 -6.44917e-4 -0.001496016 0.9999987 -6.6503e-4 0.001935124 0.9999979 0.002280592 0.001435577 0.9999964 1.22534e-4 -5.36228e-5 1 -0.002920806 -0.001806557 0.9999942 -7.02667e-4 -4.20048e-4 0.9999998 2.11652e-4 1.8495e-4 1 1.55181e-4 -8.76444e-4 0.9999997 -0.09441202 -0.9691594 0.2276323 -0.794018 -0.4801284 0.3728435 0.1158213 0.06682044 0.99102 0.7932326 0.4484209 0.4119476 0.8516715 0.4931527 0.1773588 0.8660261 0.4999987 5.30323e-5 0.8652024 0.4995224 -0.04361748 0.8652032 0.499521 -0.04361736 0.8652013 0.4995238 -0.04362022 0.8652036 0.4995202 -0.04361528 0.8652002 0.499526 -0.04361617 0.8652039 0.49952 -0.04361432 0.865202 0.4995227 -0.04361993 0.8652038 0.4995208 -0.0436064 0.8652004 0.499526 -0.04361414 0.8652009 0.4995234 -0.04363459 0.8652096 0.4995104 -0.04361087 0.8651925 0.499536 -0.04365569 0.8652097 0.4995104 -0.04360657 0.8652083 0.4995115 -0.04362392 -0.8651978 -0.4995301 -0.04361706 -0.8651973 -0.4995311 -0.04361641 -0.8652012 -0.4995243 -0.04361724 -0.8652009 -0.4995244 -0.0436204 -0.8652011 -0.4995245 -0.04361778 -0.8652026 -0.4995222 -0.04361492 -0.8652012 -0.4995235 -0.04362505 -0.8652002 -0.4995261 -0.04361522 -0.8652014 -0.4995227 -0.04363197 -0.8652005 -0.4995265 -0.0436061 -0.8652055 -0.4995162 -0.04362601 0.8652032 0.4995198 -0.04362893 -0.8652021 -0.4995231 -0.04361361 6.58135e-4 -0.001139521 -0.9999992 0.4995213 -0.8652027 -0.04362225 0.03223174 0.01331239 -0.9993919 3.44044e-7 0 -1 -0.4995203 0.8652043 -0.0436027 -0.4995242 0.8652016 -0.04361081 0.4995167 -0.8652057 -0.04361695 -0.4995067 0.8652121 -0.04360359 -0.4995195 0.8652036 -0.04362535 2.179e-7 0 -1 4.35798e-7 0 -1 0.4995257 -0.865199 -0.04364341 0.4995151 -0.8652057 -0.04363578 -0.008851468 -0.05363488 -0.9985214 0.02994424 0.01728832 -0.9994021 0.02177476 -0.03771495 -0.9990513 -0.499527 0.8652004 -0.0436033 -0.4995247 0.8652017 -0.04360306 0.4995293 -0.865199 -0.04360347 0.4995273 -0.8651999 -0.04360967 0.4995356 -0.8651943 -0.04362499 0.02994436 0.01728808 -0.9994021 0.02177405 -0.03771507 -0.9990513 -0.4995086 0.8652117 -0.04358839 -0.499539 0.8651919 -0.04363435 -0.4995246 0.8652015 -0.0436083 -0.499509 0.8652099 -0.04361957 2.17898e-7 0 -1 -2.17892e-7 0 -1 0.4995154 -0.8652077 -0.04358899 0.0299443 0.01728796 -0.9994021 -0.4995241 0.8652017 -0.04361033 -0.4995238 0.865202 -0.04360717 -2.17894e-7 0 -1 0.4995343 -0.8651955 -0.04361402 0.4995271 -0.8651993 -0.04362177 0.4995267 -0.8651999 -0.04361373 -0.008851408 -0.05363506 -0.9985215 0.02994441 0.01728844 -0.9994021 0.0217747 -0.0377146 -0.9990513 -0.4995243 0.8651998 -0.04364371 0.4995307 -0.8651979 -0.04360866 0.499513 -0.865207 -0.04363137 0.4995077 -0.8652123 -0.04358816 0.02994447 0.0172882 -0.9994021 0.02177488 -0.03771483 -0.9990513 -0.4995253 0.8652006 -0.04361653 -0.4995284 0.8651991 -0.04361367 -2.17892e-7 0 -1 0.4995281 -0.8651987 -0.04362416 -0.008851408 -0.0536347 -0.9985215 -0.4995235 0.8652005 -0.04364073 -0.4995294 0.8651975 -0.04363453 -0.4995306 0.8651966 -0.04363745 2.17896e-7 0 -1 0.4995245 -0.8652005 -0.04362797 0 0 -1 -0.008851587 -0.05363488 -0.9985214 0.02994465 0.0172885 -0.9994021 0.0217747 -0.03771471 -0.9990513 -0.499525 0.8652008 -0.04361641 -0.4995205 0.865203 -0.04362434 -0.4995234 0.8652017 -0.04361939 4.35788e-7 0 -1 0.4995217 -0.8652026 -0.04361921 0.4995287 -0.8651989 -0.04361408 0 0 -1 -0.4995248 0.8652008 -0.04361945 4.35787e-7 0 -1 0.4995247 -0.8652011 -0.04361569 0.4995247 -0.865201 -0.04361885 0.02177459 -0.03771483 -0.9990513 -0.4995232 0.8652018 -0.04361921 -0.4995231 0.8652017 -0.04362249 0.4995238 -0.8652017 -0.04361379 0.4995274 -0.8651992 -0.04362183 0.02994453 0.01728856 -0.9994021 -0.4995241 0.8652015 -0.04361337 -0.4995256 0.8652005 -0.04361492 0.4995231 -0.8652016 -0.04362177 0.4995247 -0.8652008 -0.04361939 -0.008851706 -0.05363458 -0.9985215 0.02994465 0.01728844 -0.9994021 -0.4995218 0.8652027 -0.04361659 -0.4995239 0.8652014 -0.04361945 -0.4995237 0.8652014 -0.04362189 -0.499525 0.8652005 -0.04362255 2.17895e-7 0 -1 -0.104842 -0.03678643 -0.9938083 2.0286e-7 0 -1 1.3955e-5 -2.05413e-4 -1 7.69318e-4 4.43846e-4 -0.9999997 0.4995237 -0.8652014 -0.04361933 0.4995234 -0.8652016 -0.04362028 0.4995238 -0.8652016 -0.04361569 -0.4995224 0.865202 -0.04362183 -0.4995225 0.865202 -0.04362183 -0.02994453 -0.0172885 -0.9994021 -0.02994441 -0.01728856 -0.9994021 -1.72861e-7 0 -1 0.8002492 0.4620243 -0.3822757 0.800288 0.4620352 -0.3821814 0.8002466 0.4620277 -0.3822772 0.8002237 0.4620152 -0.3823403 0.8002396 0.4620199 -0.3823015 0.8002466 0.4620242 -0.3822813 0.8002398 0.4620174 -0.3823041 0.8002398 0.462017 -0.3823043 0.8002437 0.4620238 -0.3822879 0.8002445 0.4620214 -0.3822894 0.8002463 0.4620226 -0.3822839 -0.8002263 -0.4620114 -0.3823395 -0.8001956 -0.4619848 -0.3824357 -0.8002717 -0.4620412 -0.3822083 -0.8002039 -0.4619899 -0.3824123 -0.8001977 -0.4620023 -0.3824101 -0.8002249 -0.4620118 -0.3823422 -0.800239 -0.462021 -0.3823012 -0.8002493 -0.4620238 -0.3822761 -0.800239 -0.4620204 -0.3823019 -0.8002464 -0.4620219 -0.3822847 -0.8002468 -0.4620227 -0.3822829 -0.8002443 -0.4620282 -0.3822814 0.4995363 -0.8651939 -0.04362469 0.4995241 -0.8652004 -0.04363447 -0.07737314 -0.05794674 -0.9953168 0.5524642 -0.6067758 -0.5714949 0.5534978 -0.6053839 -0.5719708 0.5822266 -0.5771545 -0.5726299 0.6094686 -0.5613036 -0.5598986 0.6946377 -0.4407632 -0.5685123 0.7888357 -0.2155762 -0.5755565 0.8168904 -0.04877591 -0.5747269 0.7412111 0.349583 -0.5730602 0.688333 0.4399707 -0.5767352 0.6718214 0.4775654 -0.5662043 0.4575372 0.6846072 -0.5674265 0.4339421 0.6946382 -0.5737352 0.337657 0.7479151 -0.5714988 0.3212052 0.7589132 -0.5664609 0.174063 0.795507 -0.5804057 0.1948 0.7938118 -0.5761213 0.02532553 0.8218207 -0.5691831 -0.1566991 0.798073 -0.581829 -0.2771992 0.7704061 -0.5741388 -0.18642 0.7978335 -0.5733318 -0.3067389 0.7799142 -0.5455688 -0.4003498 0.693461 -0.5990259 -0.5345824 0.6210846 -0.573128 -0.5977616 0.5602465 -0.5734151 -0.645047 0.5070748 -0.5716552 -0.548624 0.6087397 -0.5731037 -0.2083489 0.7928547 -0.5726886 -0.2438468 0.7859329 -0.5681973 -0.2269582 0.7905402 -0.5688024 -0.126268 0.8134543 -0.5677575 -0.7221816 0.3878206 -0.5727557 -0.7254122 0.3775767 -0.575511 -0.7877065 0.2162902 -0.5768336 -0.8143783 0.04564613 -0.5785366 -0.7959403 -0.2148586 -0.5659637 -0.7324747 -0.3699297 -0.5715181 -0.6917165 -0.4355257 -0.5760604 -0.5976553 -0.5681381 -0.5657097 -0.5678516 -0.5899633 -0.5740104 0.1267797 -0.8108247 -0.5713933 0.1796931 -0.8090922 -0.5595359 -0.816316 0.101081 -0.5686923 -0.8214967 -0.05066955 -0.5679577 0.1566799 -0.7980844 -0.5818185 0.1813521 -0.8066179 -0.5625646 0.6215041 -0.5408847 -0.5667243 -0.3175398 -0.7842934 -0.5329656 -0.4657743 -0.6839095 -0.5615356 -0.2494066 -0.782813 -0.570088 0.82048 -0.03306204 -0.5707184 -0.810992 -0.5850495 -0.003038108 -0.7198925 -0.6940785 0.003154575 -0.5642424 -0.8256034 0.003112673 -0.3313939 -0.943488 -0.00290966 0.8824185 -0.4704586 -0.002557873 0.9590583 -0.2831978 -0.002497494 0.9930179 0.11794 -0.002376794 0.7476322 0.6641091 -0.002270579 0.5986725 0.8009912 -0.002120256 -0.1900506 -0.9817697 0.003021597 0.01293623 -0.9999119 0.002973318 0.215837 -0.9764251 0.002929687 0.4091657 -0.9124556 0.002893567 0.585248 -0.8108496 0.002825796 0.7372981 -0.675562 0.0027588 0.8590191 -0.5119361 0.002735316 0.9450754 -0.326842 0.002643942 0.9917057 -0.1285037 0.002586901 0.9971659 0.07519257 0.002530276 0.9612081 0.2758137 0.002470672 0.7725163 0.6349906 0.002350032 0.4572865 0.8893167 0.002216398 0.2674294 0.9635752 0.002139091 0.066509 0.9977838 0.002067863 -0.1478661 0.9890049 0.002245903 -0.5432124 0.8395766 -0.005627393 -0.6175677 0.7865128 0.00281763 -0.7010908 0.713055 -0.004931688 -0.7795788 0.6262853 0.00487715 -0.8302987 0.5573092 -0.003244876 -0.8972027 0.4416063 0.003372311 -0.9998527 -0.016869 -0.003162801 -0.9987735 0.04940056 0.003328263 -0.9360737 -0.3517892 0.003248155 -0.5916712 -0.3677175 -0.7174323 -0.7834939 -0.4523444 -0.4260541 -0.8438721 -0.4927298 -0.212361 0.6143829 0.367795 -0.6980405 0.8331327 0.4810086 -0.2729847 0.7942973 0.4555614 -0.4019399 -0.08281463 -0.04167401 0.9956933 0.02526879 0.998619 0.04606133 0.02060759 0.01234537 0.9997115 -0.1116692 0.02556592 0.9934166 -0.120837 -0.04059916 0.9918419 0.05085933 0.0543735 0.9972246 0.5346179 0.00896424 0.8450465 0.6928531 0.4243985 0.5829585 0.3462801 0.1766658 0.9213466 0.1118413 0.9936958 -0.007757127 0.6888652 0.4036018 0.6021383 0.4109159 0.2119115 0.8867027 -0.6437498 0.3232333 0.6936184 -0.04310792 0.9904957 0.1306143 0.06416648 0.947074 0.3145371 -0.03326338 -0.9984648 0.04428952 0.2008359 0.146821 0.96856 0.03042888 0.05545699 0.9979974 0.0177443 0.07873332 0.9967378 -0.01962578 -0.01237821 0.9997308 -0.04116588 -0.008149802 0.9991192 0.2999511 0.9527753 0.04741948 0.8136057 0.5544378 -0.1750563 0.9837487 0.1523566 0.09500449 0.9787637 0.2018852 -0.03555184 0.3172215 -0.2930291 0.9019449 -0.6999053 -0.402193 0.5902317 -0.532116 -0.2696604 0.8025808 -0.04769039 -0.2088111 0.9767925 -0.2344368 -0.5306084 -0.8145515 -0.6517673 -0.369562 0.6622865 -0.04238921 -0.02876585 0.998687 -0.8646269 -0.5008447 -0.03968763 -0.728807 -0.3182795 0.6062496 0.3348072 -0.9415459 0.03735911 0.8094795 -0.567071 -0.1522288 0.2187385 0.9674444 0.1272981 -0.9570748 0.22271 0.1854946 -0.2981048 0.9535772 -0.04271292 -0.8827878 0.4553571 0.11548 0.7524397 -0.6482709 -0.1165305 0.0671162 0.9521911 0.2980399 0.8011952 -0.2856962 -0.5257985 0.9113348 0.1041995 -0.3982607 -0.3588085 0.9304201 -0.07466608 0.2931262 -0.9542064 -0.05972695 0.1484838 0.9724644 -0.1796262 0.09635031 0.9942457 0.04681974 0.9784607 0.2036477 -0.0337975 -0.8388001 -0.4459202 -0.3123614 -0.929363 0.3607684 -0.07829862 -0.9816596 -0.0809409 -0.1726065 0.9281839 0.3423236 -0.1459088 0.9763209 -0.2050404 -0.0689634 0.8573956 -0.4982621 -0.1288717 0.09779298 0.809179 0.5793668 0.07689785 0.8242043 0.5610473 0.6238702 0.4907978 0.6081971 0.8449293 0.1995799 0.4962483 0.8174877 0.07940351 0.5704463 0.8154628 0.08138614 0.5730592 0.6698604 0.6782112 0.3021865 -9.36093e-7 0 -1 -1.17378e-6 2.40073e-6 -1 0 2.65429e-6 -1 -0.4650417 0.1236921 -0.8766052 -0.04258555 -0.02089393 -0.9988744 0.01452249 -0.05027097 -0.9986301 0.05014801 -0.01781445 -0.9985829 -2.38543e-4 -2.24174e-5 -1 0.001001119 0.001354753 -0.9999986 5.31419e-4 -2.98575e-5 -1 0.05862802 0.07758182 -0.9952607 -0.4295338 -0.7066732 0.5622398 -0.1220812 -0.8095391 0.5742321 -0.05064916 -0.7645798 0.6425361 0.06260162 -0.8063845 0.5880692 2.94669e-5 1.38774e-5 -1 2.75179e-5 2.33946e-5 -1 -1.04875e-6 -2.40022e-6 -1 0.001470386 5.49751e-4 -0.9999988 1.20654e-4 3.99106e-5 -1 -0.001529872 -0.002080798 -0.9999967 0.05389791 0.02721554 -0.9981756 -0.01618957 0.06741207 -0.9975939 -0.01978212 0.183338 -0.982851 0.003641068 0.00303936 -0.9999888 -0.05857127 -0.07750898 -0.9952698 1.1015e-4 4.8962e-5 -1 0.0433191 -0.9970678 0.06308162 0.8776147 -0.4373054 -0.1963585 0.6813664 0.7142037 -0.1601658 0.946654 -0.2767938 0.1650193 -3.57882e-4 -3.78156e-4 -1 7.71605e-4 -8.53888e-4 -0.9999994 0.005364656 0.005641639 -0.9999697 0.001304745 -8.59557e-4 -0.9999988 -2.07492e-4 0.003146767 -0.9999951 -0.6813804 -0.7141945 -0.1601472 0.5342311 -0.7538294 -0.3825421 -0.04333305 0.9970672 0.06308209 0.3071533 -0.9467142 0.09689754 0.942447 -0.3279084 0.0653454 -0.9466556 0.2768177 0.1649701 -0.002193093 -0.001130163 -0.999997 0.002912282 9.95135e-4 -0.9999953 0.00423938 0.002221763 -0.9999886 0.004117727 -0.006425082 -0.9999709 -4.80021e-4 -8.47542e-5 -0.9999999 -4.6289e-4 -5.03793e-4 -0.9999998 -3.90515e-4 0.004561066 -0.9999895 0.8656454 0.5005624 -0.009760618 -0.1709339 -0.9681298 -0.1830475 -0.304489 -0.9499483 0.06989002 -0.5611229 -0.8186184 -0.1224961 -0.8369668 -0.5404322 -0.08613878 0.003291308 -0.001273274 0.9999939 4.15759e-4 0.06903642 0.9976141 0.002768278 0.00603336 0.999978 0.02860254 0.02302712 0.9993256 0.004000425 7.31892e-4 0.9999918 8.02263e-4 4.75665e-4 0.9999996 -3.62769e-7 5.47364e-7 1 5.75717e-7 2.49114e-6 1 0.001605927 -8.84913e-4 0.9999983 -0.0106343 0.01254832 0.9998647 -0.01021087 -0.02852934 0.9995408 1.89703e-4 -1.60466e-4 1 2.95175e-4 -2.60122e-5 1 0.01117748 -0.005265653 0.9999237 3.93367e-4 -4.52174e-5 1 2.40885e-4 6.01451e-5 1 2.60816e-4 -0.001798689 0.9999984 -1.05326e-4 -7.91658e-5 1 -0.1944362 0.9793428 0.05552023 0.9529505 0.3017127 -0.02923774 0.9740438 0.2263574 0.001087963 -0.103715 0.9942779 0.0255869 -0.9390937 -0.3325796 -0.0865674 0.6657379 0.7433334 -0.06518185 -0.6123775 -0.3535573 0.7071004 -0.8660259 -0.4999994 -2.78455e-5 0.8660255 0.4999999 0 0.6123791 0.3535566 0.7070994 0.02177476 -0.03771477 -0.9990513 -0.4982721 0.8659188 -0.04369992 -0.4995611 0.8652665 -0.04186493 -0.6123723 -0.3535534 0.7071069 -0.6123719 -0.3535541 0.7071068 -0.6123725 -0.3535538 0.7071066 0.6120465 0.3533891 -0.707471 -0.61234 -0.3535378 0.7071427 0.6119882 0.3533656 -0.7075332 -0.6123626 -0.3535501 0.7071169 -0.6124429 -0.3535882 0.7070285 -0.6123474 -0.3535423 0.707134 -0.6123542 -0.3535478 0.7071254 -0.6123763 -0.3535562 0.7071021 -0.6123834 -0.3535369 0.7071056 -0.6123733 -0.3535538 0.7071059 -0.6123769 -0.3535563 0.7071015 -0.6124236 -0.35359 0.7070442 -0.6124029 -0.3535789 0.7070676 -0.6123737 -0.3535545 0.7071052 -0.6123896 -0.3535655 0.7070859 -0.612383 -0.3535593 0.7070947 0.6120622 0.3460293 -0.7110863 0.6231462 0.3596725 -0.6944959 0.660668 0.3814399 -0.6465459 0.5783646 0.4121636 -0.7039998 0.6606696 0.3814401 -0.6465441 0.6606672 0.3814383 -0.6465475 0.660659 0.3814424 -0.6465535 0.5783607 0.4121615 -0.7040042 0.6606575 0.3814431 -0.6465547 0.5783625 0.4121631 -0.7040017 0.6606572 0.381443 -0.646555 0.5783626 0.4121625 -0.7040021 0.5783702 0.4121531 -0.7040013 0.6606647 0.3814328 -0.6465533 0.6123836 0.3535482 -0.7070997 0.6916577 0.3213486 -0.6467957 0.660668 0.381439 -0.6465463 -0.6123702 -0.353552 -0.7071095 -0.6183428 -0.3592237 -0.6990067 -0.6606681 -0.3814375 -0.646547 -0.6461256 -0.2947971 -0.7040004 -0.6606673 -0.3814361 -0.6465488 -0.6461274 -0.2947987 -0.703998 -0.6461245 -0.2947935 -0.7040029 -0.6461164 -0.2947841 -0.7040141 -0.660672 -0.3814547 -0.646533 -0.6461209 -0.2947927 -0.7040065 -0.6606677 -0.3814508 -0.6465396 -0.6461219 -0.2947973 -0.7040037 -0.6461252 -0.2947946 -0.7040017 -0.660636 -0.3812087 -0.6467149 -0.6461246 -0.2947942 -0.7040025 -0.6461228 -0.2947961 -0.7040033 -0.66067 -0.3814361 -0.6465461 0.5359469 0.3666648 0.7604722 0.4248144 0.8624034 -0.2753058 -0.7163746 -0.1423833 0.6830333 -0.4131596 -0.7016294 0.5805303 -0.5634453 -0.6484569 0.5118916 -0.5657147 -0.6444448 0.5144491 -0.5089555 -0.6063551 0.6109811 -0.5786787 -0.8134091 -0.05913388 0.04853087 -0.3346249 0.941101 0.1300113 -0.3354591 0.9330404 0.2293365 -0.3130657 0.9216261 0.2323381 -0.2590996 0.9374895 -0.9744263 -0.005930364 -0.2246293 -0.3937755 -0.132557 0.9095985 -0.5573722 -0.2472763 0.7925848 0.1903388 0.8604848 0.4725855 -0.1811316 -0.9785255 0.09838372 -0.4696495 0.07855063 0.8793516 -0.0844562 0.2017499 0.9757891 -0.01479732 0.02562981 0.9995621 0.007802963 -0.01488226 0.9998589 1.62713e-4 -1.48321e-4 1 -0.9053115 0.4232232 0.03596121 -0.908671 0.4162045 0.03302878 0.04121845 0.9985856 0.03358328 0.904219 -0.4255508 0.03598022 -0.03387928 -0.5123983 0.8580794 -0.4420884 -0.2552407 0.8598896 -0.1579795 0.2243263 0.9616237 -0.4997746 0.8655382 0.0326969 -0.006982266 0.8829005 0.4695082 0.8656259 0.4998241 0.02945929 0.8618156 0.5060183 0.0349211 0.9061332 -0.4214593 0.03598105 0.9128975 -0.4070745 0.03014481 -0.04123276 -0.9985851 0.03358197 -0.1575472 -0.1868389 0.9696754 -0.8660734 -0.4990496 0.02943402 0.1522791 -0.2224926 0.9629684 0.3926193 -0.7147672 0.5787556 -0.06860697 -0.9431905 -0.325092 2.05342e-4 -1.79427e-4 1 2.61048e-5 -4.83826e-5 1 -0.04122442 -0.9985853 0.03358477 -0.7601373 0.3770556 -0.5291694 -0.9068893 0.4198892 0.03528404 -0.9127304 0.407451 0.03011769 -0.5105037 0.8591619 0.0350281 -0.5103753 0.8592476 0.03479713 0.03708982 0.9986858 0.035371 0.0411874 0.9985863 0.03360158 0.8926704 -0.4498574 0.02771139 -0.03998982 -0.7177636 0.6951376 -0.08141225 -0.4979329 0.8633857 -0.7723385 -0.4173548 0.4788616 0.01960062 -0.03622847 0.9991513 -2.34393e-4 2.13671e-4 1 -0.07095921 -0.9972545 0.02117699 -0.8653807 -0.5002487 0.02945578 -0.8618259 -0.506033 0.03445231 -0.9127301 0.4074527 0.03010016 -0.08443862 0.2018057 0.975779 0.03587573 0.5171787 0.8551253 0.03708761 0.9986854 0.03538274 0.04126965 0.9985839 0.03357303 0.3891917 0.3100853 0.8673967 0.8618077 0.5060074 0.03527516 0.9064705 -0.4207867 0.03535336 0.5075975 -0.8608791 0.0351026 0.5103008 -0.8590613 0.04008597 -0.0821951 -0.5013845 0.8613116 -0.7726291 -0.4171055 0.4786099 -1.49385e-4 1.36184e-4 1 -0.8654019 -0.500211 0.02947354 -0.9978782 -0.01603758 0.06310367 -0.9042284 0.4255504 0.03575003 -0.08443397 0.2017922 0.9757822 0.03586786 0.5171575 0.8551384 0.04123008 0.9985854 0.03357845 0.3891953 0.310082 0.8673962 0.8660831 0.4990326 0.02943986 0.9064729 -0.4207847 0.03531545 0.4998506 -0.865868 0.02054071 -0.0426523 -0.7177917 0.6949503 -0.08219951 -0.5013961 0.8613045 -0.7726276 -0.4171028 0.4786146 -0.01922464 0.03692406 0.9991332 -0.07514268 -0.9963868 0.03958439 -0.8654026 -0.5002101 0.02946496 -0.9978799 -0.01601463 0.06308156 -0.9042257 0.4255465 0.0358619 -0.5105639 0.8591197 0.03518521 -0.5103452 0.8592653 0.03480064 0.03587013 0.5171561 0.8551392 0.03706347 0.9986861 0.03538978 0.8618024 0.5060159 0.03527784 0.9128442 -0.4072 0.03006416 0.3741876 -0.654744 0.6567298 0.4998503 -0.8658682 0.02054011 -0.04264986 -0.7177656 0.6949775 -0.4234809 -0.2830998 0.8605338 -2.34425e-4 2.13702e-4 1 -1.49374e-4 1.36168e-4 1 -0.08983856 -0.9953751 0.03402417 -0.8654033 -0.5002091 0.0294649 -0.8618457 -0.5059998 0.03444027 -0.904246 0.4255133 0.03574484 0.3891659 0.3100625 0.8674163 0.8617998 0.5060206 0.0352742 0.9064799 -0.4207693 0.03532147 0.9128367 -0.407216 0.03007477 0.3741711 -0.6547096 0.6567735 0.5076045 -0.8608816 0.03493577 0.4998503 -0.8658682 0.02054071 -0.772624 -0.4171001 0.4786227 -0.01922702 0.03692877 0.9991329 -0.07514321 -0.996387 0.03957873 -0.9978803 -0.01599657 0.06308001 -0.9042259 0.4255419 0.03591215 -0.9127327 0.4074472 0.03009897 0.03706562 0.9986868 0.03536683 0.3891677 0.3100643 0.867415 0.861808 0.5060073 0.0352658 0.9126704 -0.4075877 0.03008443 0.1320757 -0.1942157 0.9720269 0.3741868 -0.6547411 0.6567332 0.4998286 -0.8658808 0.0205422 -0.0426582 -0.7177638 0.6949788 -0.08220064 -0.5014019 0.861301 -0.4234955 -0.2831165 0.8605212 0.01960045 -0.03622788 0.9991514 -2.34446e-4 2.1372e-4 1 -1.49393e-4 1.36185e-4 1 -0.08983021 -0.9953754 0.03403657 -0.8618402 -0.5060089 0.03444755 -0.9978812 -0.01595461 0.0630756 -0.9042273 0.4255383 0.03591924 -0.08443063 0.2017877 0.9757834 -0.5103727 0.8592491 0.03479546 0.03585714 0.5171285 0.8551564 0.03706568 0.9986861 0.03538835 0.8660787 0.4990407 0.0294339 0.8618017 0.5060177 0.03527134 0.9064828 -0.420763 0.03532093 0.9128409 -0.4072063 0.03007757 0.5076033 -0.8608824 0.03493595 0.4998527 -0.8658668 0.02054041 -0.03999751 -0.7177521 0.695149 -0.08141189 -0.4979401 0.8633816 -0.7723171 -0.4173451 0.4789044 0.01960068 -0.03622841 0.9991514 -2.34427e-4 2.13704e-4 1 -1.49394e-4 1.36185e-4 1 -0.07096856 -0.9972538 0.02117657 -0.0412417 -0.9985651 0.0341618 -0.8653774 -0.5002539 0.02946442 -0.9042299 0.425533 0.03591787 -0.9127083 0.4074999 0.03012502 -0.0844292 0.2017848 0.9757841 -0.510562 0.8591223 0.03514653 -0.5103803 0.8592437 0.03481787 0.03585779 0.5171164 0.8551636 0.04116266 0.9985882 0.03357684 0.3891623 0.3100617 0.8674184 0.8660814 0.4990358 0.0294348 0.8618034 0.5060148 0.03526735 0.132084 -0.194227 0.9720236 0.5075953 -0.8608825 0.0350517 0.1522777 -0.2224878 0.9629697 0.3926479 -0.7148136 0.578679 -0.06858223 -0.9431729 -0.3251484 0.4997326 -0.8654729 0.03498601 -0.03700631 -0.9986807 0.03560155 -0.3729148 -0.2216364 0.9010061 -0.2799384 -0.1869599 0.9416372 -0.8618176 -0.5060146 0.03492677 -0.7601025 0.3770332 -0.5292355 -0.9068875 0.4198927 0.03529077 -0.9127275 0.4074566 0.03012788 -0.08839231 0.1904075 0.9777176 -0.2147171 0.3758426 0.9014649 0.03706079 0.9986866 0.0353772 0.04117757 0.9985871 0.03358924 0.3898521 0.30954 0.867295 0.8660666 0.4990618 0.02942985 0.8617975 0.506024 0.03528439 -0.04161727 -0.7177522 0.6950539 -0.1192311 -0.1955732 0.9734141 -0.4187138 -0.254404 0.8717554 -0.2217754 -0.03115731 0.9746 0.00622487 -0.01744252 0.9998285 -1.9807e-4 2.44267e-4 1 0.03546243 0.5161284 0.8557768 0.8613022 0.5072315 0.02957332 0.1351177 -0.1987085 0.9706999 -0.3545478 0.2887037 0.8893516 -0.5353394 -0.3062855 0.7871474 -0.3708931 -0.2680256 0.8891573 -0.4705801 -0.1070386 0.875841 -0.5288677 -0.3626286 0.7673327 -0.496958 -0.2868945 0.8189777 -0.4962767 -0.2865431 0.8195137 -0.4344761 -0.2468072 0.8662084 -0.4729602 -0.2582172 0.842397 -0.4461795 -0.2109101 0.8697361 -0.4663959 -0.1973048 0.862291 -0.4549459 -0.2779582 0.8460281 -0.4993835 -0.288137 0.8170638 -0.4524267 -0.2587556 0.8534376 -0.4475448 -0.2542013 0.8573713 -0.5680043 -0.2387654 0.7876307 -0.3808762 -0.2103598 0.900379 -0.4238245 -0.2514508 0.8701411 -0.4972184 -0.2870858 0.8187525 -0.3630352 -0.3855966 0.8482457 -0.4966819 -0.2867612 0.8191918 -0.5303537 -0.3165301 0.7864692 -0.4884973 -0.2556236 0.8342823 -0.48648 -0.3238182 0.8114672 -0.3841692 -0.2245238 0.8955463 -0.4965533 -0.2866721 0.8193008 -0.3204292 -0.3906611 0.8629653 -0.3680058 -0.1275247 0.9210371 -0.349769 -0.3306301 0.8765532 -0.4909398 -0.2827991 0.8240163 0.6954838 0.4079137 0.5915309 0.6980302 0.189393 0.6905679 0.2401768 -0.5701804 0.7856268 -0.576671 -0.4027326 0.7108144 0.1927524 -0.8030749 0.5638416 0.4921644 -0.5342254 0.6872973 -0.6507236 0.2861557 0.7033305 -0.3521831 0.5750076 0.738467 0.002844154 0.7205653 0.6933813 0.6286675 0.2812231 0.7250455 -0.5321392 -0.2448096 0.8104913 -0.2266482 0.2207709 0.9486258 -0.02384197 0.2785413 0.9601283 0.5910869 -0.02694511 0.8061578 0.3157069 -0.153964 0.9362822 -0.1976785 -0.4544522 0.8685601 -0.3083584 -0.2403366 0.9204094 -0.3513687 -0.2611658 0.8990731 -0.3733639 -0.5841888 0.7206406 -0.2413572 -0.5111996 0.8248768 -0.02734375 -0.4362058 0.8994314 0.4471915 0.2088878 0.8697044 0.5283736 0.3740303 0.762183 0.2187792 0.3301616 0.9182205 0.270977 0.6402398 0.7187938 0.01368117 0.4439633 0.8959406 -0.06719088 0.3952643 0.9161068 -0.4601076 0.7939043 0.3975134 -0.4379356 0.323822 0.8386607 -0.9926676 0.05188018 0.1091768 -0.991237 0.1227467 -0.04881221 -0.9286871 0.3608615 0.08555382 -0.8126735 0.5765815 0.08435422 -0.3892619 0.9197728 0.04993319 0.1518373 0.9846943 0.08557295 0.701118 0.7130454 0 -0.8798538 0.4724841 -0.05114996 -0.7781236 0.6261258 -0.04990386 -0.62528 0.778739 -0.05089604 0.6961258 0.7179191 0.001043498 0.4139697 0.9102877 0.002321362 0.3897523 0.9208722 0.009358286 0.2724399 0.9621102 -0.01097804 -0.1684781 0.9852316 0.03056144 -0.2531087 0.9586387 -0.1301838 -0.9340306 0.3570184 -0.01117044 -0.9846727 0.1742764 -0.006893634 -0.9919694 -0.1264776 -4.64482e-4 -0.9697807 -0.2439154 -0.005553007 -0.9084772 -0.4179345 0 -0.9086487 -0.4175614 6.95676e-5 0.5523654 0.8335861 0.005167782 -0.8748946 0.4834271 0.02929002 0.8161985 0.5777717 0 -0.8192977 -0.5732867 0.009675204 -1.9365e-4 -8.69845e-5 1 5.27601e-4 -9.92103e-5 1 5.59688e-4 -2.28945e-4 0.9999999 0.007704913 -0.005171179 0.999957 0.007929861 -0.01225578 0.9998935 0.005551755 -0.005509674 0.9999695 0.001751184 -0.01026999 0.9999458 2.4564e-6 6.10374e-5 1 5.45029e-4 4.84104e-4 0.9999998 2.06287e-4 -6.10505e-5 1 6.34003e-7 0 1 0.003596365 -0.007336199 0.9999667 2.90666e-4 2.47815e-4 1 2.16154e-4 3.80206e-4 1 1.77596e-4 -3.48485e-4 1 5.44853e-5 -8.00266e-4 0.9999997 -1.51116e-4 -4.31456e-4 0.9999999 -1.46903e-4 -1.59986e-4 1 -0.8447442 -0.5351411 0.00560379 -0.8532443 -0.5214756 0.006130397 -0.8993781 -0.4371584 -0.003395557 -0.8378651 -0.5458321 -0.00704497 -0.8474663 -0.5307978 -0.007379412 -0.8568293 -0.5155445 -0.00759685 -0.8659318 -0.5001056 -0.007527172 -0.8747581 -0.4845069 -0.007166564 -0.8915018 -0.4529861 -0.005309879 -0.8262188 -0.5633482 0.001193583 -0.8237192 -0.5668525 -0.01285058 0.8967869 0.4424622 7.88745e-4 0.8974665 0.4410827 -3.45778e-4 0.9006634 0.4345174 2.33275e-4 0.9010463 0.433722 8.62277e-4 0.8851063 0.465389 4.73799e-5 0.8975777 0.4400211 0.02712708 0.8940812 0.4479049 -4.33212e-4 0.8922399 0.4515538 -0.002662539 0.8916363 0.4526979 -0.007036626 0.8569635 0.5153273 -0.007159471 0.8476189 0.5305664 -0.006453275 0.8380454 0.5455749 -0.005298554 0.8279223 0.5608428 1.99677e-4 0.8858114 0.4640119 0.005581736 0.878234 0.478192 0.00613594 0.8623257 0.5063186 0.006002008 0.8455362 0.5338988 0.004573464 0.8368288 0.5474566 0.002995193 0.9431123 0.02826875 0.3312706 0.9878759 0.1540102 0.01954507 0.9412367 0.03491407 0.3359385 -0.395973 -0.2483952 -0.8840279 -0.4503369 -0.2752326 -0.8493785 -0.4563133 -0.2770214 -0.8455989 -0.06833302 -0.05173909 -0.9963201 -0.4253267 -0.2692182 -0.8640712 -0.4193497 -0.2596259 -0.8699083 -0.4292972 -0.2599996 -0.8649302 -0.4310731 -0.25885 -0.8643915 -0.4342157 -0.2546725 -0.8640594 -0.4488875 -0.2544608 -0.8565921 -0.4488164 -0.2544509 -0.8566321 -0.45063 -0.2570077 -0.854915 -0.114075 -0.06859129 -0.9911015 -0.4156199 -0.2562998 -0.8726801 -0.4366289 -0.2453588 -0.8655371 -0.4344815 -0.2338331 -0.8697977 -0.4401839 -0.2405427 -0.865088 -0.442534 -0.234609 -0.8655185 -0.4675391 -0.2505789 -0.8477131 -0.4464749 -0.2337377 -0.8637285 -0.4409001 -0.2227838 -0.869468 -0.4440945 -0.2230988 -0.8677598 -0.455802 -0.2176085 -0.8630707 -0.4221591 -0.2396287 -0.8742767 -0.4115605 -0.2607644 -0.8732812 -0.04358214 0.9966502 0.06920206 0.87383 0.4849172 0.03573012 0.5033482 -0.8567178 0.1125849 0.983764 -0.1763032 0.03355067 0.8690685 0.4934496 0.03503608 0.3268143 0.9441574 0.04194241 0.02759635 0.9961853 0.08278483 0.8643444 0.501652 0.03541743 0.7575274 -0.6503702 0.05631107 0.3623003 -0.9263812 0.1027452 0.8549356 0.5175424 0.03514415 0.8906894 -0.4491839 0.07004505 -0.1731484 0.9844689 0.02899575 0.844986 0.5335728 0.03603935 0.8740487 -0.4745444 0.1041473 0.7975832 -0.5976403 0.08177542 -0.003727912 -0.004153549 -0.9999845 -0.006365835 -0.004167854 -0.9999712 -0.003897547 -0.002465069 -0.9999894 -4.6609e-7 0 -1 1.80593e-7 0 -1 3.43143e-5 2.43522e-5 -1 -2.04128e-6 -1.35749e-6 -1 -9.26286e-6 -3.8715e-6 -1 -0.001171767 -6.50904e-4 -0.9999991 6.80965e-4 3.88995e-4 -0.9999998 -1.41413e-4 9.2921e-5 -1 -0.09049153 -0.02457302 -0.9955941 0 0 -1 3.4749e-4 8.75382e-5 -1 4.80147e-4 -2.63829e-4 -1 -0.08836996 -0.03478008 -0.9954804 -0.03537374 -0.02844488 -0.9989693 -0.001088619 7.44298e-5 -0.9999995 -0.007816493 -0.004512727 -0.9999593 -0.09619468 -0.06809544 -0.9930306 -0.001341581 0.001130938 -0.9999985 -0.06400275 -0.03659158 -0.9972787 -0.05590379 -0.03535902 -0.99781 -0.002556025 1.30769e-4 -0.9999967 -0.06569749 -0.03393125 -0.9972626 -0.007816731 -0.004512906 -0.9999593 -0.007757604 -0.004484355 -0.99996 -0.05302369 -0.04415076 -0.9976168 0.005437731 0.003139674 -0.9999804 -0.0364899 -0.02644836 -0.998984 -0.09590232 -0.05831831 -0.9936809 -0.007864058 -0.004534363 -0.9999589 -0.007815182 -0.00451225 -0.9999593 -0.007816791 -0.004512727 -0.9999593 -0.007802784 -0.004507422 -0.9999595 -7.57392e-7 0 -1 -0.001185715 -0.002122163 -0.9999971 0.005649983 0.00302422 -0.9999795 -0.007809996 -0.004509866 -0.9999594 -0.8667798 -0.4974311 0.03542727 -0.8666744 -0.4976285 0.03523498 -0.7522686 0.6564861 0.05583941 -0.3544259 0.9294584 0.1024176 -0.8618925 -0.5058792 0.0350368 -0.2435843 -0.9690343 0.04048621 -0.03355866 -0.9969536 0.07041043 -0.8573327 -0.5135802 0.03487378 -0.9597949 0.2490363 0.1295175 -0.2156334 0.9762482 -0.02101665 -0.02900946 -0.9957897 0.08695673 -0.8473312 -0.5298758 0.03551793 -0.01681029 -0.9963344 0.08387738 -0.8376414 -0.5450611 0.03557419 -0.8378788 -0.5447309 0.03503775 -0.8469663 0.5228019 0.09657222 -0.7874359 0.6117032 0.0759201 0.8411728 0.5296786 -0.1089452 0.1847015 0.9238942 -0.3351194 0.2646601 0.6838095 -0.6799703 0.8602202 0.4728492 -0.1908793 -0.6337833 0.6773266 -0.3735605 -0.6500008 0.6627754 -0.37179 -0.9660946 -0.08834052 -0.2426052 -0.8520733 -0.4752569 -0.2193216 -0.8502181 -0.2180146 -0.4791648 -0.8334562 -0.1194648 -0.5395174 -0.4662086 0.8083276 -0.3595221 -0.3214028 0.5566833 -0.7660315 -0.3430462 0.2291445 -0.9109402 -0.3223986 0.5565022 -0.7657444 -0.3223852 0.5565301 -0.7657298 -0.3213911 0.5566774 -0.7660405 0.3438367 -0.9390296 0 0.2586911 -0.9659545 -0.003322184 -0.7071008 -0.7071015 -0.004002332 -1.95535e-4 -3.15451e-4 -1 2.63579e-6 0 -1 -4.66293e-7 0 -1 0.002897322 -0.002928495 -0.9999915 -1.02693e-4 0.00272268 -0.9999964 -2.78413e-6 0 -1 -4.4329e-7 0 -1 0.002254426 3.41107e-4 -0.9999974 -1.75744e-4 1.32025e-5 -1 0.8660246 0.5000014 1.18362e-4 0.8660254 0.5000001 -7.5309e-5 0.6123632 0.3535493 0.7071169 0.6124042 0.3535656 0.7070732 0.6124062 0.3535658 0.7070714 0.6123217 0.3535347 0.7071601 0.612355 0.3535454 0.7071259 -0.6124268 -0.3536107 -0.7070311 -0.6124415 -0.3535915 -0.7070279 0.6123639 0.3535482 0.7071167 0.6123695 0.3535519 0.7071101 0.6124672 0.3536239 0.7069896 0.612309 0.3534945 0.7071912 0.6123773 0.3535563 0.7071011 0.6124002 0.3535789 0.70707 0.612366 0.3535532 0.7071126 0.6123741 0.3535501 0.7071071 0.6093561 0.3618391 0.7055194 0.5783641 0.4121649 -0.7039993 -0.01881325 -0.02672767 -0.9994658 0.507644 -0.86041 0.04463541 0.4998586 -0.8652281 0.03901028 -0.9509865 0.1644487 0.2618805 -0.7715114 0.5225695 0.362893 0.2411589 -0.008294284 0.9704503 -0.003106355 -0.0235967 0.9997168 0.008652627 -0.001956403 0.9999607 0.01649492 -0.01171839 0.9997953 0.007485747 -0.006540536 0.9999506 -7.75915e-4 0.001787781 0.9999982 -3.80479e-5 -1.60931e-4 1 -4.48899e-5 -1.87091e-4 1 -6.91718e-5 -1.77096e-4 1 -0.03217095 -0.05739897 0.9978328 -0.02158993 -0.03104037 0.9992849 -3.81098e-5 5.94857e-4 0.9999999 -0.8446852 -0.4926919 -0.2091926 -0.8180537 0.5465445 -0.1791014 -0.6513512 0.01285004 -0.7586676 -0.4854544 0.2311099 -0.8431621 -0.4749811 -0.1701523 -0.8633893 -0.1417462 -0.3810377 -0.9136292 -0.03756517 -0.01801097 -0.9991319 -0.4055257 0.6603309 0.6320698 0.8647654 0.5021762 0 0.440735 0.8898056 -0.1183171 -0.07583683 0.9966346 0.03111594 0.3725273 -0.8856057 -0.2773553 0.004581034 0.9992601 0.03818857 0.01603764 0.4531032 -0.8913138 0.1697788 0.9143053 0.3677242 -0.4112392 -0.8755273 -0.2536421 -0.6837805 0.502603 -0.5289939 -0.8948716 0.004917442 0.4462967 0.1353646 0.0695573 -0.9883512 -0.5276182 0.7429009 -0.4119675 -0.6947918 0.7155021 0.07294684 0.07066416 -0.3882903 0.9188239 -0.4587821 0.8807432 0.1175179 -0.8330022 0.5485215 0.07232964 -0.9789056 0.2042967 0.002617537 -0.9586269 0.2846621 -0.001455008 -0.9248536 0.3803232 -5.57372e-4 -0.880631 0.4736835 0.01063227 -0.7594258 0.650534 0.008838891 -0.2948579 0.9555343 0.003620803 -0.3110169 0.9503595 -0.009246051 -0.4010021 0.9158925 0.01839518 -0.5576456 0.8297315 -0.0240249 -0.2069633 0.9783065 -0.009094059 -0.0549708 0.9983696 0.01537495 0.4889148 0.8723194 -0.004617452 0.1346113 0.9905096 0.02775877 0.009574532 0.9990149 0.04333233 0.2328205 0.9725155 -0.002902448 -0.1553487 0.9876423 -0.02072751 -0.1909105 0.9815881 -0.006159543 -0.2938882 0.9558381 -0.001827061 -0.3366716 0.9416222 0 -0.4646836 0.8853195 0.01668947 -0.06741082 0.9948939 -0.07511389 -0.266915 0.9635984 0.01531982 -0.9321115 0.3621674 -0.001735687 -0.9037768 0.4278874 -0.01000005 0.1491759 0.8357366 -0.5284797 -0.4661284 0.7837837 -0.4103748 0.319994 0.8939566 -0.3137602 0.1149547 0.6825109 -0.7217786 0.04773133 0.5980313 -0.8000503 -0.6883849 0.6736055 -0.2690393 -0.7506031 -0.04811263 0.6589996 -0.7478511 -0.03951114 0.6626897 0.02303749 0.08596998 0.9960314 -4.23763e-7 0 1 -1.25398e-7 0 1 0 0 1 -0.1313122 -0.08711004 0.9875065 -2.00704e-7 0 1 0 0 1 -1.45053e-7 0 1 -1.22576e-7 0 1 1.27491e-7 0 1 -2.55217e-5 -2.69353e-5 1 1.5158e-5 7.16002e-7 1 3.82502e-7 0 1 5.50269e-4 -3.72133e-4 0.9999998 -0.560456 -0.4507045 0.6948055 0.365296 0.6168182 0.6972046 0.6717187 0.2604408 0.6935161 0.1992905 -0.557208 0.8061034 -0.03245979 -0.7635112 0.6449785 0.04628193 -0.5727807 0.818401 0.6904374 0.1313435 0.7113685 0.4753524 -0.3562368 0.8044474 0.716622 0.1184342 0.6873328 -0.4976964 0.8673431 0.00377947 -0.01310598 -0.9997576 -0.01769644 -0.3538826 -0.9348948 -0.02718311 -0.3579155 -0.9333637 -0.02699416 -0.6650791 -0.746037 -0.0331465 -0.7716762 -0.6353659 -0.02874338 -0.7784813 -0.6271283 -0.02602517 0.6446945 -0.7644156 -0.006149947 0.8696583 -0.4933297 -0.01789265 0.9865835 -0.1609787 -0.02718287 0.9777306 0.2072082 -0.03328037 0.6470892 -0.7623904 -0.006048083 -0.6884891 -0.7249735 -0.01990759 0.9872953 0.1546158 -0.03663408 -0.9877468 0.1547901 -0.01990813 -0.7521055 -0.658742 0.0199083 -0.9693779 0.2447656 0.01990741 3.94178e-4 3.4189e-4 -1 -3.05268e-4 -3.5932e-4 -1 0.002863824 -0.006276607 -0.9999762 -5.03164e-4 0.008749783 -0.9999617 1.49883e-4 -8.42242e-5 -1 4.54282e-4 -7.14994e-5 -0.9999999 0.8732366 -0.4860384 -0.03499293 -0.03449398 0.9992617 -0.01691979 -0.8022743 0.5957924 -0.0372492 -0.9452173 -0.3215373 -0.0563746 -0.7954348 -0.6049311 0.03663396 -0.6967734 0.7170918 0.01691967 -1.19824e-4 4.22739e-4 -1 0.002863883 -0.006276667 -0.9999762 -0.012766 0.01010519 -0.9998676 5.1936e-4 1.76249e-4 -0.9999999 -0.9961332 0.08621174 -0.0169211 -0.731588 0.6809273 -0.03342199 -0.3455391 0.9367679 0.05539667 0.5725958 0.8195961 0.01990759 0.9959203 0.09009855 0.005026757 0.9878169 0.1546983 -0.0169205 0.903447 -0.4286968 0.001612007 -0.6885041 -0.7249745 -0.01934033 0.1052253 0.004393637 0.9944387 -0.08203154 0.1437181 0.986213 -0.9795532 0.1999961 0.02184188 -0.731562 0.6808998 -0.03453415 0.8345289 0.5503628 -0.02573978 0.996976 -0.06736809 0.03873622 0.6338173 -0.7724829 0.03931951 0.2725709 -0.961783 -0.02604919 -0.2063173 0.1213479 0.9709315 -0.9961333 0.08621019 -0.0169211 0.4783847 0.8777014 -0.02808094 -0.7521048 -0.6587429 0.01990818 0.9872953 0.1546154 -0.03663516 0.8734278 -0.4861433 0.02808171 -0.01092261 0.002757906 0.9999366 0.005350768 0.006122887 0.999967 2.56449e-4 -6.51442e-4 0.9999998 0.03640455 0.04298913 0.9984121 0.05766433 -0.0654608 0.9961876 -0.008820116 -0.007725179 0.9999313 0.001840591 -0.01591122 0.9998718 -0.6963871 0.7166939 0.03735083 -0.4847582 0.8739242 -0.03558135 0.9872949 0.1546187 -0.03663456 0.2052378 -0.9770871 -0.05637484 -0.6881594 -0.7246028 -0.03724944 -0.01066416 0.00146526 0.9999421 3.57646e-4 0.007385611 0.9999728 5.05885e-4 -5.20729e-4 0.9999998 2.08178e-4 -4.74816e-4 1 0.001574754 -0.01170063 0.9999303 -0.008998155 -0.00684309 0.9999361 -1.18464e-4 -9.31416e-4 0.9999997 0.009256243 0.004791259 0.9999457 0.009257495 -0.01582282 0.999832 -0.004026174 -0.01529699 0.9998749 0.2816829 0.416463 0.864415 -0.08688855 0.3794435 0.921126 -0.8871917 0.4613993 0.00133711 -0.9693448 0.2449234 -0.01957851 -0.7067447 -0.7071618 -0.02083671 0.2614061 -0.9649999 -0.02102607 -0.4647102 0.8854619 0.001348853 0.3422524 0.9395593 -0.009577453 0.7750946 0.6318374 0.003161251 0.9665566 -0.2562883 0.009210109 -0.7069012 -0.7070743 0.0183494 0.8999801 -0.4359291 -0.001289486 0.04507631 -0.9989827 -0.001350879 -0.9621226 0.2719143 0.0195629 -0.8871822 0.4614174 0.001336812 0.2614092 -0.9649991 -0.02102535 0.9673551 0.2531948 -0.01079809 -0.07141298 0.9974468 -4.61981e-4 0.899989 -0.4359108 -0.001289248 -0.6640273 -0.7462448 0.04675978 -0.8655998 -0.4998207 0.03027188 0.08670067 0.9956709 0.03350257 0.8653246 0.5002796 0.03055268 0.8615766 0.5064319 0.03482347 0.8655973 0.499825 0.03027242 0.8615808 0.5064263 0.03479874 -0.8616042 -0.5064049 0.03453099 -0.9781177 -0.2019951 0.04983866 -0.08627223 -0.9955981 0.03662681 -0.6646516 -0.7468194 0.02234107 -0.8614544 -0.5066246 0.03504049 0.368054 0.9258776 0.08536374 0.01922672 0.9980471 0.05943489 0.8657323 0.4998322 0.02599036 0.8602026 0.5088049 0.0341916 0.09914851 0.994342 0.03812766 0.6639974 0.746121 0.04910117 0.09356313 0.9950021 0.03488218 0.8616298 0.5063636 0.03449732 0.7048567 -0.7053596 0.07513225 0.9960303 0.06643748 0.05924385 -0.07175016 -0.996693 0.03814631 -0.08121502 -0.9957179 0.04415822 -0.8327754 -0.5523805 0.03689247 -0.8983266 0.4369223 0.0459184 -0.871431 0.489161 0.03646385 -0.8961874 0.440985 0.04878997 0.8654963 0.4996981 0.03489804 0.9781402 0.201929 0.04966413 0.9225803 -0.3844501 0.03230941 0.01227712 0.9992772 0.03597503 0.8779938 0.4773451 0.03561782 0.8801106 -0.4733594 0.03655672 0.8967617 -0.4400652 0.04649001 0.8864578 0.4614799 0.03506022 0.8918963 -0.4507556 0.03661245 0.8801422 0.4741843 0.02233713 -0.8838391 0.4650544 0.05052667 -0.9129009 0.4071296 0.02928239 0.8701117 0.4919716 0.02949005 0.8619004 0.5055283 0.03961038 -0.9031971 0.4282608 0.02877449 -0.8904368 0.4538682 0.03355747 -0.8998044 0.4334329 0.04988145 -0.8800128 -0.4736039 0.03573441 -0.8825291 0.4688709 0.0360918 -0.9009153 0.4313104 0.0482003 0.8602067 0.5087981 0.03419017 -0.001588523 -0.9993839 0.03506189 -0.08294749 -0.9949894 0.0558204 -0.9781196 -0.2018902 0.0502249 -0.9185971 0.3938359 0.03275609 -0.05226242 -0.996699 0.062128 -0.9945971 0.07956588 0.06667822 -0.5744069 0.8172822 0.04589527 -0.9950914 -0.06141948 0.07759475 -0.01384723 0.9992766 0.03541773 0.07419908 0.9956047 0.05714821 -0.9906931 0.09475618 0.09771698 0.8402585 0.5406537 0.0407356 -0.2608418 0.4612448 0.8480653 -0.6124106 -0.3554568 0.7061189 -0.5972357 -0.1030643 0.7954164 -0.4374313 -0.2522121 0.8631588 -0.3237817 0.1802912 0.9287952 -0.6952688 -0.1527064 0.7023405 -0.4209569 -0.2448434 0.8734111 -0.5956746 -0.3723123 0.711727 -0.09474468 -0.1829125 0.9785533 -0.87239 -0.4875311 0.03534382 -0.3526782 -0.931314 0.09095323 0.04202133 -0.9977873 0.05152517 -0.6121938 -0.3602589 0.7038696 0.0442143 0.4566896 0.8885267 0.4303132 -0.8420307 0.3252922 0.6898555 0.4262943 0.5851262 0.6611673 0.3990634 0.6353001 -0.9524953 0.3025137 0.03518736 0.03433847 0.3068733 0.9511307 -0.6237511 -0.3909612 0.6768191 -0.5760075 -0.3280446 0.7487336 -0.2637303 0.2644123 0.927649 0.6919126 0.4017406 0.5998846 0.4492425 0.1638038 0.8782651 -0.5353487 0.712633 0.453383 -0.8656269 -0.4997751 0.03024917 -0.8616121 -0.506392 0.03452485 0.3870587 0.7942885 0.4682855 -0.6870508 0.585133 0.4307907 -0.5968725 0.5767795 0.5577353 -0.07813638 0.03827607 0.9962077 0.2565394 -0.3129568 0.9144647 -0.3797779 0.2793992 0.8818759 0.5793203 0.3321794 0.7443419 0.5830065 -0.1376616 0.8007202 0.6334773 -0.1149957 0.7651684 0.1823667 0.8306378 0.526102 0.6335293 -0.0965355 0.7676728 0.9306401 -0.364503 0.03235107 0.0323314 -0.2100077 0.9771651 -0.08451855 0.1442918 0.9859192 -0.1485906 0.7162725 0.6818171 0.1399828 0.02335095 0.9898786 -0.70836 -0.3063144 0.6359228 0.3498809 -0.8390269 0.4166738 -0.05216836 -0.9979104 0.03812181 0.9865614 -0.1391982 0.08556091 0.2086973 0.6938822 0.6891828 0.6109406 0.3595614 0.7053136 0.6270507 0.3744316 0.6830875 -0.2102267 -0.691231 -0.6913788 0.1764897 0.1322306 0.9753803 0.5288584 0.7980805 0.2887498 -0.1196869 -0.03153711 0.9923107 -0.5883518 -0.3830495 0.7121203 0.554427 -0.8043453 -0.2136337 0.5904542 0.3726257 0.7159008 0.4093582 0.8068186 0.4259927 -0.1571552 0.2918003 0.9434801 -0.02119964 0.2221352 0.9747854 -0.4288256 -0.2482882 0.8685976 -0.4235956 -0.2446084 0.8722004 -0.003332972 -0.1654187 0.9862178 0.7028803 -0.6513118 0.2859235 0.6632481 0.3588898 0.6567344 -0.9882701 0.1267989 0.08511292 -0.9199687 0.3872917 0.06052166 -0.6065416 -0.3568885 0.7104491 -0.5855921 -0.3381087 0.7367255 0.2249432 -0.8767135 0.4251753 0.2223016 0.09088683 0.9707326 0.6382808 0.4060288 0.654017 -0.1332631 0.1074925 0.9852342 -0.4234611 -0.2445318 0.8722872 -0.4304117 -0.7707858 0.4697182 0.1676302 0.04417717 0.9848597 -0.1351368 0.837374 0.529663 0.06956011 0.996558 0.04509454 -0.9868506 0.1371782 0.08548772 -0.9093304 0.4120032 0.05806618 0.7798863 -0.09720134 0.6183279 -0.6624693 -0.3892798 0.6399967 -0.6078261 -0.3349131 0.7199866 -0.4512158 -0.562177 0.693081 -0.3964374 -0.5946532 0.6994463 -0.6991239 -0.1991372 0.6867097 -0.1954049 -0.01083868 0.9806628 -0.9216346 0.3860232 0.03969746 -0.6218443 -0.3317266 0.7094132 -0.4271256 -0.2485259 0.8693669 0.6799955 0.3249085 0.6572981 -0.2543679 0.8754932 0.4108632 0.0831384 0.995413 0.04733854 -0.4191423 0.9070433 0.03990083 0.6398082 -0.6394135 0.4263753 -0.03686201 -0.06454449 0.9972338 -0.1415248 -0.1363513 0.9804995 -0.7268701 -0.1806085 0.6626013 0.7797779 -0.1081851 0.616638 0.3494174 0.6949304 0.6284738 -0.9115784 0.4093441 0.03823894 -0.913308 0.4053284 0.03971695 0.6025742 0.3456636 0.7193198 0.1186544 -0.3021341 0.9458522 -0.5821158 0.3634987 -0.7273307 -0.6310509 -0.3713568 0.6810793 -0.6542908 -0.3778781 0.6550663 0.2035497 -0.8681905 0.4525625 0.5973212 0.8013845 0.03146868 0.05621975 -0.06544488 0.9962713 0.4234967 0.2445493 0.872265 0.05332022 0.7134836 0.6986402 -0.2515112 -0.1813118 0.9507198 0.3615457 -0.8604447 0.3590539 0.9885342 -0.1247749 0.08503705 0.6115447 0.3611207 0.7039923 0.2721618 -0.2514146 0.9288265 0.03139156 -0.001356899 0.9995062 -0.7200991 -0.4365553 0.53933 0.5472885 0.3680112 0.7516936 0.03704369 -0.9788642 0.2011284 0.9375259 -0.3463441 0.03302973 -0.05856299 -0.1874219 0.9805322 -0.07244873 0.5244933 0.8483266 -0.2229499 0.4957147 0.8393808 -0.07404202 -0.05231362 0.9958821 -0.2194109 -0.1734754 0.9600861 0.5605949 -0.4444497 0.6987116 -0.8810106 0.4555689 0.1275826 -0.09288591 -0.01743167 0.9955242 0.4795117 -0.3677313 0.7967699 0.3405868 -0.6166926 0.7097119 0.6111252 0.3839932 0.6921526 0.7841521 0.5344512 0.3153846 0.5540792 0.5593165 0.6165722 0.9742661 -0.2188786 0.05383193 0.4687845 0.7368611 0.4871108 0.2839362 0.6269022 0.7255163 -0.9077907 0.4158809 -0.05439764 0.7182681 -0.6601059 0.2198889 0.8639047 -0.197722 0.4632221 0.9081653 -0.4172068 0.034271 -0.4353028 -0.245589 0.8661394 -0.3745511 -0.8026299 0.4642164 0.6904709 -0.5536136 0.4655771 0.07840907 0.9959412 0.04419457 -0.9159073 0.3968386 0.06027674 0.1654255 -0.8228891 0.5435881 0.7608873 -0.2317817 0.6060758 0.6916631 0.399331 0.6017782 0.6104758 0.5930679 -0.5249664 -0.07721245 0.9928982 0.09050768 0.2446149 0.968541 0.04573851 0.2008786 0.59356 0.7793167 0.5130371 0.6413071 0.570542 0.5970169 0.3500955 0.7218061 0.5792707 0.3342313 0.7434614 0.4241635 -0.7000012 0.5745291 -0.03249287 -0.7798341 0.6251425 -0.5436011 -0.3200753 0.7759186 -0.8213621 0.3670654 0.436609 -0.5890128 0.3539 0.7265114 -0.3843284 0.6470407 0.6585059 -0.3611676 0.5935032 0.7192441 0.6056541 0.355826 0.7117381 0.4319449 0.1968499 0.8801556 0.3504881 -0.4575451 -0.8171968 0.00922662 -0.01192146 0.9998864 -0.002403318 -0.6954806 0.718541 -0.6056406 -0.3576539 0.7108328 -0.6652412 0.2895392 0.6882015 -0.3561087 0.5864112 0.7275359 0.02650213 0.8099078 0.5859584 -0.02009809 0.6918743 0.7217382 0.6413802 -0.2884178 0.7109477 -0.008826911 -0.7119497 0.7021751 -0.5929946 -0.3444129 0.7278305 -0.6524319 0.3094762 0.6917782 -0.6395438 0.3094331 0.7037293 -0.3538954 0.5880636 0.7272821 -0.400584 0.6960896 0.595812 0.02643716 0.8087389 0.5875735 0.6018781 0.3538431 0.7159175 0.5544938 -0.2887738 0.7804784 0.3549255 -0.6337383 0.6873164 0.1489499 -0.1826795 0.9718242 0.002495229 -0.7157148 0.6983882 -0.6020408 -0.3533025 0.7160477 -0.5929459 -0.3444527 0.7278513 -0.6346101 0.2828046 0.7192299 -0.642326 0.2823858 0.7125136 -0.3504701 0.5740466 0.7400279 0.01457446 0.7278616 0.6855692 0.6045676 0.3546451 0.7132495 0.5976015 0.3478984 0.7223843 0.6144204 -0.3093657 0.7257965 0.366999 -0.5911085 0.7182636 -0.03242689 -0.7847987 0.6189019 -0.6362817 0.3181974 0.7027773 -0.3480071 0.578 0.7381106 0.6018428 0.3539428 0.7158979 0.5873851 0.339921 0.7344607 0.4697601 -0.277535 0.8380333 0.6421847 -0.2833935 0.7122408 0.3619652 -0.6174638 0.6983693 -0.591197 -0.3427436 0.7300774 -0.6006035 0.3040885 0.7394631 -0.4369016 0.7241305 0.5336217 -0.2657003 0.4889419 0.8308666 0.03119474 0.752955 0.6573322 0.01000565 0.711551 0.7025632 0.602043 0.3533015 0.7160463 0.5839584 -0.2827865 0.7609366 0.3437759 -0.5854426 0.7342174 0.2705956 -0.6420397 -0.7173306 -0.06055271 -0.6627778 0.7463639 -0.5281395 0.2812024 0.8012453 0.01000773 0.7115503 0.702564 0.5929457 0.3444547 0.7278506 0.2956032 -0.533613 0.7923862 -0.06635618 -0.6980676 0.7129507 -0.5911397 -0.34277 0.7301113 -0.4369068 0.7241401 0.5336043 0.03119647 0.7529447 0.657344 0.01000565 0.7115302 0.7025843 0.6422246 -0.2833939 0.7122046 0.3828323 -0.6514319 0.655039 0.2740796 -0.5003206 0.821316 -0.06424474 -0.704146 0.707143 -0.6019639 -0.3535848 0.715973 -0.3504765 0.5740633 0.7400119 -0.3885116 0.6589673 0.6440659 0.01975989 0.7129081 0.7009791 0.6628049 -0.3667088 0.652851 0.60384 -0.2992309 0.7388086 0.2956135 -0.5336283 0.7923721 -0.06416749 -0.7032727 0.7080185 -0.5913745 -0.3432617 0.7296901 -0.6423324 0.2823969 0.7125034 -0.3507985 0.5745875 0.7394523 0.02087146 0.7232404 0.6902809 0.6020575 0.353262 0.7160537 0.5941703 0.3455742 0.7263197 0.3282138 -0.5332662 0.7796813 0.003029823 -9.06078e-4 0.9999951 -0.8016489 0.3582029 0.4785916 -0.591029 0.3437223 0.7297532 -0.3509868 0.5992454 0.719523 -0.01917654 0.6905056 0.7230728 0.554441 -0.2887556 0.7805225 0.6412777 -0.2893047 0.7106798 0.3443112 -0.6400384 0.6868774 0.04193562 -0.7279217 0.6843767 -0.6020559 -0.3533029 0.7160348 -0.5929675 -0.3444601 0.7278303 -0.6423572 0.2824088 0.7124763 0.014575 0.7278561 0.6855751 0.5928112 0.3437655 0.7282858 -0.07276105 -0.9963603 0.04440855 0.01251006 0.9982934 0.05704134 0.03402459 0.9976688 0.05915677 -0.01453524 -0.9982576 0.05718898 0.6286644 -0.7732536 0.08282554 0.262932 -0.957431 0.1191339 -0.006818592 0.9950677 0.09896415 -0.2970311 -0.9533529 0.05376762 0.8945662 0.4444132 0.04741692 -0.352337 -0.9314195 0.09119486 0.5000004 -0.8660252 5.38921e-6 -0.9017851 0.4300802 0.04259818 0.01580846 0.9979678 0.06172907 0.8698257 0.4907069 0.05109077 0.8709052 0.4890203 0.04882103 1.27206e-4 -0.99553 0.09444713 -0.8840143 -0.465182 0.04609358 0.8651244 0.4994766 0.04564052 0.8651233 0.4994785 0.04564058 -0.8694266 0.492752 0.03595799 -0.8900937 0.4533909 0.0465815 -0.8713244 -0.4894809 0.03467351 -0.8755916 -0.4817644 0.0352478 0.04672735 0.9979624 0.04344755 -0.3693814 -0.924865 0.09045571 0.02468895 -0.9982503 0.05373018 0.8754221 -0.4819521 0.03685832 -0.8651198 -0.4994842 0.04564428 -0.8651125 -0.4994961 0.04565256 0.8906794 -0.45312 0.03704971 -0.1104522 -0.9931077 0.03921264 -0.8652215 -0.4993101 0.04562109 -0.8651078 -0.4994911 0.04579275 -0.868846 0.4932072 0.04304987 -0.4606381 -0.8858371 -0.05572444 -0.3932321 -0.9088631 -0.1390557 0.8944926 0.4441329 -0.05127614 0.5777097 0.8148269 -0.04805117 -0.05094802 0.9955818 -0.07887589 -0.9464263 -0.3124495 -0.08156359 -0.9383852 -0.3415361 -0.05278742 -0.9965897 0.04401481 0.06979918 0.4411236 0.8953399 0.06145328 0.939462 0.3419153 0.02247738 0.9972331 -0.06570482 0.03477281 0.7512072 -0.6531202 0.0955094 0.1455442 -0.9771029 0.1551991 0.1078946 0.7162492 0.6894533 -0.684633 0.3559159 0.6360831 0.3170351 0.685249 0.6556847 0.3571389 0.267875 0.8948156 0.4209873 0.05711346 0.9052667 0.1472623 -0.09388166 0.984632 0.1109166 -0.35581 0.927953 0.3977733 -0.7268015 -0.5599429 -0.09859699 -0.3902088 0.9154321 -0.1718272 -0.3498637 0.9209077 -0.4464182 -0.05474829 0.893148 -0.4148769 -0.03908741 0.9090377 -0.5362762 0.06792795 0.8413048 -0.8646321 0.1237909 0.4869161 0.1748548 0.392326 0.9030538 0.621461 0.6197283 0.4792945 0.4470731 0.4394134 0.7791287 0.5222219 0.2746304 0.80738 0.4936588 0.03763896 0.8688409 0.5464065 -0.1885454 0.8160212 0.2725064 -0.6065298 0.7469015 0.008699715 -0.4078592 0.9130035 -0.07015484 -0.3370925 0.9388542 -0.164522 -0.3919147 0.9051715 -0.4708437 -0.4604226 0.7525407 -0.7847669 -0.3889198 0.4825791 -0.6020489 -0.297683 0.7408927 -0.2052229 0.09773707 0.9738229 0.2602166 -0.616137 0.7434127 -1.62162e-7 0 -1 4.56691e-7 0 -1 -5.32295e-7 -4.50586e-7 -1 -1.61716e-6 2.9945e-7 -1 9.269e-6 5.13575e-6 -1 -1.71692e-6 0 -1 -8.54526e-6 -1.50932e-6 -1 1.34544e-6 4.62242e-6 -1 -0.8652006 0.4995223 -0.0436508 0.4995154 0.8652048 -0.04364711 0.01244568 -0.05549871 -0.9983812 -2.19838e-6 0 -1 -0.4640888 0.2733762 0.8425481 0.9034024 0.4268976 0.04028391 0.8420532 -0.5392529 0.01236045 0.01788878 -0.004489421 0.99983 0.4988473 -0.2939971 0.8153019 0.512941 -0.2995496 0.8044636 0.8602201 -0.5087291 0.03487461 0.8647627 -0.5000315 0.04641139 -0.2056344 -0.9772143 0.05259925 -0.02727591 0.02260708 -0.9993724 0.8843976 0.459559 0.08152562 -0.07383191 0.9959418 0.05146926 -0.4116389 0.2608128 -0.8732298 -0.4385771 0.22161 -0.8709416 -0.4380855 0.2125889 -0.8734341 -0.452924 0.2159504 -0.8650001 -0.3950058 0.247643 -0.8846714 -0.4497583 0.2748773 -0.8498001 -0.4159146 0.256433 -0.8725007 -0.4341897 0.2546698 -0.8640732 -0.4301928 0.2565585 -0.8655125 -0.4378756 0.247972 -0.8641614 -0.4590985 0.2407369 -0.8551458 -0.4385823 0.2440154 -0.864929 -0.4527508 0.2338507 -0.8604247 -0.5117117 0.2761837 -0.8135563 -0.4739903 0.2322509 -0.8493485 -0.4538561 0.2291656 -0.8611028 -0.4490624 0.2432196 -0.8597599 -0.4343148 0.2473108 -0.8661454 -0.4368909 0.2476465 -0.864753 -0.434705 0.2467486 -0.8661102 -0.4200251 0.2621536 -0.8688236 -0.441236 0.2816436 -0.8520492 0.1025086 0.2071022 -0.9729341 0.008470356 -0.001962602 -0.9999622 1.32873e-4 -4.3269e-5 -1 -1.73259e-5 6.66314e-6 -1 0.009488701 -0.005478262 -0.99994 -0.02703416 0.01998734 -0.9994348 7.04835e-4 -4.10609e-4 -0.9999998 0.007589578 0.05455553 -0.9984819 0 0 -1 -9.63109e-7 0 -1 0.001180768 -6.32122e-4 -0.9999992 -0.09000462 0.03877139 -0.9951865 -6.04971e-7 0 -1 -8.80895e-4 9.37811e-4 -0.9999992 0 0 -1 -0.05629515 0.02272498 -0.9981556 -0.05613052 0.02517527 -0.9981061 -0.06188601 0.03197187 -0.9975711 -5.38731e-5 7.26171e-4 -0.9999998 1.21017e-6 0 -1 0.004004359 -0.001912355 -0.9999902 1.20203e-7 0 -1 8.28517e-7 0 -1 0.002336442 -0.001250684 -0.9999966 -2.5311e-4 7.64776e-4 -0.9999998 1.20209e-7 0 -1 3.55993e-5 -2.42214e-5 -1 -3.57892e-5 2.07498e-4 -1 -0.01525276 -0.001270711 -0.9998829 0.002383351 -5.36295e-4 -0.999997 -0.01230597 0.02126556 -0.9996981 -0.08455538 0.05940806 -0.9946462 -2.74335e-5 1.99183e-5 -1 6.84801e-6 -5.25952e-6 -1 -3.87656e-6 2.02836e-6 -1 1.513e-7 0 -1 4.73958e-6 -1.65821e-6 -1 -0.0978499 0.04225826 -0.9943037 -0.007242619 0.02073144 -0.9997589 -0.001143634 6.36115e-4 -0.9999992 0.2946117 0.4780706 -0.8274372 0.3243297 0.5513998 -0.7686147 -0.6254231 -0.7469086 0.2257732 0.7904054 0.3285253 0.5170403 0.3293668 0.1959336 0.9236491 -0.3079059 0.2417309 0.9201958 -0.2937546 -0.5265095 0.797807 -0.8246034 0.5506153 0.1298158 0.8983539 0.4336977 0.06976187 0.9808278 0.1948313 -0.004200816 -4.60529e-4 3.35783e-4 1 4.96703e-4 -0.001275181 0.9999991 -0.8823877 -0.3978981 0.251136 -0.392296 0.2246887 0.8919747 0.2534508 0.427989 0.8675184 -0.0822044 0.9959141 0.037386 -0.09514123 0.9949086 0.0332424 0.5060479 0.8621373 0.02519941 0.913285 0.4070261 0.01550722 0.8852623 0.463334 0.04040157 0.8616482 -0.5066466 0.02952516 0.1085575 0.1295731 0.9856096 0.8145271 -0.4156141 0.4047355 -0.07528156 0.6647786 0.7432376 -0.5120918 0.3068277 0.8022586 -0.5785784 0.3321585 0.744928 -0.8658271 0.5000023 0.01847511 -0.08437812 0.9960258 0.02851444 -0.100507 0.9949331 0.002558946 0.8564387 0.3477342 0.3815678 0.6389672 0.7691699 -0.009942233 -0.5983354 0.348124 0.7216679 -0.6010333 0.3502977 0.7183666 0.5312993 -0.3071153 0.7895576 -0.4184799 -0.2169567 0.8819323 -0.8693525 0.4932017 0.03127866 -0.8632459 0.5034236 0.03703206 -0.864665 0.5008972 0.03816634 -0.01812446 -0.002302885 0.9998331 -0.001032233 -0.006964027 0.9999752 0.6028717 -0.3339722 0.7245745 0.1826253 -0.507416 0.8421266 0.9102908 0.4116199 0.04404276 0.9937285 0.1090418 0.02477204 0.8655154 -0.4996661 0.03488403 0.02799338 -0.02079844 0.9993917 2.22752e-4 0.00120902 -0.9999993 0.8313931 -0.5540927 0.04203313 -0.388803 -0.9161495 0.09748107 0.5647978 -0.2387672 -0.7899327 -0.8928893 0.4489043 0.035124 -0.8937107 0.4474181 0.03314089 -0.8951256 0.4444603 0.03471595 -0.5102208 0.8525293 0.1134402 0.4237129 0.9015179 0.08793687 0.4290817 0.8990803 0.08685457 3.73401e-4 -8.29626e-5 -1 0.01911503 0.01721829 -0.9996691 0.3045324 0.5369856 -0.7867061 0.3158673 0.5585693 -0.7669604 -0.5493533 0.8012333 -0.2371422 0.2229124 -0.9747716 0.01142275 0.2027716 -0.979187 -0.008754789 0.6913856 0.7224436 -0.007821917 -0.6934823 -0.7204432 -0.00662738 -0.2589182 -0.9605618 0.1014028 -0.7005829 0.71025 -0.06876486 -0.4390517 0.897881 0.03229969 0.2782303 -0.9530777 0.1192929 0.9655898 0.2591783 -0.02151453 0.9542593 0.2989683 0.002681255 -0.258343 0.9660528 9.82457e-4 -0.8646333 0.50042 -0.04460132 -0.8652048 0.4995186 -0.04361134 0.8652002 -0.4995247 -0.04363334 0.8652002 -0.4995249 -0.04363024 0.8652439 -0.4994621 -0.04348474 0 1.81865e-7 -1 1.449e-6 -1.7146e-6 -1 7.77411e-6 0 -1 -4.14968e-6 2.09867e-6 -1 -0.4656268 -0.8064954 -0.3643581 -0.8856372 -0.3588818 -0.2947041 8.58631e-7 0 -1 -0.8661226 0.4998316 -5.8053e-5 -0.8660255 0.5 0 -0.8660252 0.5000004 0 0.8884889 0.3866512 -0.2471609 -0.1894904 -0.9816352 -0.0220437 0 0 -1 0.05370396 0.08810806 -0.9946622 -0.5001524 -0.8659375 -4.09179e-4 -0.331108 0.8223692 -0.462684 -0.9817496 0.1895112 0.01591736 -0.7567138 -0.6537463 0 -0.7727599 -0.5249799 -0.3567048 -0.1732852 -0.3337074 -0.9266131 -0.7306236 -0.6286433 -0.2664526 -0.8055565 0.5925191 0 0.2588282 0.9659206 -0.002331674 -0.2882606 -0.4473956 -0.8466068 -0.3938261 -0.712831 -0.5803216 -0.1503363 -0.2395457 -0.9591752 0.3036779 0.5451326 -0.7814154 0.376133 0.6431207 -0.6670231 0.4890893 0.8471268 -0.2077687 0.4811984 0.8296818 -0.2829775 0.4999969 0.8660273 3.82226e-7 0.5000001 0.8660253 -4.9507e-7 0.4999965 0.8660274 -2.8667e-7 0.3443266 0.6490002 -0.6784084 0.4872438 0.8677523 -0.09797734 0.8660256 -0.4999997 0 0.8660247 -0.5000014 -1.10967e-6 0.8660248 -0.5000012 -8.17179e-7 0.8660247 -0.5000014 3.69082e-6 -0.8660266 0.499998 1.27554e-6 -0.8660257 0.4999996 -1.54213e-5 -0.4971962 0.8676347 -0.002462089 -0.4863744 0.8737504 6.11351e-4 -0.5000104 0.8660194 7.10202e-6 0.9998889 0.0149132 0 1 -1.45666e-4 -1.27769e-5 -0.666864 -0.6828234 0.2984035 -0.5339725 0.2496533 0.8078037 -0.5212085 0.2429435 0.8181199 -0.5291812 0.2279973 0.8173033 -0.364058 0.2673235 0.8921884 -0.4959022 0.2863485 0.8198083 -0.5466551 0.1745259 0.8189682 -0.5472855 0.2513443 0.7983137 -0.4056828 0.2285887 0.8849682 -0.5310094 0.3614022 0.7664318 -0.4103466 0.2407445 0.8795783 -0.4956927 0.2861114 0.8200178 -0.4443662 0.245905 0.8614346 -0.4249342 0.2488699 0.8703418 -0.3985549 0.2988222 0.8670982 -0.5182842 0.2869162 0.805643 -0.5243264 0.2788547 0.8045632 -0.5125579 0.2842795 0.8102282 -0.5016947 0.2915053 0.814449 -0.5629429 0.3905323 0.7284091 -0.5658668 0.2388374 0.7891461 -0.4715729 0.2181918 0.854407 -0.5587801 0.3297241 0.7609512 -0.9510026 -0.1110715 -0.2885432 -0.1149777 0.6256203 0.7716084 0.6495841 -0.3825361 0.657044 0.2190286 0.7700678 0.5991845 -0.4806312 -0.8495884 0.2172399 -0.5143102 -0.856309 0.04711765 -0.3307411 0.7748513 0.5387169 -0.2966421 0.7527754 0.5876502 0.815013 -0.4157375 0.4036286 -0.9732205 -0.2204647 -0.06509435 -0.002984404 -0.008348762 0.9999608 0.001168727 -1.48519e-4 0.9999994 -0.3132294 0.06781083 0.9472535 -0.01368218 0.007973611 0.9998747 -0.001446962 0.004278123 0.9999898 0.001077413 -6.47221e-4 0.9999992 3.27753e-4 -2.11799e-4 1 -0.02899229 0.01678782 0.9994387 -0.001123011 0.002112925 0.9999971 0.003098785 -0.001759588 0.9999938 4.34007e-4 -4.2023e-4 0.9999998 3.54299e-4 -3.66499e-4 0.9999999 -7.28112e-4 1.54559e-4 0.9999998 0.00336045 -0.00186491 0.9999926 0.002182722 -0.001551151 0.9999964 0.001772105 -6.60143e-4 0.9999983 0.002775371 -0.001639425 0.9999948 -2.84247e-4 1.36196e-4 1 -1.52761e-4 -2.14598e-4 1 5.46437e-4 -3.96059e-4 0.9999998 -2.26186e-4 -2.18693e-4 1 0.002310395 -0.001702666 0.999996 0.001514732 -5.57697e-4 0.9999988 0.002244174 -0.001320421 0.9999966 2.808e-4 -1.79096e-4 1 -0.21535 0.2287538 0.9493662 3.65045e-4 -1.93326e-4 1 0.1719446 0.009988248 0.985056 0.003337323 9.1833e-4 0.9999941 -0.002807557 0.002154707 0.9999938 -0.005269348 0.002937316 0.9999818 0.02976286 -0.06210368 0.9976259 -0.002258002 0.001359403 0.9999966 -0.00194019 0.001189708 0.9999974 0.1238469 -0.02746295 0.9919213 0.2316589 -0.2169638 0.9482936 -0.002277016 0.001058876 0.9999969 2.33394e-4 -4.0711e-4 0.9999999 -0.001939415 0.001096189 0.9999976 -0.002855658 0.001467823 0.9999949 -0.002995908 0.001726925 0.999994 -2.276e-4 1.18002e-4 1 -1.31624e-4 -3.99618e-4 1 -0.002002477 0.001457691 0.999997 -6.35316e-4 3.59039e-4 0.9999998 -2.01953e-4 1.06941e-4 1 0.07360649 -0.04012501 0.9964799 -0.001598238 6.48533e-4 0.9999986 -8.3781e-4 6.86431e-4 0.9999995 -0.007332086 0.004454255 0.9999633 0.1112232 -0.00774759 0.9937653 -0.002204775 0.001257002 0.9999969 7.66191e-4 1.56952e-4 0.9999997 0.05692243 -0.03811162 0.997651 -6.50784e-4 2.55425e-4 0.9999998 0.02303206 -0.01712453 0.9995881 -0.007033109 0.008109629 0.9999424 -0.002004563 0.001253187 0.9999972 0.06816846 -0.0616343 0.9957682 -4.68066e-4 3.64109e-4 0.9999998 0.02174097 0.003303229 0.9997583 -0.003148794 0.001903474 0.9999933 -0.001420617 3.4723e-5 0.999999 -6.21462e-5 1.48913e-4 1 3.29836e-4 6.19782e-4 0.9999998 -0.001975834 0.001189351 0.9999974 0.005773782 0.01089775 0.999924 0.001570463 2.47442e-4 0.9999988 -8.16662e-5 -4.49866e-5 1 -2.2468e-4 1.06655e-4 1 1.27029e-4 1.74566e-5 1 -1.11036e-4 2.31822e-5 1 1.09665e-4 2.77992e-4 1 0.002364873 -0.001325368 0.9999964 -1.46521e-4 -8.20635e-5 1 6.95868e-4 -3.95027e-4 0.9999998 0.003024518 -0.001624763 0.9999941 -6.52573e-4 4.01789e-4 0.9999997 0.001092612 -7.27533e-4 0.9999992 6.81414e-4 5.72383e-4 0.9999997 -0.07656896 0.9518334 0.2969014 0.8071198 -0.4548718 0.3763632 0.8626703 -0.4973224 0.09203606 0.3755086 -0.2188181 0.9006177 -0.1157823 0.0668962 0.9910194 -0.4643295 0.26823 0.844068 -0.7842425 0.4639433 0.4119716 -0.2127454 0.1206119 0.9696351 -0.8660241 0.5000025 -3.07029e-5 -0.8651987 0.4995281 -0.04362255 -0.8652045 0.4995188 -0.04361695 -0.8651999 0.4995266 -0.04361724 -0.8652016 0.4995234 -0.04361951 -0.8652011 0.4995248 -0.04361319 -0.865202 0.4995229 -0.04361826 -0.8652029 0.4995211 -0.04361933 -0.865199 0.4995272 -0.04362642 -0.8652046 0.499517 -0.04363226 -0.8652004 0.4995247 -0.04363065 0.8652033 -0.4995204 -0.0436204 0.8651997 -0.4995262 -0.04362368 0.8652015 -0.4995238 -0.04361867 0.8652028 -0.4995214 -0.04361754 0.8651983 -0.499529 -0.04362159 0.8652006 -0.499524 -0.04363316 0.8652005 -0.4995239 -0.04363363 -0.865193 0.4995398 -0.04360258 0.4995221 0.8652011 -0.04364669 0.4995143 0.865206 -0.04363602 0.02177482 0.03771466 -0.9990513 -0.02764517 0.0212565 -0.9993919 -0.01244574 0.05549979 -0.9983812 -0.4994978 -0.8652171 -0.04360336 0.4995236 0.8652018 -0.04361438 -0.499523 -0.8652021 -0.04361307 0.4995118 0.865207 -0.04364627 -0.02994436 0.0172885 -0.9994021 -0.4995216 -0.8652015 -0.04363948 0.499518 0.8652055 -0.04360461 0.02177488 0.03771471 -0.9990513 -0.4995246 -0.8652015 -0.0436083 -0.4995228 -0.8652024 -0.04361021 -0.4995289 -0.8651984 -0.04361915 -0.4995273 -0.8651998 -0.04361039 2.17893e-7 0 -1 0.4995209 0.8652036 -0.0436092 0.4995293 0.865199 -0.04360347 0.499527 0.8651996 -0.04361575 0.05087411 0.01915132 -0.9985215 -0.4995363 -0.8651943 -0.04361605 -0.4995087 -0.8652119 -0.04358315 -2.17898e-7 0 -1 0.4995087 0.8652101 -0.04361945 0.4995223 0.8652009 -0.04364645 0.05087482 0.01915162 -0.9985215 -0.02994453 0.0172885 -0.9994021 0.02177476 0.03771495 -0.9990513 -0.499524 -0.8652015 -0.04361641 2.17899e-7 0 -1 -2.17893e-7 0 -1 0.499527 0.8652 -0.04360961 0.05087453 0.01915109 -0.9985215 -0.02994465 0.01728832 -0.9994021 0.02177447 0.0377143 -0.9990513 -0.4995281 -0.8651987 -0.04362416 -0.499525 -0.865201 -0.04361486 0.4995089 0.8652092 -0.04363542 0.4995254 0.8652007 -0.04361575 2.18115e-7 0 -1 -0.499519 -0.8652039 -0.0436244 -0.4995235 -0.8652005 -0.04364222 0.499526 0.8652004 -0.04361402 0.4995274 0.8651993 -0.04361921 0.4995178 0.8652045 -0.04362821 -0.02994471 0.0172885 -0.9994021 -0.499524 -0.8652013 -0.04361945 -0.4995253 -0.8652006 -0.04361653 0.4995249 0.8652009 -0.04361569 -0.02994465 0.0172885 -0.9994021 0.02177464 0.0377146 -0.9990513 -0.4995238 -0.8652017 -0.04361379 -0.4995256 -0.8652004 -0.04361641 -0.4995222 -0.8652024 -0.04361909 0.4995207 0.8652032 -0.04361915 0.4995239 0.8652013 -0.04361879 0.05087471 0.01915132 -0.9985215 -0.4995224 -0.8652021 -0.04361939 -0.4995235 -0.8652012 -0.0436269 -2.17895e-7 0 -1 -0.02994489 0.01728844 -0.9994021 -0.4995236 -0.8652016 -0.04361641 -0.4995234 -0.8652017 -0.04361659 2.17894e-7 0 -1 0.4995231 0.8652016 -0.04362177 0.0217747 0.0377146 -0.9990513 -0.4995237 -0.8652017 -0.04361408 1.60481e-5 2.37396e-4 -1 -1.99465e-4 1.15407e-4 -1 0.4995232 0.8652018 -0.04361921 0.4995211 0.8652029 -0.04362177 -0.4995229 -0.8652018 -0.04362177 -0.4995226 -0.8652021 -0.04361873 0.02994453 -0.01728838 -0.9994021 0 0 -1 0 0 -1 -0.8002527 0.4620283 -0.3822634 -0.8002215 0.4620122 -0.3823485 -0.8002533 0.4620267 -0.3822643 -0.8001776 0.4619765 -0.3824833 -0.8001786 0.4619756 -0.3824825 -0.8002544 0.4620244 -0.3822648 -0.800245 0.4620214 -0.382288 -0.8002396 0.4620199 -0.3823015 -0.8002457 0.4620219 -0.382286 -0.8002455 0.4620215 -0.3822871 -0.8002451 0.4620213 -0.3822883 -0.8002503 0.4620229 -0.3822753 -0.8002419 0.4620196 -0.3822968 -0.8002431 0.4620197 -0.3822942 -0.8002401 0.4620188 -0.3823018 -0.8002148 0.4620066 -0.3823693 -0.8003033 0.462049 -0.3821327 -0.8002525 0.4620209 -0.3822732 0.8002423 -0.4620222 -0.3822932 0.8002782 -0.4620311 -0.3822072 0.8002499 -0.4620297 -0.3822678 0.8002108 -0.4620019 -0.3823832 0.8002523 -0.4620289 -0.3822638 0.8002754 -0.4620324 -0.3822113 0.800368 -0.4620802 -0.3819594 0.8002651 -0.4620379 -0.3822262 0.8002154 -0.4619983 -0.3823781 0.8002619 -0.4620311 -0.382241 0.800214 -0.4619995 -0.3823794 0.8002445 -0.4620217 -0.3822889 0.8002436 -0.4620198 -0.3822932 0.8002411 -0.4620171 -0.3823015 0.8002489 -0.4620267 -0.3822737 0.8002485 -0.4620206 -0.3822818 0.8002478 -0.4620203 -0.3822835 0.8002445 -0.4620205 -0.3822902 0.8002465 -0.4620245 -0.3822816 0.8002483 -0.4620214 -0.3822813 0.4995406 0.8651908 -0.04363554 -3.92753e-4 -6.80168e-4 -0.9999998 0.1440744 0.7990239 -0.5837837 0.1812984 0.8085133 -0.5598547 0.0343132 0.8219527 -0.5685213 -0.03480994 0.8164954 -0.5763016 -0.1129906 0.8152086 -0.5680389 -0.6745648 0.4672644 -0.5715124 -0.6726837 0.4719553 -0.5698727 -0.7494193 0.3427991 -0.5664446 -0.7975662 0.2060897 -0.566935 -0.7986545 0.1883116 -0.5715678 -0.7759706 -0.2470144 -0.580391 -0.7848709 -0.2281895 -0.576114 -0.7243713 -0.3889928 -0.5691844 -0.7041609 -0.4155395 -0.5757469 -0.643091 -0.511857 -0.5695934 -0.5977572 -0.5604048 -0.5732651 -0.5345555 -0.6211084 -0.5731273 -0.5220679 -0.6555774 -0.5455855 -0.2705863 -0.7734876 -0.5731493 -0.1862486 -0.7978246 -0.5734 -0.126267 -0.8134455 -0.5677703 -0.2527122 -0.7795208 -0.5731352 -0.2523604 -0.7796021 -0.5731796 -0.5496806 -0.6063366 -0.5746365 -0.5404924 -0.6162182 -0.5728377 -0.6413428 -0.5160771 -0.5677534 0.02524495 -0.8193392 -0.572753 0.3676559 -0.7280952 -0.5785382 0.5840204 -0.5818885 -0.5659735 0.5709826 -0.588844 -0.5720504 0.6748164 -0.4775261 -0.5626649 0.6865961 -0.4493891 -0.5715202 0.7796759 -0.2549204 -0.5719451 0.81778 -0.09019917 -0.5684189 0.8222467 0.04078227 -0.5676683 0.7998447 0.1534517 -0.5802595 0.7663748 0.3010109 -0.5675054 0.705646 0.416377 -0.5733184 0.620448 0.5417811 -0.5670253 0.61581 0.5559254 -0.5583233 0.1757301 -0.8024368 -0.5702756 0.6128045 0.5347607 -0.5818089 0.5241782 0.6481118 -0.5524385 0.5807363 0.5983346 -0.5520337 0.6078682 0.5604017 -0.5625357 0.6003153 0.5611187 -0.5698838 0.6909675 0.4777652 -0.5424984 -0.46315 0.6841605 -0.5633974 0.9121624 -0.409818 -0.00303775 0.8302945 0.557318 -0.002813398 0.5432198 0.8395858 -0.002816021 0.3630897 0.9317504 -0.002646744 0.1681004 0.9857667 -0.002527356 -0.5986819 0.8009834 -0.002377033 -0.7476449 0.6640948 -0.002318799 -0.9489426 0.3154408 -0.002267777 -0.9930164 0.1179574 -0.002116382 -0.9590516 -0.2832248 -0.002003014 -0.7696605 -0.6384516 -0.001522719 -0.5000005 -0.8660241 0.001411378 -0.6175468 -0.786532 -0.001890301 0.8594806 0.5111598 0.00297141 0.4095675 0.9122754 0.002824604 0.01380109 0.9999011 0.002734363 -0.7194551 0.6945347 0.002465367 -0.9879319 0.1548727 0.002278447 -0.8973686 -0.4412772 0.002072811 -0.7736417 -0.6335408 0.01022517 -0.6920072 -0.7218906 3.4791e-4 -0.2669406 -0.9637004 -0.004931747 -0.1525615 -0.988282 0.004870951 0.2674701 -0.9635603 0.00335282 0.6276163 -0.778516 0.003267884 -0.2671968 -0.9636293 -0.004969596 0.5886428 -0.3707978 -0.7183375 0.7266436 -0.4134723 -0.5486617 -0.2361691 0.1366426 -0.9620567 -0.8331906 0.4810482 -0.2727382 -0.7916225 0.4600714 -0.4020797 -0.5603402 0.3152461 -0.7659236 -0.6353155 -0.7177256 0.2850337 -0.02026975 0.01530337 0.9996775 -0.3772685 -0.1349462 0.9162194 -0.07351988 0.1093915 0.9912762 -0.8267019 0.4597413 0.3243486 -0.6224223 -0.3498553 0.7001371 -0.4012058 -0.3770068 0.8348053 -0.9778043 -0.2094662 0.004774034 -0.8884782 -0.4548172 0.06121969 0.726619 -0.3169763 0.6095498 0.4590435 -0.6866207 0.5637652 0.7312727 -0.5394858 0.4173671 -0.6256197 -0.7771633 -0.06795066 -0.7747678 -0.6320084 0.01732879 -0.8778901 -0.4738425 -0.06915509 0.8813306 0.4704201 0.04428541 0.003325164 0.006714284 0.999972 0.02436643 0.06774461 0.9974051 -0.1873208 0.253059 0.9491428 0.1676886 -0.03164559 0.985332 0.03773176 -0.03430509 0.9986989 -0.5145524 -0.8545722 0.07030129 -0.887077 0.4261643 -0.1774216 -0.6238257 0.7757713 0.09497702 -0.99304 0.03828096 -0.1113836 -0.6642107 0.7467006 -0.0355286 0.7308702 -0.3666353 0.5756799 0.01051408 0.08983689 0.9959011 0.364031 0.1655982 0.9165471 0.7043882 0.7057046 0.0762785 0.04610604 -0.02232754 0.998687 0.6626103 -0.4019257 0.6319838 0.8579857 -0.4925833 -0.1456788 0.8660336 -0.4985179 -0.03828322 0.6275382 -0.6195734 0.4715133 0.9993299 0.03660148 5.48783e-4 0.7990262 0.5444096 0.255295 -0.9644114 0.1945796 -0.1790238 -0.0732603 -0.981468 -0.1770696 -0.574262 0.8007617 0.1703051 0.1016517 -0.9869692 0.1247344 0.9948132 -0.08011823 0.0626738 -0.1981171 -0.9795247 0.03579413 -0.9582382 0.233222 0.1654908 0.679804 0.7309584 -0.05972009 -0.9164184 -0.3576434 -0.1796348 -0.1904903 0.9732298 0.1285969 0.1761184 -0.9613571 0.2116009 -0.9983919 -0.04664766 0.03221458 0.4090819 -0.7519989 -0.5168651 0.9544401 -0.1487256 0.2586983 -0.5846793 0.737752 -0.3374495 -0.8977513 -0.3755755 0.2301865 0.2828575 0.8409302 -0.4613331 0.3969396 -0.9087375 0.1289776 -0.02548068 0.9903568 -0.1361771 -0.8612202 0.1986386 0.4678062 -0.6991173 -0.398126 0.5939115 -0.7369784 0.2949011 0.608191 -0.7379199 0.3552553 0.5738188 -0.5953302 0.6319254 0.496238 -0.9219282 0.2413302 0.3029985 8.12112e-4 -4.14413e-4 -0.9999997 2.20349e-6 -1.08065e-6 -1 -2.3795e-6 -9.39968e-7 -1 0 2.18318e-7 -1 0.02573764 9.96325e-4 -0.9996683 0.03939133 -0.02643978 -0.998874 2.07892e-4 -2.09606e-4 -1 -0.001672387 1.90496e-4 -0.9999986 -0.00153619 -8.7419e-4 -0.9999985 -0.09649091 0.01197868 -0.9952619 4.39916e-4 2.60173e-6 -1 6.27326e-4 -2.72422e-4 -0.9999998 0.8241294 -0.01131635 0.5662887 -2.4864e-5 1.67171e-5 -1 7.5557e-7 2.30714e-7 -1 -1.33926e-5 7.33442e-6 -1 -0.001591682 3.50328e-4 -0.9999987 0.003893375 -0.01061731 -0.9999361 -0.05142998 0.0345394 -0.9980792 0.001697421 -1.95988e-4 -0.9999986 -9.31708e-6 -5.64524e-5 -1 -1.02629e-4 7.56073e-5 -1 0.9454936 0.09423923 -0.3117066 -0.9444775 -0.1122356 -0.308813 -0.4666054 -0.8671765 -0.1740245 0.0408234 0.9676221 0.2490805 -0.6647421 -0.7321118 0.1487628 0.1740077 -0.9819332 -0.0743547 0.9091195 -0.4082542 0.08264595 -0.001749932 0.001892149 -0.9999967 -8.20908e-4 -2.90269e-4 -0.9999997 -0.005079805 0.001133739 -0.9999865 -0.004964351 6.00293e-4 -0.9999875 0.00113815 0.005130827 -0.9999862 0.94445 0.1122975 -0.3088747 0.3265613 0.8823984 -0.3387194 -0.7973893 0.5989446 -0.07372844 -0.760542 -0.5894416 -0.2722763 -0.7816988 0.3512481 -0.5153365 -0.003261208 -0.001495063 -0.9999936 -6.87838e-5 -2.6932e-4 -1 -4.11678e-4 -1.66387e-4 -1 -0.001220345 0.002350866 -0.9999966 0.002929508 -0.003557264 -0.9999895 3.60696e-4 -7.99523e-4 -0.9999997 -0.8615359 0.507219 -0.02202284 -0.8615869 0.5061681 -0.03823554 0.9130334 0.4077418 0.01080524 0.9251239 0.3344663 -0.1796611 0.974927 0.2112625 0.06989741 0.9909736 0.08090692 0.1068899 0.6291489 -0.7738136 0.0733779 0.9758371 -0.08037358 -0.2031801 0.6609985 -0.7496397 -0.0334872 0.8524444 0.5224601 0.01934635 -1.78618e-4 5.52604e-5 1 3.99875e-4 0.001846492 0.9999983 -0.05754423 -0.03460103 0.9977432 -0.006607651 -6.18573e-4 0.9999781 -0.008414983 -0.002196729 0.9999622 -0.002637922 -0.002645492 0.999993 -0.03424489 0.0132513 0.9993257 -0.02838122 0.02582687 0.9992635 -0.03300976 0.02604812 0.9991156 -0.005764663 -0.01550281 0.9998633 0.01270204 -0.01137369 0.9998547 0.01308125 -0.02187782 0.9996751 -8.70584e-4 5.67813e-4 0.9999995 -1.72994e-4 1.78258e-4 1 1.21304e-4 -5.12254e-5 1 0.1036065 -0.9940888 0.03245311 -0.2047744 -0.9777188 -0.04618769 -0.673711 0.738514 -0.02665835 0.8142863 -0.5768169 -0.06496274 -0.6825858 0.7301656 -0.0305776 -0.092651 -0.9945195 -0.0484448 -0.6736425 0.7385771 -0.02663892 0.9761486 -0.2151228 -0.02926218 -0.6824904 0.7302567 -0.03052973 0.9566749 -0.2911561 0.001084864 0.8608784 -0.5053644 -0.05912268 -0.8680992 0.4928554 -0.05914002 -0.4995224 -0.865203 -0.04360288 0.6123735 -0.3535524 0.7071064 0.6123728 -0.3535539 0.7071064 0.6123732 -0.3535523 0.7071067 0.6123739 -0.3535537 0.7071054 0.612374 -0.3535538 0.7071053 0.6123687 -0.3535509 0.7071112 -0.6123313 0.3535344 -0.707152 0.6123753 -0.3535558 0.7071031 0.6123815 -0.3535596 0.7070958 0.6123719 -0.3535503 0.7071087 0.6123776 -0.3535563 0.7071009 0.612362 -0.3535495 0.7071179 -0.612147 0.3534521 -0.7073526 0.6124039 -0.3535673 0.7070726 0.6120306 -0.353391 0.7074838 0.612392 -0.3535547 0.7070893 0.6123737 -0.3535545 0.7071052 0.6123604 -0.3535462 0.7071208 -0.6123719 0.3535515 -0.7071082 -0.6324918 0.4258658 -0.6469872 -0.6606689 0.3814373 -0.6465464 -0.6461239 0.2947957 -0.7040024 -0.646126 0.294797 -0.704 -0.6461234 0.2947946 -0.7040035 -0.6461257 0.2947933 -0.7040017 -0.6606695 0.3814341 -0.6465477 -0.6606675 0.3814296 -0.6465523 -0.6606646 0.3814406 -0.6465489 -0.6461207 0.2947916 -0.704007 -0.6461207 0.294786 -0.7040094 -0.6606509 0.3813086 -0.6466406 -0.6123706 0.3535619 -0.7071042 -0.6606684 0.3814374 -0.6465468 -0.646125 0.2947998 -0.7039998 0.6123731 -0.3535523 -0.7071068 0.6203584 -0.3559194 -0.6989113 0.5783672 -0.4121591 -0.7040002 0.5783631 -0.4121611 -0.7040025 0.6606699 -0.3814356 -0.6465464 0.6606668 -0.3814355 -0.6465496 0.5783737 -0.4121576 -0.7039958 0.6606632 -0.3814366 -0.6465526 0.660668 -0.3814426 -0.6465442 0.6606717 -0.3814346 -0.6465452 0.6606693 -0.3814386 -0.6465453 0.5783679 -0.4121625 -0.7039977 0.5783631 -0.4121549 -0.7040061 0.6606733 -0.381429 -0.6465469 0.6606646 -0.3814322 -0.6465539 0.6606733 -0.381429 -0.6465468 -0.001621842 0.001060605 -0.9999982 -3.59211e-4 -6.22421e-4 -0.9999998 -0.4045909 0.1895739 0.8946329 -0.6095731 0.2746903 0.7436168 -0.6108922 -0.6045338 0.5112237 0.5313257 -0.2149656 0.8194406 -0.6426066 0.43768 -0.6288824 0.8490305 -0.06001073 0.5249249 0.8443704 -0.2032976 0.4956903 0.05078232 0.3256908 0.9441117 0.1536028 0.3483251 0.9247031 0.4634265 -0.02177256 0.885868 -0.6221218 0.2239329 0.7502125 -0.6832 0.5027509 0.5296031 -0.8684254 -0.2478381 0.4294341 0.6120332 0.7839468 0.1041287 0.9714419 0.2316057 0.05157095 -0.4231358 -0.6826696 0.5957502 -1.46345e-5 8.44706e-6 1 0.008987367 0.01419943 0.9998589 0.08613812 -0.995634 0.03596168 0.09389007 -0.9950345 0.03303045 -0.4887297 -0.8717274 0.03513759 -0.4889428 -0.8716231 0.0347585 -0.885411 -0.4635943 0.03358149 -0.3633263 0.155572 0.9185812 -0.8659188 0.4993159 0.02946615 -0.8691446 0.4933571 0.03444719 -0.5128265 0.8561719 0.06307744 -0.0835852 0.9958509 0.0359795 -0.1039033 0.9941303 0.03015208 0.1361869 0.1747123 0.9751558 0.8854299 0.4635587 0.03357607 0.4420956 -0.2552433 0.8598852 0.448456 -0.257339 0.855958 0.8658288 -0.499473 0.02945196 -0.4984474 -0.8662185 0.03486943 -0.2407541 0.01718235 0.9704341 -0.4297414 0.2341486 0.8720647 -1.2391e-5 -1.526e-4 1 -0.8656733 0.4997421 0.02946007 -0.8691312 0.4933476 0.03491872 0.488869 0.8716485 0.03515797 0.4889411 0.8716127 0.0350427 0.8887757 0.4573273 0.03049182 0.8652252 -0.500519 0.02943098 0.8691117 -0.4933575 0.03526002 0.4629818 0.1303257 0.8767344 1.83091e-6 8.38335e-6 1 0.8827831 0.4684056 0.03592038 0.8854117 0.4635927 0.03358876 0.3784575 -0.2121778 0.900972 0.4430589 -0.2664954 0.8559668 0.8656914 -0.4997103 0.02946424 -0.1207163 -0.1717776 0.9777117 -0.218105 -0.3738127 0.9014955 -0.4889434 -0.8716214 0.03479391 -0.4658424 -0.227521 0.855117 -0.4630638 0.1828883 0.8672507 -0.8691048 0.4933697 0.03526198 -0.03775101 0.9986576 0.03546696 -0.05674952 0.9980039 0.02771019 0.4753234 0.1795064 0.8613044 0.4569151 -0.225192 0.8605331 0.7475284 -0.4605613 0.4786278 -3.83827e-5 -1.99861e-4 1 -0.02168208 -0.04313552 0.998834 0.8691352 -0.4933736 0.03444802 0.08359104 -0.995853 0.03591072 0.1035044 -0.9941734 0.03010219 -0.4231588 -0.6826683 0.5957354 -0.836867 -0.4015744 -0.3720102 -0.8854326 -0.4635533 0.03357779 -0.397871 0.1400596 0.9066874 -0.08882462 0.9954211 0.03531444 0.4917498 0.870036 0.03492295 0.4999334 0.8658199 0.02055412 0.4569082 -0.2251874 0.860538 0.7475159 -0.4605545 0.4786539 -0.0216785 -0.04312878 0.9988343 0.0836215 -0.9958527 0.03584498 0.1035069 -0.9941726 0.03011894 -0.4889618 -0.8716125 0.0347566 -0.883415 -0.4672524 0.03540319 -0.08881562 0.9954218 0.03531777 -0.1037696 0.994147 0.03006458 0.1021606 0.2114896 0.9720265 0.3799332 0.651426 0.6567305 0.4999402 0.8658165 0.02053892 0.6429485 0.3219396 0.6949619 0.02157425 0.03508853 0.9991514 -4.70464e-5 -2.75779e-4 1 -3.83767e-5 -1.99875e-4 1 0.9004762 0.4331007 0.03957957 0.8658924 -0.4993619 0.02946239 0.8691341 -0.4933756 0.03444689 0.08361864 -0.9958524 0.03586143 0.1036873 -0.994154 0.0301156 -0.4231626 -0.6826742 0.595726 -0.4887296 -0.8717256 0.03518706 -0.8691218 0.493339 0.03526926 0.3799405 0.6514403 0.6567121 0.4917472 0.8700374 0.03492319 0.4999395 0.8658168 0.0205394 0.4753294 0.1795127 0.8612998 0.7475085 -0.4605428 0.4786767 0.02157491 0.03508961 0.9991513 -0.02167987 -0.04313141 0.9988341 0.8658975 -0.4993526 0.02947056 0.1034677 -0.9941768 0.03011691 -0.4231568 -0.682661 0.5957452 -0.4889559 -0.871616 0.0347566 -0.8368775 -0.401579 -0.3719817 -0.8854163 -0.463584 0.03358513 -0.3978772 0.1400578 0.906685 -0.8652158 0.5005352 0.02943152 -0.8691181 0.4933456 0.03527235 -0.08882135 0.9954214 0.03531503 -0.1037668 0.9941471 0.03006762 0.1021553 0.21148 0.9720292 0.3799405 0.65144 0.6567125 0.4917479 0.8700369 0.03492718 0.4999393 0.865817 0.02053701 0.4753366 0.1795178 0.8612946 -4.70569e-5 -2.75791e-4 1 -3.83828e-5 -1.99872e-4 1 0.8658882 -0.4993689 0.02946686 0.5128216 -0.8561752 0.06307393 0.08361184 -0.9958514 0.03590303 0.1035035 -0.9941737 0.03009456 -0.4887261 -0.8717297 0.03512912 -0.4889414 -0.8716244 0.03474903 -0.8834165 -0.4672513 0.03537887 -0.8853964 -0.4636214 0.03359168 -0.3978823 0.1400609 0.9066823 -0.8691158 0.4933498 0.03526765 -0.08883625 0.9954214 0.03527921 -0.1036288 0.9941611 0.0300824 0.1021666 0.211505 0.9720225 0.6429654 0.3219347 0.6949486 0.4753927 0.1795284 0.8612615 0.4569635 -0.2252132 0.8605018 0.02157419 0.03508824 0.9991514 -4.70568e-5 -2.75825e-4 1 -3.84022e-5 -1.99882e-4 1 0.9069349 0.419893 0.03404331 0.5128132 -0.8561799 0.06307804 0.08360934 -0.9958519 0.03589856 0.1035 -0.9941741 0.03009784 -0.4231507 -0.6826496 0.5957626 -0.4889389 -0.8716256 0.03475075 -0.8834165 -0.467249 0.0354073 -0.8652106 0.5005443 0.02942979 -0.1037613 0.9941479 0.03006231 0.1021774 0.2115263 0.9720166 0.4917534 0.8700341 0.0349183 0.4999322 0.8658207 0.02055144 0.4585886 -0.2260118 0.8594273 0.7476034 -0.4601929 0.478865 -3.84023e-5 -1.99858e-4 1 -0.021685 -0.04314154 0.9988336 0.8991277 0.4371736 0.02118521 0.8853958 0.46358 0.03417396 0.8659121 -0.4993282 0.02945494 0.8691377 -0.49337 0.03443741 0.5128006 -0.856186 0.06309723 -0.836848 -0.401571 -0.372057 -0.8854315 -0.4635557 0.03357839 -0.3978737 0.1400621 0.9066859 -0.8652089 0.5005465 0.02944004 -0.103927 0.9941304 0.03006738 0.1021869 0.2115488 0.9720108 0.4917549 0.8700281 0.0350455 0.4630107 0.1303398 0.876717 0.02273124 0.03721499 0.9990487 5.81071e-5 2.65355e-4 1 0.4997422 0.865468 0.03497153 0.4995613 0.8655608 0.03525757 0.8857046 0.4630322 0.03359586 0.443066 -0.2665026 0.8559609 0.8656895 -0.4997138 0.02946192 0.8691286 -0.4933521 0.03492099 0.08979254 -0.995335 0.03529208 -0.2180929 -0.373791 0.9015075 -0.8853905 -0.4636318 0.03360563 0.6422129 0.3233235 0.6949996 0.2294445 -0.005524694 0.9733061 0.9027834 0.4287916 0.03346675 0.1378533 -0.1764742 0.9746043 -8.6693e-5 -2.62983e-4 1 -0.003871023 -0.0145142 0.9998872 0.8656455 -0.4994127 0.03528201 0.8654425 -0.4997854 0.03498739 0.08831971 -0.9954477 0.03582787 0.103551 -0.9941683 0.03011 -0.4887275 -0.8717283 0.0351504 -0.4889437 -0.8716223 0.0347687 -0.8367896 -0.4012354 -0.3725498 -0.8834118 -0.4672576 0.03541392 -0.8854324 -0.4635531 0.033589 -0.3960881 0.1402607 0.9074367 -0.8699175 0.4923099 0.02957653 -0.089468 0.9953629 0.0353294 -0.1212933 0.9922963 0.02521842 0.1045153 0.2163395 0.970708 0.379445 0.65185 0.656592 0.1957328 0.5927643 0.7812294 0.4734904 -0.2733828 0.8372985 0.2107325 -0.2469257 0.9458433 0.4485549 -0.2958068 0.8433841 0.4600985 -0.2804871 0.8423992 0.4057425 -0.2809523 0.869735 0.4040675 -0.305257 0.8622921 0.5404712 -0.319905 0.7781721 0.5009887 -0.2893709 0.8156438 0.4194794 -0.3267093 0.8469346 0.4997938 -0.2890506 0.8164899 0.498443 -0.2878372 0.8177434 0.4348313 -0.2595626 0.8622929 0.3823592 -0.2089777 0.9000722 0.4972817 -0.2870853 0.8187142 0.56544 -0.2445258 0.7877086 0.5794243 -0.2771518 0.7664558 0.4967036 -0.286773 0.8191746 0.4999234 -0.3086881 0.8091899 0.4656165 -0.2952432 0.8342858 0.5237011 -0.2593799 0.8114551 0.4553247 -0.2785795 0.8456198 0.3320487 -0.09164303 0.9387999 0.4788389 -0.1769199 0.8598911 0.5652419 -0.3311077 0.7555589 0.472938 -0.326758 0.8182657 -0.7656817 0.2517303 -0.591915 -0.02029508 0.01713258 0.9996473 -0.7026789 0.3992863 0.5889082 -0.6297181 0.5609742 0.5373668 -0.5257524 0.5136367 0.6780573 -0.02222913 0.4886004 0.8722245 0.1125549 0.5724486 0.8121787 -0.08888858 0.9948425 0.04885959 -0.4539428 0.646759 0.6128938 0.3306665 0.622626 0.7092226 0.2165555 0.693383 0.6872583 0.06925863 -0.6913071 0.7192342 0.07899081 -0.7060115 0.7037814 -0.6742037 -0.3647531 0.6421874 -0.6246858 -0.3586507 0.6936406 -0.5580458 0.4039133 0.7248716 0.001211583 0.001598536 -0.999998 -0.002210915 0.001601278 -0.9999964 0.4781099 -0.3384532 0.8104693 0.3166716 -0.3265777 0.8905426 0.2125074 -0.2617282 0.9414559 0.2769539 -0.417961 0.8652198 -0.1655057 -0.33612 0.9271631 -0.3067129 -0.156661 0.9388209 0.05070406 0.3756384 0.9253783 0.1581801 0.3152966 0.9357175 0.5835005 -0.01861935 0.8118994 0.4046102 -0.1755867 0.8974743 0.5788313 -0.01644468 0.8152816 0.322255 0.2785702 0.9047378 -0.1244415 0.4254031 0.8964076 -0.3639174 0.37308 0.8534492 -0.6976988 0.1754544 0.6945734 -0.425023 0.02621704 0.9048029 -0.3338084 -0.1792588 0.9254395 -0.5520017 -0.4579819 0.6968119 -0.2804328 -0.4888007 0.826094 0.2940385 -0.6946538 0.6565041 0.471202 -0.8659656 0.1675483 0.2136391 -0.9755311 -0.05193871 -0.09300684 -0.9920775 0.0844506 -0.9286961 -0.3608289 0.08559262 -0.9084563 0.4179799 -3.08584e-5 -0.7781149 -0.6261393 -0.04986804 -0.9516616 -0.3027271 -0.05192905 -0.9955912 0.06492388 -0.06769949 -0.9698049 0.24388 0.001050353 -0.992564 0.1217238 -4.50734e-5 -0.9923914 -0.122879 0.007763922 -0.902009 -0.4305298 -0.03200334 -0.4804138 -0.8350037 0.2682748 -0.4632126 -0.8841276 0.06125873 -0.1168067 -0.9857276 0.1212327 0.05611401 -0.9975689 -0.0413236 0.2565528 -0.9665234 -0.003647565 0.4064611 -0.9136648 0.00245285 0.5523622 -0.8335883 0.005178034 0.5996448 -0.8002663 1.76673e-4 0.6960802 -0.7178559 -0.01246249 0.8161467 -0.5778449 0 -0.8805813 -0.4728782 0.03102958 -0.8326578 0.5537878 9.10352e-5 -0.9083763 0.4181538 0 0.8161906 -0.5777829 1.32384e-5 0.9028953 -0.4298608 7.90337e-5 0.9181977 -0.3929831 0.04977452 9.71352e-4 -9.48919e-4 0.9999991 4.81184e-4 -0.00137037 0.9999989 0.002612113 0.009430348 0.9999521 0.003987967 0.007197737 0.9999662 0.003488421 0.00684762 0.9999705 1.14769e-4 -3.82238e-5 1 -5.80146e-5 3.31793e-5 1 -5.05035e-5 4.45533e-5 1 -1.07819e-4 4.46815e-4 0.9999999 1.00135e-5 5.77227e-5 1 2.41618e-5 6.10075e-5 1 2.79554e-4 3.09305e-4 1 2.65319e-4 7.25954e-5 1 4.67798e-5 4.30026e-5 1 -1.19122e-4 3.00197e-4 1 3.40663e-4 3.46859e-4 0.9999999 6.89577e-4 -1.1636e-5 0.9999998 2.50243e-4 2.75896e-4 1 2.05213e-4 -1.21277e-4 1 0.07385265 0.09981179 -0.9922618 0.8940792 -0.4479089 -4.35895e-4 0.898005 -0.4399836 -0.001236557 0.8994365 -0.4370511 -5.32051e-4 0.8922446 -0.4515447 -0.002654314 0.8858165 -0.4640021 0.00560379 0.8703921 -0.4923203 0.006206154 0.8916369 -0.4526965 -0.007049977 0.8834178 -0.4685283 -0.007370412 0.8748902 -0.4842619 -0.00759685 0.8660689 -0.4998681 -0.007520973 0.8476265 -0.5305539 -0.006471872 0.8380489 -0.5455693 -0.005308687 0.8967934 -0.4424489 7.93525e-4 0.9027628 -0.4299493 -0.01277238 0.9027627 -0.4299492 -0.01278197 -0.8295655 0.5584064 -0.001873314 -0.8265494 0.5628643 3.39212e-4 -0.8236191 0.5669907 -0.01316374 -0.8235919 0.5670232 -0.01345902 -0.8127793 0.5825597 -0.00376451 -0.8349722 0.5502921 -4.43271e-4 -0.8371787 0.5469231 -0.0026775 -0.8568377 0.5155302 -0.007592082 -0.8832944 0.4687744 -0.006449937 -0.8993768 0.4371614 -0.003394126 -0.899666 0.4365789 1.57869e-4 -0.8532447 0.5214747 0.00613594 -0.8696494 0.4936335 0.00599116 -0.8851382 0.4653059 0.004575073 -0.8925256 0.4509869 0.002994 0.7749741 -0.3133165 -0.5488607 -0.6531185 0.6681853 0.3563211 -0.4715504 0.8544655 0.2180115 -0.4747176 0.8510011 0.2245894 0.413132 -0.2187384 -0.884011 0.4779593 -0.2636079 -0.8378936 0.4633386 -0.2484652 -0.8506366 0.4860834 -0.2502035 -0.8373298 0.4504948 -0.2473407 -0.8578327 0.4398189 -0.2417881 -0.8649265 0.4397152 -0.2438938 -0.8643879 0.4289463 -0.2416377 -0.8704117 0.4448171 -0.2615181 -0.8565898 0.4297092 -0.2317487 -0.8727213 0.424073 -0.2604832 -0.8673585 0.4524549 -0.2714504 -0.8494701 0.1214012 -0.06509745 -0.9904667 0.422836 -0.2655565 -0.8664235 0.3945062 -0.259459 -0.8815022 0.4255811 -0.2687251 -0.8640993 0.1096892 -0.06552118 -0.9918041 0.4259955 -0.2533738 -0.8685215 0.3807149 -0.2503491 -0.8901582 0.4163644 -0.2859339 -0.8630659 -0.8824652 -0.4572186 0.1104821 -0.3952282 -0.9184852 0.01340657 -0.8567048 0.5145593 0.03585672 0.2345566 0.9705943 0.05412966 0.655323 0.7490676 0.09720873 -0.8618792 0.5059012 0.03504902 -0.8619794 0.5057424 0.03487527 -0.9829654 -0.1789267 0.04200446 -0.8765525 -0.4738658 0.08430278 -0.8668892 0.4972406 0.03542745 -0.8665612 0.4978869 0.03435546 -0.2934725 0.9524228 0.08224838 -0.8721224 0.4878783 0.03711324 -0.8712768 0.4895154 0.03537487 -0.8756713 0.4816267 0.03514903 0.05343759 0.9936743 0.09877109 -0.1645087 0.9839346 0.0693528 -0.8171202 -0.5735771 0.05765426 -0.5913528 -0.8012003 0.09154099 -0.884651 0.4648565 0.03607356 -0.8844115 0.4653585 0.03546589 0.02756524 0.9948984 0.09704321 0.004848837 -8.29844e-4 -0.9999879 0.004083752 -0.002142846 -0.9999895 -5.81025e-7 0 -1 -1.80588e-7 0 -1 -3.80156e-5 1.78484e-5 -1 1.51261e-6 -4.31323e-7 -1 7.99148e-6 -6.03018e-6 -1 0.001149833 -6.89664e-4 -0.9999991 -6.77119e-4 3.9521e-4 -0.9999998 -7.18614e-4 4.46383e-4 -0.9999997 -2.49632e-4 2.57111e-4 -1 0.01088958 -0.02862769 -0.9995308 0.002409636 -0.001289904 -0.9999964 -1.1504e-5 5.47661e-4 -1 0.07400518 -0.05883443 -0.9955208 -0.002095282 0.001124382 -0.9999972 0.08721399 -0.05893802 -0.9944446 4.97835e-5 -6.46164e-4 -0.9999999 0.007815062 -0.004511952 -0.9999594 0.007817149 -0.004513204 -0.9999593 -0.001151025 2.78789e-4 -0.9999994 0.05870121 -0.03066796 -0.9978044 0.06222748 -0.03992623 -0.9972631 0.007816791 -0.004513025 -0.9999594 0.007761955 -0.004475533 -0.9999599 0.06474369 -0.02383983 -0.9976171 7.57453e-7 0 -1 0.007816493 -0.004512965 -0.9999594 0.007815897 -0.00451219 -0.9999593 0.007804811 -0.004503607 -0.9999595 0.04560029 -0.01392734 -0.9988628 0.002429306 3.44222e-5 -0.9999971 -0.005442142 0.003379881 -0.9999796 0.007811009 -0.004508972 -0.9999594 -5.29327e-4 -2.45863e-4 -0.9999998 0.9967574 0.07124125 0.03741073 0.8858481 0.4545382 0.09310364 0.8641719 -0.5019474 0.03544074 0.8692142 -0.4931694 0.03536516 0.961027 0.2734739 0.0404883 0.8802095 0.4693329 0.07041412 0.8736871 -0.485205 0.03531545 0.8734395 -0.4856828 0.03486752 0.2642067 -0.9557302 0.1295177 -0.7376589 -0.6748465 -0.02101397 0.8779737 -0.4773837 0.0355972 0.8744494 0.4781324 0.08202302 0.6546148 0.7555458 0.02510267 0.8824666 -0.4690534 0.03524023 0.8823834 -0.4692359 0.03488963 -0.9448215 0.2805653 -0.1691015 0.8056665 0.5869252 0.08012729 0.7472037 0.6615179 0.06388241 0.8907696 -0.4530901 0.03519731 0.2220412 -0.9731433 0.0607438 -0.8818602 0.457813 -0.1128269 -0.8775925 -0.3344643 -0.3434607 -0.4526055 -0.4342875 -0.7788087 -0.7245259 -0.1127026 -0.6799708 -0.8328772 0.117513 -0.5408385 -0.8502221 0.2180066 -0.4791613 -0.8527972 0.4731346 -0.2210901 -0.8396086 0.5085486 -0.1908819 -0.7716772 0.6353646 -0.02874386 -0.7735185 0.633325 -0.02384656 0.8413605 -0.529242 -0.1096152 0.6139142 -0.6273047 -0.4791641 0.1742885 -0.6873555 -0.7051 -0.4777675 -0.7999033 -0.3631706 -0.3213944 -0.5566709 -0.7660439 -0.321393 -0.5566689 -0.766046 0.0575478 -0.5586708 -0.8273907 0.7447213 -0.6593413 -0.1032441 -0.3207767 -0.5574585 -0.76573 -0.3213999 -0.5566757 -0.7660381 0.9654427 0.2605169 -0.007180631 0.9905636 -0.1370534 4.9807e-4 0.9659159 -0.2588256 -0.004002213 -3.29475e-7 0 -1 -1.86517e-6 0 -1 0 0 -1 -0.001420557 0.001781225 -0.9999974 -0.3223747 -0.5565076 -0.7657505 -0.8660242 0.5000022 3.55086e-4 -0.8660258 0.4999993 -1.00412e-4 -0.6123709 0.35355 0.7071098 -0.6123676 0.3535499 0.7071128 -0.6123797 0.3535604 0.7070971 -0.6123676 0.3535488 0.7071133 -0.6124029 0.3535789 0.7070676 -0.6123727 0.3535533 0.7071067 -0.6123405 0.3535373 0.7071425 0.6127444 -0.3538823 -0.7066199 0.6123751 -0.3535416 -0.7071104 -0.6123712 0.3535521 0.7071086 -0.6123536 0.3535437 0.7071279 -0.6123668 0.3535503 0.7071132 -0.6123561 0.3535473 0.707124 -0.61236 0.3535441 0.7071222 -0.6123609 0.3535544 0.7071164 -0.6123699 0.3535506 0.7071104 -0.6123735 0.3535513 0.707107 -0.6123709 0.3535525 0.7071087 0.5085353 0.8591309 0.05732291 0.02200537 0.009078919 0.9997166 -2.83827e-5 1.17312e-4 1 -0.002609789 0.008401334 0.9999613 -0.001152098 -0.001554787 0.9999982 1.62706e-4 5.25131e-5 1 -2.66526e-4 -5.99932e-5 1 1.44212e-4 3.26887e-5 1 -2.75458e-5 8.95259e-5 1 0.006695687 0.01585906 0.9998519 -0.8490592 0.4851037 0.2092197 -0.06416428 -0.9817369 -0.1790966 -0.04456162 -0.8566816 -0.5139173 0.0974766 -0.5171235 -0.8503421 0.4381135 -0.3126734 -0.8427881 -0.04176688 -0.1412505 -0.9890924 -0.5216517 -0.8286429 -0.203053 -0.031874 0.7014117 -0.7120434 -0.6320964 -0.6525498 -0.4178913 -0.5930194 -0.802568 0.06490588 -0.2284623 -0.6710841 0.7053021 -0.8206875 -0.5710539 0.0192281 -0.07848834 0.4001901 -0.9130649 -0.4003031 -0.2125895 -0.8913828 -0.6502473 0.3255867 0.6864194 -0.8767137 -0.3101584 0.3676615 0.9091868 0.3643649 -0.2015384 -0.7385572 -0.6501697 -0.1783611 0.6329576 -0.3911014 0.668135 0.4924373 -0.8506838 0.1839634 0.4432687 -0.777309 0.4464342 -0.2620159 0.919712 -0.2923657 -0.05807673 0.778119 -0.6254264 0.3009576 0.2552184 0.9188515 -0.1027401 -0.9605972 -0.2582587 -0.06759625 -0.996897 -0.04033988 -0.05849176 -0.995665 0.07231783 0.4340844 -0.9008615 0.004425048 0.3125112 -0.9499106 0.002613008 0.2104015 -0.977614 0.001512467 0.1329386 -0.9911242 -5.5739e-4 0.03016465 -0.9994886 0.0106216 -0.1807231 -0.9831836 -0.02625149 -0.2927901 -0.9561685 0.003965854 -0.1836638 -0.9829493 0.008841454 -0.2672727 -0.9635775 -0.00915867 0.371109 -0.9285793 -0.004325807 -0.5408001 -0.8411458 0.00300306 -0.5885925 -0.8082473 0.01718354 -0.9342964 -0.3564897 0.002327442 -0.9764404 -0.2157518 0.003920674 -0.9971303 -0.07562261 0.003540933 -0.9991073 0.04214233 0.002980113 -0.9251127 -0.3786771 0.02775311 -0.9586378 -0.284614 -0.00290507 -0.900346 -0.4343157 -0.02733212 -0.825001 -0.5648217 0.01870632 -0.7266823 -0.6868916 0.01062673 -0.6861896 -0.7274199 0.002076566 -0.6516277 -0.75852 -0.005377411 -0.8278847 -0.5558423 -0.07514238 0.1524192 -0.9883144 -0.001746177 0.08132797 -0.9966371 -0.01001751 -0.7685883 -0.3659545 -0.5247375 -0.4457185 -0.7955578 -0.4103936 -0.9318991 0.3396582 -0.1272653 -0.5849772 -0.3471072 -0.73302 -0.5569799 -0.2039982 -0.8050828 -0.1470956 -0.05547571 -0.9875654 0.09895104 0.2451606 -0.9644195 -3.1545e-4 2.0777e-4 1 3.67386e-5 6.30246e-5 1 -0.05023217 0.323116 0.9450253 0.08576232 -0.1509335 0.9848167 0 0 1 2.34156e-7 0 1 0 0 1 0.2032129 0.0806961 0.9758037 -2.5532e-7 0 1 0 0 1 3.01955e-7 0 1 -2.04254e-7 0 1 0 0 1 3.82501e-7 0 1 -4.10752e-6 3.45256e-6 1 -3.33232e-7 0 1 0.6706862 -0.2600703 0.6946535 -0.5604561 0.4507027 0.6948065 0.631533 0.3537471 0.6899486 0.6167538 -0.381214 0.6886877 0.4190757 0.4937907 0.761936 0.6797767 0.3510749 0.6439333 0.5005704 0.3288838 0.8007901 0.353554 0.6123737 0.7071055 -0.4608822 0.5614012 0.6873255 -0.4999348 -0.8660631 -1.026e-4 0.9865837 0.1609777 -0.02718245 0.9872967 0.1565793 -0.02698725 0.9786247 -0.2029539 -0.03322225 0.6446982 0.7644126 -0.006150305 0.9318026 -0.3613233 -0.03448843 0.9318028 -0.3613227 -0.03448987 0.9294151 -0.3671153 -0.03760612 0.9323126 -0.3606793 -0.02652877 0.3396536 0.9405305 -0.006150484 -0.007588684 0.9998111 -0.01789253 -0.6650794 0.7460329 -0.03323143 0.3366973 0.9415935 -0.00604856 -0.3573201 0.9335911 -0.02702176 0.9720919 -0.2337544 -0.01990753 0.8026685 0.5960934 0.01990717 -0.9287573 -0.3690332 -0.03499412 0.9465424 -0.3219648 0.01990813 -0.5877466 0.808288 0.03499418 -0.9947003 0.08598452 0.05637419 -0.6363779 -0.7704775 0.03724968 -4.91409e-4 1.67794e-4 -1 -6.12176e-4 0.04450631 -0.999009 -0.00681591 -0.02104175 -0.9997554 0.01165688 -0.01091039 -0.9998726 -4.04268e-4 9.71459e-5 -1 -0.00741589 -0.01267296 -0.9998922 0.9716046 -0.2336605 -0.03724908 0.964178 0.2629377 0.03499335 -0.8314783 0.5548473 0.02808183 -0.9965353 -0.07466983 -0.03663527 -0.5632777 -0.8260278 -0.01990669 0.3598183 -0.93281 -0.01990759 0.9220927 -0.3865991 0.0169208 0.4331152 0.8995739 0.05637454 -0.4336084 0.9003564 0.03663444 -0.5474608 -0.8363601 -0.02807992 -4.96683e-4 1.72075e-4 -1 -3.76815e-4 -3.41352e-4 -0.9999999 0.002966046 0.00945276 -0.999951 -2.25765e-6 0 -1 0.632843 -0.7740558 0.01864451 -0.1148831 -0.9931945 -0.01914781 -0.4947395 0.8682427 0.03724855 0.833276 0.5513414 0.04091107 0.9759306 -0.2152557 0.03499293 -0.8481355 -0.5295093 -0.01692026 -0.6278715 0.7781331 -0.01691991 0.450577 0.8922958 0.02808314 0.04039222 -0.08525943 0.9955397 -0.08391737 0.001720666 0.9964713 -0.1231312 0.02715766 0.9920188 0.03682136 -0.0646196 0.9972305 -0.6317074 -0.7730446 0.05786234 -0.9947003 0.08598482 0.05637365 -0.4942947 0.8674646 0.05637544 0.4331161 0.8995735 0.05637466 0.7510673 -0.6578145 -0.0563749 -0.8866669 0.4589594 -0.05637478 0.6964097 0.7167088 -0.03663563 -0.2642931 0.02284657 0.9641718 -0.1398721 0.2454691 0.9592605 0.1149255 0.238699 0.9642692 0.3165962 -0.948309 0.02184063 0.3774664 -0.9260233 0 -0.1604105 -0.9870505 0 -0.2725688 -0.9617443 0.02746367 -0.9872953 0.1546159 0.03663474 0.03449356 0.9992617 0.01692116 0.945226 -0.3215116 0.05637574 -0.5860251 -0.809961 -0.02319318 -0.8866665 0.4589601 -0.0563749 0.9900881 0.1360192 -0.0349943 -0.006577491 -0.003381431 0.9999727 1.99151e-4 7.02342e-4 0.9999998 3.1061e-4 4.14998e-4 1 -0.02011168 -0.007881224 0.9997667 0.02979493 0.05686032 0.9979376 6.80815e-4 3.78861e-4 0.9999997 7.15298e-4 -1.11986e-4 0.9999998 -0.03051441 0.04196429 0.9986531 0.3598209 -0.932809 -0.01990765 -0.2724915 -0.9614605 0.03663682 -0.8960537 0.4425647 0.03499227 -0.4337372 0.9006209 0.02746433 0.4331146 0.8995743 0.05637395 0.9641798 0.2629312 0.03499388 0.9220905 -0.3866044 0.01692062 -0.01570504 0.9992642 -0.03499323 0.7435544 0.6662946 -0.05637699 0.9716058 -0.2336556 -0.03724908 0.03187835 0.02868545 0.9990801 0.009344995 0.007205128 0.9999304 8.63841e-4 3.62257e-4 0.9999997 -0.02479767 0.0514906 0.9983657 0.01524949 0.004158675 0.9998751 -0.4127082 0.6262671 0.6614087 0.2048368 -0.2722545 0.9401699 0.4621617 -0.8867947 -0.001351714 0.0439983 -0.9990308 0.00133711 0.9657915 -0.2584817 -0.02083873 -0.7014819 -0.7124664 -0.01774275 -0.8281117 -0.560563 -4.62282e-4 -0.9848135 -0.1733517 -0.009575843 -0.9985196 0.05417203 0.004904389 -0.9347392 0.3553203 0.003161132 0.8870274 -0.4617151 -0.001349389 -0.6726273 0.7399446 -0.007387816 -0.07248818 0.9973685 -0.001288831 0.5348449 0.8449491 -0.001450419 0.2725406 -0.9619451 -0.01958131 0.7050113 0.7088844 -0.02102667 -0.7029694 0.7111382 -0.01079845 -0.5344903 -0.8451735 0.001348674 -0.9985174 0.05421262 0.004906058 -0.9191868 0.393733 0.008360564 0.7062447 0.7077286 0.01839989 -0.6726452 0.7399283 -0.007387638 0.5348528 0.8449441 -0.001450657 0.999065 -0.04321342 -0.001358628 0.9022856 0.430094 0.02999722 0.9166928 0.3979355 0.03635478 0.978203 -0.201953 0.04831022 -0.9054426 -0.4233611 0.0306434 -0.9215286 -0.3863121 0.03934621 -0.8659127 0.499261 0.03055417 -0.8693631 0.4929456 0.03481942 -0.9243505 -0.3801217 0.03292202 -0.9782936 0.2018815 0.04674875 -0.8656251 0.499777 0.03026777 -0.8693742 0.4929455 0.03454381 0.9270398 0.3736738 0.03106641 0.9932004 -0.10468 0.05094265 0.8656277 -0.4997728 0.03026562 0.909368 0.4145685 0.03439146 0.9132403 0.4057535 0.03682583 0.8656294 -0.4997722 0.03022515 0.8693397 -0.4930095 0.03450155 0.9047948 0.4244472 0.03451216 0.910785 0.4110614 0.03872084 0.9832546 0.1744344 0.05275392 -0.9038751 -0.4261559 0.03743255 -0.9781693 0.2019326 0.04907083 -0.865629 0.4997764 0.03016924 0.0755968 -0.9961401 0.04461228 -0.9067843 -0.4201959 0.0343194 -0.9781512 0.2020148 0.04909628 -0.8656573 0.4997227 0.03024429 -0.9087676 -0.4158267 0.03506606 -0.9781792 0.2019622 0.04875266 -0.8656286 0.4997735 0.03022718 -0.8693369 0.4930143 0.03449976 0.4944089 0.8677443 0.05079209 0.9029029 0.4275701 0.0441609 0.8947095 -0.4451156 0.03697657 0.07075589 -0.9964362 0.04591995 0.01211738 -0.9992611 0.03647786 -0.8715588 -0.4889693 0.03597807 -0.8908467 -0.4519579 0.04611235 -0.8525375 0.5214667 0.03539043 -0.03012281 0.9988774 0.03656035 -0.07159054 0.9962955 0.04764503 -0.8433674 0.5361912 0.03507965 -0.05559039 0.997762 0.03715968 -0.07262575 0.9963751 0.04429912 -0.9778171 0.2020778 0.05512303 -0.8523564 0.5226396 0.01834738 -0.07963186 0.9958232 0.04466718 -0.5112817 -0.8592529 0.01660138 -0.91398 -0.4054785 0.01509457 -0.8852542 -0.4633652 0.04022091 -0.8687493 0.4936692 0.03956687 0.08072137 -0.9963214 0.02877324 0.8502105 -0.5252334 0.03566557 0.8507149 -0.5244666 0.03491377 0.06978726 -0.9964947 0.04613327 -0.9884498 -0.1259975 0.08421242 -0.8803873 -0.4703708 0.06057745 -0.8657323 0.4998316 0.02599847 -0.424528 0.9029454 0.06682527 -0.5541257 0.8287172 0.07856458 0.9031661 0.4256464 0.05582457 0.1181576 -0.9924549 0.03274524 0.9880564 0.1289166 0.08441054 0.8893227 0.4530411 0.06212168 -0.843562 -0.5362902 0.02821528 -0.2534114 -0.3040194 0.9183436 -0.5583019 0.3779271 0.7385595 0.3720542 -0.3399435 0.8637211 -0.610652 -0.6662229 0.4280787 -0.1347557 0.4244349 0.8953748 0.4338777 -0.25145 0.8651723 0.8659207 -0.4992344 0.03076261 0.2335445 0.9034835 0.3594089 -0.7308105 0.3263562 0.5995061 0.1190752 -0.007890641 0.9928539 -0.09614104 -0.5449423 0.8329435 0.6202723 -0.3297226 0.7117199 0.1907941 0.02615541 0.9812816 0.8584043 -0.5117551 0.03533703 0.982867 0.1603047 0.0909664 0.6203849 -0.3499033 0.701919 -0.4175547 -0.1900717 0.8885499 0.8177272 0.1745283 0.548509 0.3529275 -0.2169793 0.910144 -0.7186618 0.3869189 0.5777708 0.4436785 -0.2753902 0.8528246 0.2142919 -0.9761356 0.03518861 -0.3343634 -0.4457892 0.8303452 0.5438198 0.5647777 0.6207143 -0.6492552 0.4057663 0.6432896 0.4604468 -0.2639232 0.8475455 0.6290088 -0.3317159 0.7030736 0.1080003 0.375338 0.9205745 0.1456241 0.2298313 0.962274 0.6161964 -0.3490453 0.7060237 0.5787439 -0.3369727 0.7426338 -0.08412992 -0.3613808 0.9286152 0.1451314 -0.6549239 0.7416276 0.8656274 -0.4997739 0.03025466 0.869355 -0.4929804 0.03452992 0.9782347 -0.2019841 0.04753369 -0.5258166 0.3421402 0.7787535 0.08207833 -0.214751 0.9732139 -0.1993435 -0.805996 0.5573444 0.6560645 -0.3403971 0.6735795 -0.03299051 -0.0663771 0.9972491 -0.07793122 0.9933239 0.08505463 -0.03815889 -0.4691852 0.8822751 -0.6200632 0.3479593 0.7031686 -0.5773756 0.335632 0.7443041 -0.1722994 0.5737701 0.8006878 -0.8105404 -0.2573982 0.5260897 0.3013049 -0.1839838 0.9356096 0.1985819 0.898047 0.3925262 -0.2332835 0.5967761 0.7677482 -0.1496435 0.9882109 0.03234302 -0.1093356 0.992995 0.0447967 0.1649829 0.1379277 0.9766047 -0.4295407 0.2472642 0.8685362 -0.002493739 -0.2268981 0.9739153 -0.4780188 -0.384362 0.7897872 0.8902056 0.4539686 0.03803354 0.8987903 0.4360632 0.04500061 -0.6377819 0.3558131 0.6831043 -0.1637925 0.5927532 0.7885529 0.7036635 0.1634392 -0.6914806 -0.0365495 4.54489e-4 0.9993318 -0.2274761 0.08968734 0.9696448 0.06305193 0.7049684 0.7064305 -0.157927 -0.9181075 0.3635075 -0.4643715 0.2662394 0.844675 0.1360394 0.08973789 0.9866308 -0.6883491 0.4078169 0.5998842 -0.6403287 0.3943312 0.6591526 0.4972773 -0.2949772 0.8159068 0.1555929 0.3518589 0.923031 0.6149518 -0.348267 0.7074916 0.8741133 0.3154813 0.3693205 -0.7167207 0.3683606 0.5921335 0.09995073 -0.9939624 0.04526191 0.4285222 -0.2467865 0.8691749 0.6231209 0.2804242 0.7301251 0.1201016 -0.990921 0.06042611 0.6209137 -0.3500926 0.7013568 0.7187601 -0.1076124 0.6868795 -0.0727846 0.07504844 0.9945201 -0.05448234 0.06610774 0.996324 0.5211957 -0.5689182 0.6361504 0.4271306 -0.2453154 0.8702757 0.308025 0.7316638 0.6081026 0.4845791 0.3567941 0.7986746 0.1934788 0.7844009 0.5893058 -0.6310166 -0.6580373 0.4108588 -0.9036212 -0.4257085 0.04733902 0.4467874 -0.8916232 0.07341092 0.368101 -0.9260453 0.08331692 0.1888467 -0.05439227 0.9804992 0.1012911 -0.994157 0.03731137 -0.6098101 0.3520742 0.7100532 -0.6006588 0.3490216 0.7193004 -0.02373623 -0.6858739 -0.7273333 -0.4379936 0.2444853 0.8650946 -0.9927031 0.1164042 0.03147566 0.02856022 0.08141243 0.9962712 -0.6445454 -0.3105209 0.6986688 0.2827872 -0.1271666 0.9507157 0.5643393 0.7433426 0.3591142 0.8671063 0.4968386 0.03574949 0.8886125 0.4562978 0.04647719 -0.1261497 0.9901588 0.06059676 -0.614759 -0.1422064 0.7757892 -0.5924766 0.3406652 0.7300128 -0.3506275 -0.8687228 0.3498303 -0.01449185 0.02785158 0.999507 0.7380897 -0.4053354 0.5393764 0.6696122 -0.343546 0.6584799 -0.1688157 0.9850943 0.03302341 0.1916107 0.04299145 0.980529 -0.8970947 -0.07110959 0.4360787 -0.3993949 -0.3480647 0.848136 -0.3179497 -0.4405781 0.8395231 0.08178919 -0.03199797 0.9961359 0.2222193 -0.08224099 0.9715221 0.6588802 0.5199036 0.5436701 0.8954348 0.4428499 0.04561299 -0.1000055 0.9932838 0.05819249 0.104658 0.7077031 0.6987153 -0.6381068 0.3372524 0.6921565 -0.8549246 0.4118705 0.3153837 -0.6929976 -0.06383025 0.7181087 -0.5468697 0.2451176 0.8005317 0.5060711 -0.8510093 -0.1402687 -0.188674 0.1397007 0.9720524 0.6988604 -0.3036236 0.6476163 0.2133154 0.9521516 0.2188694 -0.2607296 0.8470181 0.4632285 -0.5512781 0.3154137 0.7724032 -0.5893718 0.584124 -0.5580682 -0.1039976 0.9938481 0.03808599 0.4991225 -0.2881201 0.8172293 0.2051066 0.7784754 0.593218 -0.6368591 0.4835143 0.6005201 -0.5673079 -0.6697031 0.479228 -0.9018139 -0.430112 0.04165732 -0.1094071 -0.9903064 0.08557748 -0.6528683 0.660058 -0.3715997 -0.0816906 -0.02416437 0.9963648 0.09637343 0.5828886 0.8068168 -0.8188451 0.2321544 -0.5249735 -0.8212736 -0.5633094 0.09051221 -0.6105134 -0.1246625 0.7821335 -0.590495 0.2350289 0.7720605 -0.232544 -0.9357963 0.2649689 -0.1204876 0.09480381 0.9881776 -0.3907924 0.2564896 0.8840218 0.6756758 -0.3536759 0.6468196 -0.5790961 0.3345529 0.7434529 -0.108758 0.9934174 0.03596675 -0.1532667 0.987076 0.04680246 0.3941394 0.7173416 0.5745217 0.6189193 0.3562564 0.7000146 0.6115917 -0.346351 0.7113344 0.5946785 -0.3415041 0.7278273 0.041188 -0.7707126 0.6358504 -0.2820096 -0.4989479 0.8194644 -0.3299588 -0.6114626 0.7191945 -0.6273714 -0.3285245 0.7060289 -0.6109783 0.3465993 0.7117406 -0.6020513 0.3440535 0.7205287 0.2210096 0.5323229 -0.8171824 0.005710601 0.01395124 0.9998865 0.6125599 -0.3456749 0.71083 0.5878736 -0.3386801 0.7346431 0.06273257 -0.6919202 0.7192435 -0.3297923 -0.6016048 0.727536 -0.376425 -0.6659463 0.6440651 -0.5891386 -0.3633465 0.7217306 -0.07090741 0.6996464 0.7109621 0.2976366 0.5507696 0.7797855 0.6077464 -0.3450067 0.7152724 -0.3323283 -0.6005116 0.7272853 -0.4025421 -0.6949658 0.595804 -0.5888419 0.3390499 0.7336964 -0.02716219 0.6245965 0.7804752 0.3559461 0.5965739 0.7193067 0.6185879 0.3600239 0.698378 0.6069691 -0.3447243 0.7160682 0.5947927 -0.3412855 0.7278364 -0.6376312 -0.3513068 0.6855728 -0.6272925 -0.3393464 0.7009623 -0.6098611 0.346507 0.7127429 0.3213908 0.5515491 0.7697414 0.3093708 0.5238757 0.7936271 0.6193128 0.3182993 0.7177307 0.7125437 0.4311566 0.553521 0.5944123 -0.3409219 0.7283174 -0.3265558 -0.5903784 0.7381156 -0.3584246 -0.6336513 0.6855785 -0.6742501 -0.3611901 0.6441494 -0.5991504 -0.3510686 0.7195621 -0.6074616 0.3442445 0.7158815 -0.04705572 0.6470808 0.7609679 -0.07566827 0.6978503 0.7122355 0.6419168 0.2964298 0.7071579 0.654331 0.3109787 0.6893064 0.5924206 -0.3406084 0.7300848 -0.6676828 -0.349473 0.6573191 -0.6212271 -0.347113 0.7025593 -0.6069741 0.3447152 0.7160683 -0.5947925 0.3412796 0.7278394 -0.04707348 0.647114 0.7609387 0.6042323 0.2789362 0.7463899 0.6071734 -0.3445222 0.7159923 0.5990005 -0.3422277 0.7239328 0.0749613 -0.6980637 0.7121011 -0.2907584 -0.4791529 0.8281739 -0.6676798 -0.3494684 0.6573246 -0.6212354 -0.3471198 0.7025485 -0.6069672 0.3447205 0.7160717 -0.5947742 0.3412777 0.7278552 -0.05275076 0.6906298 0.721282 -0.06022435 0.7037033 0.707937 0.3143144 0.5227994 0.7923935 0.6419082 0.2964333 0.7071642 0.609781 -0.3455215 0.7132896 0.5924208 -0.3405507 0.7301115 0.06348335 -0.8142884 0.5769787 -0.3046544 -0.5015292 0.8097248 -0.6212173 -0.3471117 0.7025686 -0.6069729 0.3447279 0.7160633 -0.5948003 0.3412906 0.7278279 -0.04777342 0.6484058 0.7597946 -0.07566553 0.6978408 0.7122451 0.3735263 0.656424 0.6554279 0.6386066 0.2925868 0.7117406 0.5924717 -0.340373 0.7301531 0.07661062 -0.6974611 0.7125159 -0.3219087 -0.5905392 0.7400258 -0.6272698 -0.3393388 0.7009863 -0.6094622 0.3458608 0.7133976 -0.005392611 0.6838204 0.7296305 0.6411394 0.2960675 0.7080144 0.6375394 0.2918977 0.7129791 0.5929685 -0.3405135 0.7296842 -0.3294859 -0.6012993 0.7279273 -0.6180769 -0.3566567 0.7005548 -0.5950019 0.3413947 0.7276142 0.4370701 0.7346169 0.5189488 0.6097827 -0.3458285 0.7131393 0.03341591 -0.7509304 0.6595354 0.004491806 -0.6824759 0.7308943 -0.2593727 -0.4489208 0.8551 -0.7326467 -0.3826458 0.5628598 -0.5883738 -0.3618409 0.7231097 -0.6073677 0.3443267 0.7159215 -0.5888763 0.3390685 0.7336602 -0.02712714 0.6245343 0.7805263 0.382248 0.6184274 0.6866105 0.6094456 0.4002751 0.6843654 0.5947983 -0.3412793 0.7278348 0.0723893 -0.6910066 0.7192147 -0.6273255 -0.3393737 0.7009195 -0.6081315 0.3455343 0.7146903 -0.6002269 0.3432806 0.7224169 -0.007783949 0.68624 0.7273336 0.8646354 -0.4975087 0.06993484 0.899344 0.4349817 0.04439932 -0.8708428 -0.4882416 0.05703622 -0.9861408 -0.1391679 0.09032511 -0.8810437 -0.4693225 0.05914759 0.2472511 0.9680023 0.04288017 -0.8564317 -0.5043641 0.1101891 0.9941471 0.08489513 0.06681716 0.974148 0.2194193 0.05376863 -0.1902161 0.9775125 0.09103327 -0.9932912 -0.1034966 0.05158597 0.9828029 0.1605674 0.09119546 0.8673294 0.4945378 0.05632358 -0.8598721 0.5079475 0.05108225 -0.9845991 -0.1494269 0.09075367 -0.8708904 -0.4881576 0.0570271 -0.8651236 0.4994779 0.04564094 0.05235576 -0.9975419 0.0465756 0.8534701 -0.5191815 0.04516106 -0.8651261 0.4994733 0.04564297 -0.8651301 0.4994659 0.04564678 -0.5675132 -0.8224611 0.03855699 0.2529001 -0.9587939 0.1294441 0.8488046 -0.5267598 0.04533147 0.9856629 0.1424289 0.09045737 0.8651334 -0.4994596 0.04565501 0.8651244 -0.4994764 0.04564261 0.8651303 -0.4994651 0.04565352 -0.1001176 0.9935353 0.05351769 0.9099969 0.4130975 0.03544431 0.9154404 0.4005391 0.03921121 0.8654991 -0.4996924 0.03491395 0.8716697 -0.4880362 0.04486328 0.8650252 -0.4996498 0.04562395 0.8651263 -0.4994595 0.0457921 0.06544655 -0.9964811 0.05236619 0.001061022 -0.9990868 0.04271346 0.4555687 0.8760458 -0.1581169 -0.3083252 0.9461691 -0.09848642 -0.8318794 0.5525808 -0.05129551 -0.9945149 0.09290522 -0.04804968 -0.836723 -0.5419243 -0.078821 0.1748728 -0.9816975 -0.07542872 0.743774 -0.6634359 -0.08156597 0.764968 -0.6419036 -0.05276119 0.773386 0.6146449 0.1551958 -0.6742702 -0.2646768 0.6894243 -0.3235479 -0.2444739 0.914084 -0.8315891 -0.04278904 0.5537409 -0.2599556 0.3360438 0.9052612 0.1639485 0.190746 0.9678517 0.00767219 0.1744737 0.984632 0.2897716 0.343604 0.893291 0.4684904 -0.264792 0.8428536 0.2640406 -0.6440005 0.7180153 -0.7984304 -0.3920108 0.4569862 -0.4330288 -0.136533 0.8909797 -0.4272194 -0.04474037 0.9030404 -0.8474592 0.228335 0.4792453 -0.4989529 0.314924 0.807384 -0.4101072 0.3954084 0.8218663 -0.2794371 0.4087353 0.8688212 0.3890156 0.5392439 0.7469156 0.390947 0.5410958 0.7445642 0.5418264 -0.04059875 0.8395093 0.5649114 -0.3765753 0.7342113 0.01217442 -0.2373185 0.9713556 -3.24328e-7 0 -1 5.02287e-7 1.22767e-7 -1 7.0633e-7 -1.79764e-6 -1 0 -1.87823e-6 -1 -8.84505e-6 5.48904e-6 -1 8.58499e-7 0 -1 5.12771e-6 -6.67682e-6 -1 -3.58784e-6 -1.35866e-6 -1 -0.2637728 0.2283374 0.9371692 0.4945748 -0.1849057 0.8492382 -0.818041 -0.5735095 0.04354268 -0.9238193 0.3826252 0.01249492 -0.9300967 0.3656067 0.03538411 -0.02628737 0.004938244 0.9996423 0.2336376 -0.2069359 0.950048 -0.5288661 0.1925385 0.8265771 0.03275018 0.9980916 0.05235219 0.8198392 0.5704733 0.04923564 -0.0187813 0.0119962 0.9997518 -0.004978835 0.0129503 -0.9999037 -0.9242123 -0.3802896 0.03480756 0.2273764 -0.9731535 0.03567177 0.4505939 -0.185357 -0.8732743 0.468344 -0.1332868 -0.8734349 0.4855248 -0.1356952 -0.8636276 0.4718834 -0.1968949 -0.8593943 0.4906551 -0.1926041 -0.8498007 0.478789 -0.18607 -0.8579855 0.4541389 -0.1803224 -0.8724917 0.4578894 -0.182651 -0.8700436 0.4659671 -0.1742745 -0.8674694 0.4682192 -0.17795 -0.8655083 0.4743092 -0.1681715 -0.8641465 0.4927301 -0.1620903 -0.8549525 0.49393 -0.1573576 -0.8551444 0.4756531 -0.1540117 -0.8660454 0.4742924 -0.1641521 -0.8649283 0.4910457 -0.1523869 -0.8577018 0.5515967 -0.1829615 -0.8137974 0.4693645 -0.1584586 -0.8686702 0.4725407 -0.1763346 -0.863488 0.4759022 -0.1757071 -0.8617681 0.4701965 -0.1967548 -0.8603504 -0.06438553 -0.2219704 -0.9729254 3.97598e-4 3.62826e-5 -1 -6.00338e-4 8.79625e-5 -0.9999999 -2.07122e-7 0 -1 -0.001683533 0.001091778 -0.999998 0.03009724 -0.01499122 -0.9994346 -0.02165222 0.07320547 0.9970819 1.20229e-7 0 -1 1.2119e-6 0 -1 -0.001271247 4.16896e-4 -0.9999991 -1.16197e-6 0 -1 1.20244e-7 0 -1 0.05938285 -0.01260459 -0.9981558 0.06650447 -0.02074098 -0.9975706 0.1029323 -0.03963279 -0.9938985 0 0 -1 1.45259e-7 0 -1 0 0 -1 -0.002517998 8.2578e-4 -0.9999966 3.81763e-4 -7.08789e-4 -0.9999997 -0.001367986 5.48238e-4 -0.999999 0.03673112 -0.02407425 -0.9990352 4.14275e-7 0 -1 -7.57054e-4 2.79178e-4 -0.9999997 9.97522e-5 -2.14577e-4 -1 0.00253731 -0.001016855 -0.9999964 0.01581209 -0.01880562 -0.9996981 0.1026616 -0.04648637 -0.9936295 3.00527e-7 0 -1 7.47558e-6 -1.89999e-6 -1 3.64663e-7 0 -1 -0.9396929 0.3420196 9.54524e-5 -0.9396927 0.3420202 0 -0.2071974 -0.5219438 -0.8274321 -0.2192656 -0.606418 -0.7643166 -0.2265091 -0.598493 -0.7684398 -0.7957596 0.2769624 0.538571 -0.7174323 -0.4764166 0.5082501 -0.4903684 -0.3833953 0.7826538 0.1795564 0.5158485 0.8376515 0.3560481 0.7639773 0.5381157 0.9092289 -0.3982031 0.1213961 9.67896e-4 -2.69955e-4 0.9999995 0.1871592 0.5102572 0.83941 0.8037694 0.5774263 0.1432957 0.1751357 -0.1159048 0.9776981 0.4237226 -0.1521876 0.8929156 -0.8037852 -0.5773684 0.1434409 0.2115978 -0.97605 0.05052661 0.2667677 -0.9632108 0.03255975 -0.3436118 -0.9389547 0.01717329 -0.814699 -0.5793368 0.02518916 -0.7913668 -0.6100212 0.04015851 -0.9365391 0.3493105 0.02961379 6.35448e-6 4.9349e-6 1 0.1921433 -0.6523708 0.7331394 0.2830805 0.858334 0.4279348 0.2618342 0.620297 0.7393745 0.9394995 -0.342054 0.01843297 0.2560524 -0.9662421 0.02851825 0.2717506 -0.9623643 0.002558946 -2.3939e-5 2.31913e-4 1 0.8373608 -0.3231114 0.4409375 0.665945 -0.2339999 0.7083512 -0.7637106 0.3351626 0.5517358 0.7354134 0.5467135 0.4003394 0.8204821 0.5706331 0.03445607 0.8273266 0.5604432 0.03787273 0.9385094 -0.3431451 0.03810125 0.4937714 -0.8683798 0.04589778 0.03715157 -0.01503902 0.9991965 -0.8215835 0.3236504 0.4693092 -0.4685305 0.1556113 0.8696347 0.6791722 -0.2072511 0.7041109 -0.8243717 -0.5647832 0.03783088 -0.9750574 -0.2203977 0.026232 -0.9391358 0.3417693 0.03489655 -0.9375774 0.3458287 0.03676068 -0.9390673 0.3415501 0.03868246 -0.4775652 0.8774104 0.04563534 1.86722e-4 -9.55092e-6 -1 0.03450983 -0.08750748 0.995566 -0.4941437 -0.8634835 0.1010867 -0.1161241 -0.523598 -0.8440145 -0.09308844 -0.1931553 -0.9767423 0.9569483 -0.285173 0.05409491 0.9467703 -0.3196803 0.03782427 0.5290371 -0.8391309 0.1264085 0.927328 0.3643152 0.08565777 -0.01493614 -0.0149089 -0.9997773 -0.01092487 -0.0157119 -0.999817 -0.2346218 -0.5531926 -0.7993314 -0.2161622 -0.603457 -0.7675374 0.9470636 0.3134438 0.06945157 0.4430485 -0.8954712 0.04288667 -0.5552045 -0.8308661 0.03754502 -0.6105359 -0.7919886 -3.33901e-4 0.05574238 0.9982227 -0.02108156 0.8320526 -0.5528017 -0.04581439 -0.4432532 0.8961338 -0.0216974 0.3812193 -0.9244567 -0.007186055 -0.9305718 -0.3079186 0.1980462 -0.9058997 -0.4229453 -0.02152156 -0.8878483 -0.460129 0.002648115 0.9075981 0.1999358 0.3691766 -0.9387987 0.3416911 -0.04363924 1.85875e-5 -6.84487e-6 -1 -6.81909e-6 -2.40002e-7 -1 -0.7690006 0.6290737 -0.1135978 -0.1269314 0.9362229 -0.3276813 3.26903e-7 0 -1 -0.01071989 -0.004685759 -0.9999316 -2.55652e-6 0 -1 -6.02517e-4 0.01081418 -0.9999414 2.50851e-6 0 -1 6.52152e-7 0 -1 0.9396926 -0.3420206 1.23251e-7 0.9396925 -0.3420206 0 0.5761775 0.8154801 -0.0548799 -0.8700269 -0.3456073 -0.3515806 -0.867264 -0.3891109 -0.3105575 -0.1707074 0.889657 -0.4235205 -0.9396998 0.3420005 -1.35637e-5 -0.9483882 0.317104 0.00223428 -0.9395477 0.3424184 -8.4551e-5 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -2.94708e-4 0.001463353 -0.999999 -0.03758829 -0.09609472 -0.9946622 0.3421852 0.9396325 -4.10604e-4 0.34202 0.9396927 0 0.9028097 -0.3279992 -0.2781212 0.05609869 0.1973876 -0.9787192 0.627856 -0.7769785 -0.04584187 0.9997248 -0.0161674 0.01700127 0.6773514 0.3587187 -0.6422742 0.5487197 0.7903506 -0.2724933 0.8962067 -0.4436366 0 0.2861486 -0.9581849 8.40316e-4 -0.08715319 -0.9961923 -0.002331912 0.8191498 -0.5735659 -0.004001855 -0.01864612 -0.07928192 -0.9966779 -0.3298161 -0.9006384 -0.2829698 -0.3420218 -0.9396921 0 -0.3420201 -0.9396926 0 -0.1683431 -0.3825032 -0.9084888 -0.08852159 -0.2432116 -0.9659255 -0.2263948 -0.698922 -0.6784199 -0.3291587 -0.9391782 -0.0979737 -0.9396919 0.3420223 0 -0.939692 0.3420219 -4.43873e-6 -0.9396925 0.3420205 3.26872e-6 -0.9396924 0.3420208 -7.38166e-6 -0.9396922 0.3420215 2.24706e-5 0.9396935 -0.3420178 -2.55108e-6 0.9461731 -0.3234463 -0.01178741 0.9396926 -0.3420204 1.92765e-5 0.6427977 -0.766036 0 0.6427949 -0.7660383 7.10201e-6 -0.9848101 -0.1736357 1.13351e-5 -0.9848116 -0.1736271 -5.39063e-7 -0.6895878 0.5360946 -0.4868997 0.02281904 0.9254468 0.3781897 0.3423336 0.9386478 0.04180991 -0.5889666 0.8069136 -0.04482191 0.5708504 -0.1361628 0.809685 0.5609133 -0.152344 0.8137369 0.3624545 -0.1189345 0.9243817 0.3129348 -0.1018993 0.9442926 0.3548474 -0.1768637 0.9180428 0.5405763 -0.196706 0.8179756 0.4485742 -0.1747945 0.8764862 0.5781193 -0.270494 0.7698123 0.5451392 -0.1987922 0.8144353 0.2684615 -0.08811575 0.9592518 0.4527751 -0.1742994 0.8744224 0.5564264 -0.01749539 0.8307129 0.5260391 -0.03138852 0.8498811 0.5895484 -0.1565194 0.7924231 0.5445118 -0.1973721 0.8152001 0.4637174 -0.1489437 0.8733739 0.4790804 -0.1132211 0.8704383 0.8599296 -0.1631753 -0.4836269 0.8746455 -0.4121295 0.2552347 0.4690755 -0.2663232 0.8420453 0.2218673 -0.596141 0.7716158 -0.7110677 0.2663975 0.6507036 -0.9354826 0.3532832 0.007965207 -0.9404016 0.3375878 0.04097974 0.4228562 -0.6898281 0.5876479 -0.1429001 -0.9224519 0.3586952 -0.3990057 0.08381444 0.9131098 -0.7201278 0.1656982 0.6737657 0.6703123 -0.2440415 0.7008033 0.001488566 0.008739471 0.9999607 -0.04316651 0.06177389 0.9971563 0 0 1 -1.07078e-6 -2.06168e-6 1 0.001731216 0.00272721 0.9999948 0.0253992 -0.008740246 0.9996393 -5.38313e-4 7.56313e-4 0.9999996 0.02083271 -0.01036167 0.9997293 0.003671705 -0.001260638 0.9999925 0.007483184 -0.00252968 0.9999689 0.003648042 -0.001306056 0.9999926 -3.43379e-4 1.17909e-4 1 -0.01706421 -0.003863573 0.9998469 0.1631982 -0.07919752 0.9834094 0.001472771 -0.001885831 0.9999972 -7.37881e-4 -3.52244e-4 0.9999997 -5.63504e-4 -4.34837e-4 0.9999998 0.004942178 -0.002533197 0.9999847 7.44095e-4 -2.58391e-5 0.9999998 4.96624e-4 6.53715e-5 0.9999999 0.2438076 0.06594389 0.9675791 -0.001859366 3.42172e-4 0.9999983 -7.35852e-4 3.313e-4 0.9999998 0.1724765 -0.04280292 0.9840833 -4.5331e-4 9.40795e-5 0.9999999 -4.8988e-4 -4.40952e-5 1 -0.001646697 6.08107e-4 0.9999985 -3.46389e-4 1.31373e-4 1 1.13927e-4 2.3814e-4 1 -0.001171469 5.45637e-4 0.9999992 -0.002587795 0.001281499 0.9999959 -0.002416312 9.12245e-4 0.9999967 -3.11545e-4 1.40699e-4 1 1.83541e-4 2.55399e-4 1 -0.007388293 -0.1685355 0.985668 -2.73395e-4 1.64223e-4 1 -0.001286149 6.13541e-4 0.9999991 -4.88696e-4 1.62598e-4 1 -0.07662934 0.06215286 0.9951207 -0.002530276 0.01276797 0.9999154 -3.9292e-4 1.26788e-4 1 2.37635e-5 -3.91918e-4 1 0.003171205 -0.001638412 0.9999937 -2.95278e-4 4.13321e-4 0.9999999 0.005697727 -0.001977086 0.9999818 -0.04011619 0.05599766 0.9976246 0.002115428 -8.34541e-4 0.9999974 -0.2253015 0.03371894 0.9737054 0.00251007 -0.001000463 0.9999964 -0.0572372 0.204672 0.9771558 0.002019822 -9.50829e-4 0.9999975 8.33302e-4 -5.86435e-5 0.9999997 -0.1135647 0.1046385 0.988005 6.36223e-4 -2.13141e-4 0.9999998 0.002818763 -6.41977e-4 0.9999958 0.003249168 -0.00118035 0.999994 7.11302e-6 2.79888e-4 1 5.65456e-4 8.66625e-5 1 0.00222516 -0.001087725 0.999997 2.1739e-4 -7.01807e-5 1 4.51345e-4 -1.70138e-4 0.9999999 0.002397358 4.78999e-5 0.9999971 -0.1328588 -0.01663982 0.9909953 -3.15472e-4 7.87003e-4 0.9999997 1.19325e-4 5.6817e-4 0.9999999 1.66451e-5 3.97271e-5 1 0.008303642 -0.003048241 0.9999609 0.008333742 -0.006764948 0.9999424 -0.07782936 0.04885596 0.9957689 -0.03632575 0.01287013 0.9992572 -6.26858e-4 -6.22571e-4 0.9999997 5.23959e-4 -2.77272e-4 0.9999999 -0.02083742 -0.00702846 0.9997582 8.71957e-5 -1.35865e-4 1 -2.17256e-4 -6.67648e-4 0.9999998 -4.42444e-4 -1.86067e-4 0.9999999 -0.03664851 0.01325786 0.9992403 -0.003793656 -0.01173585 0.999924 -0.001503765 -5.16376e-4 0.9999988 -1.1158e-4 -2.42313e-4 1 -3.95383e-5 1.49352e-5 1 1.72821e-4 6.19989e-5 1 -5.96689e-5 -2.92487e-4 1 -4.29157e-4 -1.46156e-4 1 -9.83017e-5 -2.17696e-7 1 0.002360403 -8.54037e-4 0.9999969 -0.002554595 8.93556e-4 0.9999964 1.57094e-5 -1.52851e-4 1 -5.92173e-4 3.11261e-4 0.9999998 -4.98644e-4 -0.001323163 0.999999 -0.002994954 0.001137733 0.9999949 7.12468e-4 -2.82349e-4 0.9999997 -5.71757e-4 -6.82008e-4 0.9999997 9.12838e-4 -6.05341e-4 0.9999995 0.001264512 0.00909096 0.999958 -0.8031788 -0.5505161 0.2276754 -0.9396936 0.3420178 -4.76567e-5 -0.8751358 0.3083867 0.3728738 -0.6627048 0.2585502 0.7028329 0.1246903 -0.04542785 0.9911553 0.9263736 -0.3356981 0.1707012 0.3599675 -0.1260119 0.9244158 0.2292625 -0.08548772 0.9696033 0.9396655 -0.3420948 -1.95557e-5 0.9387975 -0.3416962 -0.04362261 0.9388011 -0.3416868 -0.04362016 0.9387975 -0.3416967 -0.04361742 0.9387965 -0.3416996 -0.04362016 0.9387971 -0.341698 -0.0436173 0.9387972 -0.3416972 -0.04362177 0.9388007 -0.3416876 -0.04362106 0.9388007 -0.341688 -0.04361796 0.9387968 -0.3416981 -0.04362189 0.9387966 -0.3416994 -0.04361772 0.9387981 -0.341695 -0.04361891 0.9387987 -0.3416929 -0.04362338 0.938798 -0.3416951 -0.04362195 0.9387956 -0.341702 -0.04361969 0.9387944 -0.3417059 -0.04361462 0.9387933 -0.3417084 -0.0436185 -0.9387975 0.3416964 -0.04362183 -0.938797 0.3416981 -0.04361945 -0.938798 0.3416954 -0.04361993 -0.9388 0.3416899 -0.04361951 -0.9387991 0.3416926 -0.04361754 -0.9387996 0.3416915 -0.04361671 -0.9387996 0.3416911 -0.04361736 -0.9387983 0.3416951 -0.04361557 -0.9387965 0.3416991 -0.04362142 -0.9388025 0.3416833 -0.04361677 -0.9387979 0.3416951 -0.04362344 -0.9388037 0.3416807 -0.04361271 -0.9387993 0.3416917 -0.04361999 -0.9388014 0.341687 -0.04361134 0.9387972 -0.3416984 -0.04361438 -1.63589e-7 0 -1 0.3415985 0.938833 -0.04362589 -8.19159e-4 2.98101e-4 -0.9999997 -2.44901e-4 -6.72614e-4 -0.9999998 -0.3416842 -0.9388023 -0.04361402 -0.04677629 -0.02769488 -0.9985215 0.03249192 -0.0118255 -0.9994021 -0.01489531 -0.04092276 -0.9990513 0.3417108 0.9387927 -0.04361385 0.3417044 0.9387956 -0.04360085 -0.3416879 -0.938801 -0.04361397 -0.3416891 -0.938801 -0.04360371 -0.04677629 -0.02769452 -0.9985214 0.03249216 -0.01182574 -0.9994021 -0.01489478 -0.04092317 -0.9990513 0.3416896 0.9388003 -0.0436142 -2.17896e-7 0 -1 0.3416894 0.9387999 -0.04362463 4.35791e-7 0 -1 -0.3417107 -0.9387923 -0.04362428 -0.3417033 -0.9387947 -0.04362785 -0.04677617 -0.02769452 -0.9985214 -0.01489531 -0.04092252 -0.9990514 0.3417077 0.9387944 -0.04360294 0.3417051 0.9387945 -0.04361915 -2.17888e-7 0 -1 -0.3416941 -0.938798 -0.04363101 -2.18118e-7 0 -1 0.03249192 -0.01182585 -0.9994021 4.35792e-7 0 -1 -0.3416858 -0.9388015 -0.04361951 -0.3416873 -0.9388002 -0.04363536 -0.3416875 -0.9388016 -0.04360347 0.3416844 0.9388025 -0.04360884 0.3416926 0.938799 -0.04361939 -0.3416876 -0.9388008 -0.04361945 -0.341695 -0.9387977 -0.04363101 -0.3416845 -0.9388027 -0.04360359 -0.3416889 -0.9388006 -0.04361593 -0.04677623 -0.02769482 -0.9985214 0.3416859 0.9388015 -0.04361951 2.17896e-7 0 -1 2.1789e-7 0 -1 -0.3417091 -0.9387933 -0.04361361 -0.3417013 -0.9387958 -0.04362171 -0.04677629 -0.0276947 -0.9985214 0.03249174 -0.01182591 -0.9994021 0.3416914 0.9387984 -0.04364067 0.03249192 -0.01182615 -0.9994021 0.3416989 0.9387969 -0.04361641 -0.3416966 -0.9387976 -0.04361933 -0.3416903 -0.9388001 -0.04361408 -0.3416921 -0.9387992 -0.04362195 2.18114e-7 0 -1 0.03249192 -0.01182603 -0.9994021 -0.01489466 -0.04092282 -0.9990513 0.3416913 0.9387992 -0.0436244 0.3416941 0.9387984 -0.04361957 -0.3416954 -0.9387977 -0.04362469 0.3416972 0.9387973 -0.04361963 0.3416913 0.9387991 -0.04362934 -0.3416929 -0.9387986 -0.04362457 -0.3416919 -0.9387991 -0.04362326 -0.3416965 -0.9387979 -0.04361432 -0.04677635 -0.0276947 -0.9985214 0.0324918 -0.01182591 -0.9994021 -0.01489472 -0.04092293 -0.9990513 0.3416975 0.938797 -0.0436244 0.3416933 0.938799 -0.04361474 -0.3416957 -0.9387979 -0.04361921 -0.04677629 -0.0276947 -0.9985215 -0.01489472 -0.04092288 -0.9990513 0.3416942 0.9387986 -0.04361641 0.3416942 0.9387985 -0.04361927 -2.17895e-7 0 -1 1.35239e-7 0 -1 -0.09557145 0.0566684 -0.9938083 -3.87297e-5 -3.71171e-5 -1 -0.3416939 -0.9387986 -0.04361921 -0.3416948 -0.9387982 -0.04361879 0.3416939 0.9387987 -0.04361671 -0.0324918 0.01182597 -0.9994021 0.03249174 -0.01182597 -0.9994021 0.8683145 -0.3160424 -0.3822922 0.8683002 -0.3160299 -0.382335 0.8682565 -0.3160095 -0.3824509 0.8683813 -0.3160779 -0.3821109 0.8682435 -0.3160039 -0.3824851 0.868368 -0.3160674 -0.3821501 0.8682687 -0.3160208 -0.3824141 0.8683539 -0.3160576 -0.3821901 0.8682953 -0.316033 -0.3823437 0.8683522 -0.3160627 -0.3821894 0.8683113 -0.3160392 -0.3823019 0.8683161 -0.3160424 -0.3822883 0.868315 -0.3160417 -0.3822914 0.8683323 -0.3160442 -0.3822504 0.8683138 -0.3160404 -0.3822954 0.8683103 -0.3160398 -0.3823037 0.8683361 -0.3160479 -0.3822385 0.8683184 -0.3160422 -0.3822835 0.8683191 -0.3160414 -0.3822826 0.8683169 -0.3160424 -0.3822866 -0.8683201 0.3160384 -0.3822826 -0.8682332 0.316026 -0.3824902 -0.8683427 0.3160413 -0.382229 -0.8683868 0.3160601 -0.3821133 -0.868209 0.3160098 -0.3825588 -0.8683281 0.3160421 -0.3822615 -0.8682777 0.3160204 -0.3823937 -0.8683958 0.3160806 -0.3820759 -0.8683096 0.3160356 -0.382309 -0.8683151 0.3160395 -0.3822931 -0.868292 0.3160269 -0.3823558 -0.8683505 0.3160595 -0.3821961 -0.8683229 0.316044 -0.3822717 -0.8683194 0.316041 -0.382282 -0.8683198 0.3160448 -0.3822781 -0.8683183 0.3160382 -0.3822869 -0.8683152 0.3160471 -0.3822866 -0.3417002 -0.9387958 -0.04362773 -0.3416979 -0.9387983 -0.04359269 -0.01359397 -0.005337774 -0.9998934 -0.1099058 -0.8132546 -0.5714349 -0.1078341 -0.8131488 -0.5719798 -0.06779283 -0.8169977 -0.5726422 -0.003144025 -0.8118998 -0.5837885 -0.03883284 -0.8275837 -0.5599976 0.4877395 -0.6571162 -0.5747247 0.2476142 -0.7843815 -0.5687116 0.3745339 -0.7311824 -0.5701725 0.7452242 -0.3435201 -0.5715197 0.7442445 -0.3481405 -0.5699986 0.6838534 -0.4573137 -0.5685146 0.8212363 -0.06448835 -0.5669323 0.8192215 -0.04676681 -0.5715671 0.8185687 0.0895949 -0.5673782 0.8142257 0.1045053 -0.5710651 0.7882075 0.2418577 -0.5658922 0.7442001 0.3229078 -0.5847194 0.7213516 0.3778515 -0.5804139 0.7333145 0.3610211 -0.5761194 0.5106244 0.6330382 -0.5818294 0.5444312 0.6157651 -0.5695859 0.4185781 0.7045081 -0.5731149 0.4002819 0.7362868 -0.5455787 0.1666414 0.8213264 -0.5455765 -0.02616602 0.8200752 -0.5716574 0.003108322 0.8118996 -0.583789 0.06749117 0.8169963 -0.5726797 0.105043 0.8122162 -0.5738214 0.4662739 0.675862 -0.5707884 0.4360617 0.6925641 -0.5746347 -0.1671392 0.8025007 -0.5727627 -0.48852 0.653182 -0.578534 -0.6762067 0.4716176 -0.5659695 -0.7474591 0.3531303 -0.5626758 -0.7542142 0.3233028 -0.571521 -0.7764701 0.2560138 -0.5758048 -0.8131639 0.1092258 -0.5716941 -0.8179282 0.03184431 -0.5744383 -0.820343 -0.04596573 -0.5700216 -0.8026748 -0.18295 -0.5676639 -0.7222608 -0.355347 -0.593353 -0.6225987 -0.5326036 -0.5733275 -0.5169152 -0.64133 -0.5670049 -0.5099123 -0.65441 -0.5583341 -0.312413 0.7597237 -0.570279 -0.5668604 0.5967411 -0.567952 -0.4035597 -0.7293976 -0.5523756 -0.4680242 -0.690113 -0.551994 -0.5976658 -0.5903142 -0.5425171 -0.6942147 -0.4373599 -0.5716487 -0.823297 -0.08281117 -0.5615376 -0.9989807 0.04504007 -0.002999961 -0.9875959 -0.1569892 -0.002956748 -0.38919 -0.9211533 -0.002814173 0.005636394 -0.9999809 -0.00253123 0.5758806 -0.8175303 -0.002438843 0.7286422 -0.6848905 -0.002377927 0.9666486 0.2560979 -0.002063155 0.8953099 0.4454394 -0.002003073 0.7873183 0.6165438 -0.001928567 0.6470935 0.7624093 -0.001525223 0.3420183 0.9396923 0.00141555 0.4715688 0.8818274 -0.00187993 -0.9545174 -0.2981396 0.003064632 -0.7576495 -0.652655 0.002968728 -0.4359886 -0.8999475 0.00289452 -0.2449409 -0.9695339 0.00282377 0.1597747 -0.9871498 0.002723753 0.3569036 -0.9341375 0.00266689 0.5390375 -0.8422778 0.002587199 0.8291152 -0.5590725 0.002467989 0.9252471 -0.3793576 0.002403974 0.9829977 -0.1836032 0.002348721 0.6518759 0.7582569 0.01022124 0.2939842 0.9557939 -0.005617737 0.20559 0.9786341 0.002821862 -0.1067567 0.9942799 -0.003245115 -0.3047387 0.9524302 -0.003349304 -0.6044014 0.7966732 0.003300487 -0.7532445 0.6577326 0.0032714 -0.8711815 0.4909505 0.003245055 -0.6615936 0.2129804 -0.7189807 -0.7873714 0.2809968 -0.5487142 -0.786693 0.2808537 -0.5497595 -0.9323015 0.3393256 -0.125189 -0.8883028 0.3251032 -0.324386 -0.3702394 0.1368209 -0.9188051 0.6459333 -0.2611002 -0.7173541 0.64415 -0.1855667 -0.7420485 0.7744829 -0.2781161 -0.5681796 0.8600764 -0.3134416 -0.4025207 0.64944 -0.7573485 0.0681973 0.01767748 -0.00852853 0.9998074 0.3522838 0.1632408 0.9215468 0.02874547 -0.01312351 0.9995007 0.82976 0.5560055 -0.04854196 0.7406253 -0.2644556 0.6176872 0.7483894 -0.2747145 0.6036931 0.8939536 -0.309191 0.3244192 0.7424848 0.6657538 0.07408303 0.7960729 0.6020988 0.06119793 -0.7782298 0.139519 0.612285 -0.7754334 0.4065887 0.4831033 0.8096274 0.5867944 0.01326167 -0.7101418 0.7040367 0.005564272 -0.01910436 0.01086884 0.9997585 -0.005095183 -0.05451703 0.9984999 -0.5917827 -0.7558702 0.2800959 0.2642702 0.9503096 0.1645391 0.7491309 -0.6556304 0.09461408 0.7836646 -0.62016 -0.03565847 0.2205613 -0.5248429 0.8221269 0.5969167 -0.2290158 0.7689228 -0.2400742 -0.1869048 0.9525918 -0.7019907 0.2617138 0.6623557 -0.5404942 0.2082344 0.8151715 -0.8255157 -0.5643599 -0.004658222 -0.7452014 -0.6635612 0.06604117 -0.9988315 -0.03699314 0.03110188 -0.6806423 -0.6635181 0.310596 -0.09763342 -0.9687451 -0.2280365 0.9652278 -0.2504481 -0.07490694 -0.07503056 0.9939315 -0.08044058 -0.9518938 0.2255758 -0.2073974 0.5388819 0.8412977 -0.04271411 -0.8652005 -0.4448733 -0.2313349 -0.2715696 0.9542969 0.1247694 -0.7082273 0.7058974 -0.01109349 0.7456995 0.6597641 0.09297174 0.2962144 -0.7976238 -0.5254077 -0.9806531 -0.06315743 0.185286 0.02515208 0.9990435 0.03577065 0.9954404 0.09340256 -0.01934802 0.3566497 -0.9253479 0.128578 0.7848992 -0.6187015 -0.03379136 -0.8141223 0.4755892 -0.3331965 -0.7042008 -0.6262522 0.3345289 -0.9937439 0.01557272 0.1105924 -0.5511597 0.8337987 -0.03166484 0.7869125 0.4058576 0.4648098 0.4675372 -0.881221 -0.06970405 -0.7582864 -0.6399261 -0.1244848 -0.7751623 0.5971356 -0.206283 0.2054641 -0.9765765 -0.06389683 0.5451036 -0.8345862 -0.0795499 0.8151664 0.09418338 0.5715184 0.9472098 0.003889799 0.3205909 0.5352402 0.6298944 0.5628064 0.680938 0.4681565 0.5631635 0.5861037 -0.5754287 0.5704072 0.586296 -0.5722166 0.5734329 -1.3394e-5 4.9308e-6 -1 -0.02725434 -5.04514e-4 -0.9996285 2.18729e-4 -0.03541517 -0.9993727 -0.04180592 0.01743674 -0.9989737 0.001360058 0.001128673 -0.9999985 0.09710204 0.004957675 -0.9952622 0 -5.73638e-5 -1 -1.13067e-4 5.69753e-5 -1 -0.7986191 -0.08676069 0.5955504 -0.8137811 -0.1529725 0.5606779 -0.6663819 -0.4686627 0.5799056 2.80524e-5 -1.24266e-5 -1 0.001319468 -7.95217e-4 -0.9999989 9.87249e-7 -4.13456e-7 -1 1.2878e-5 -4.93024e-6 -1 -0.009099185 0.1185105 -0.9929111 -0.01731675 0.04643291 -0.9987713 2.42043e-4 -1.69952e-4 -1 -0.001704454 -1.02052e-4 -0.9999986 4.05877e-4 -0.006902158 -0.9999762 0.00465393 -8.31682e-4 -0.9999889 1.03527e-6 5.73627e-5 -1 -0.9147513 -0.2569482 -0.3117814 -0.7710364 -0.5956724 0.2251162 0.9106221 0.2745421 -0.3088595 0.5275045 0.8364193 0.1488013 -0.9662019 0.2441707 0.08267098 -0.001192986 -3.64345e-4 -0.9999993 0.001339614 -7.41708e-4 -0.9999989 0.001489758 6.4897e-4 -0.9999988 0.002993762 1.84901e-4 -0.9999956 0.8892853 -0.4513744 -0.07370734 -0.52797 -0.836189 0.1484443 0.3545625 -0.9327459 0.06534987 0.8308021 -0.210137 -0.5153741 -0.1267458 0.9517818 0.2793694 -6.8817e-4 -8.96407e-4 -0.9999994 7.18904e-5 4.1473e-4 -1 2.49444e-5 4.13851e-4 -1 -7.25897e-4 -7.44005e-4 -0.9999995 6.93029e-4 -3.26229e-4 -0.9999998 6.14131e-4 7.99982e-4 -0.9999995 -4.98214e-4 7.26583e-4 -0.9999996 0.9365265 -0.3499034 -0.02204161 0.9274694 -0.3380823 -0.1596897 -0.9639208 -0.2474725 0.09805184 -0.9992504 -0.01978033 0.03328126 -0.7528915 0.6574876 0.02940434 -0.798187 -0.5621051 0.2166461 -0.7364981 -0.6752883 0.03945082 1.85682e-4 -2.33831e-5 1 -5.90274e-5 -2.20328e-5 1 0.06277477 0.02842634 0.9976229 0.06068301 0.04624485 0.9970852 0.006400763 0.001757919 0.999978 0.02770996 0.022385 0.9993653 0.03243565 -0.02050662 0.9992635 4.90544e-4 1.10902e-5 0.9999999 3.25051e-6 2.15209e-6 1 0.001291811 0.01356154 0.9999073 0.01514029 0.00950694 0.9998402 -0.03669655 -0.00799185 0.9992945 4.22478e-4 -5.17641e-5 1 3.04185e-5 1.6432e-5 1 -0.00172615 -0.01855766 0.9998264 1.07759e-5 -9.44971e-6 1 -1.26629e-4 2.85912e-5 1 0.03191035 0.9973629 -0.06518435 0.5357981 0.8436191 0.03503417 0.990961 -0.1327396 0.01940649 0.3804157 -0.9242985 0.03092277 -0.8490895 0.5274477 -0.02908754 0.7974005 -0.5996392 -0.06771546 -0.3816542 -0.9227674 -0.05329871 -0.380667 0.9247068 -0.003189265 0.3806622 -0.9247087 -0.003188967 -0.9911546 0.1326745 -0.003187596 0.5102705 0.8595308 -0.0288254 0.4720352 -0.8810963 -0.02919602 -0.527095 -0.8493056 -0.02917116 -0.999067 0.03183436 -0.0291835 0.9404912 -0.3346323 -0.05914002 0.664458 -0.2418433 0.707112 0.03249162 -0.01182585 -0.9994021 0.3417167 0.9388713 -0.0418393 -0.6644622 0.2418446 0.7071077 -0.6644634 0.2418472 0.7071056 -0.6644663 0.2418438 0.707104 -0.6644784 0.2418541 0.7070891 -0.6644482 0.2418279 0.7071264 -0.6644759 0.2418578 0.7070903 -0.6644635 0.241837 0.707109 -0.6640136 0.2441958 0.7067209 0.6644697 -0.2418435 -0.7071009 -0.6644639 0.2418447 0.707106 0.6647332 -0.2419453 -0.7068184 -0.6644606 0.2418446 0.7071092 -0.6644607 0.2418451 0.7071089 -0.6644638 0.2418437 0.7071065 0.6644619 -0.2418451 -0.7071078 0.658498 -0.2464445 -0.7110876 0.6838837 -0.2539004 -0.6839867 0.6874994 -0.1781193 -0.7040016 0.6874976 -0.1781206 -0.7040029 0.6875012 -0.1781229 -0.7039989 0.7168693 -0.2609194 -0.6465443 0.7168691 -0.2609199 -0.6465443 0.6875004 -0.1781202 -0.7040004 0.6875015 -0.1781197 -0.7039994 0.6874979 -0.1781117 -0.704005 0.7168707 -0.2609171 -0.6465436 0.716867 -0.2609061 -0.6465523 0.7168645 -0.2609116 -0.6465528 0.6875008 -0.1781154 -0.7040011 0.7168671 -0.2609196 -0.6465467 0.6874997 -0.1781194 -0.7040013 -0.6648461 0.2407123 -0.7071332 -0.7168705 0.2609144 -0.646545 -0.6411461 0.3054692 -0.704003 -0.716869 0.2609206 -0.6465442 -0.7168663 0.2609217 -0.6465467 -0.6411502 0.3054679 -0.7039998 -0.6411495 0.3054682 -0.7040005 -0.6411476 0.3054684 -0.7040021 -0.6411488 0.3054737 -0.7039987 -0.6411526 0.3054624 -0.7040001 -0.7168685 0.2609174 -0.646546 -0.7168642 0.2609214 -0.6465492 -0.6411503 0.3054624 -0.7040022 -0.6411451 0.3054766 -0.7040008 -0.641149 0.3054691 -0.7040004 -0.01529175 0.006685256 -0.9998608 -0.03462582 -0.00582695 -0.9993834 0.002601683 -0.004403889 -0.999987 0.6253575 -0.174857 0.7604954 -0.2953914 0.1688295 0.9403407 0.9337098 0.2290111 -0.275209 -0.715027 -0.1525445 0.682251 0.7052438 -0.327186 -0.6289519 -0.6295971 0.1158531 0.7682355 -0.8664015 -0.004679381 0.4993262 -0.8125457 -0.03177309 0.5820309 -0.8068583 -0.1359789 0.5748823 -0.3317084 -0.1853663 0.9249913 -0.1723534 -0.3680421 0.9136955 -0.05148059 -0.3732504 0.9263013 0.03098487 -0.3360258 0.941343 -0.230914 -0.2605866 0.9374292 -0.08875441 -0.3753944 0.9226061 -0.9149709 0.4019249 0.03584104 -0.9163448 0.3986998 0.03675365 1.58817e-5 -5.77805e-6 1 -0.006385028 -0.01554411 0.9998589 2.40936e-5 -1.40341e-4 1 -0.2577217 0.9655498 0.03596079 0.3301598 0.9432849 0.03475952 0.7888481 0.6135687 0.03538811 0.7914571 0.6103014 0.03358286 0.3848168 -0.09011602 0.9185833 0.8162394 -0.3234158 0.4787021 0.9394685 -0.3413661 0.02946531 0.941611 -0.3349362 0.03444743 0.6537135 -0.7541085 0.0630809 0.2552455 -0.9662067 0.03597903 0.2749528 -0.9609848 0.03015482 -0.1037819 -0.1957104 0.9751548 -0.3299301 -0.9433504 0.03516149 -0.7888866 -0.6135193 0.03538727 -0.4796958 0.1745951 0.8598886 -0.9394065 0.3415378 0.02945178 -0.941468 0.335343 0.03439998 0.2944748 0.757815 0.582238 0.3417909 0.9392069 0.03270161 0.4180312 -0.07071346 0.9056764 1.82125e-6 2.76361e-4 1 4.12631e-5 -3.52568e-4 1 0.78885 0.6135667 0.03537988 0.791445 0.6103174 0.03358024 0.9415883 -0.3349246 0.03517097 -0.3299311 -0.94335 0.03516018 -0.3301641 -0.943282 0.03479832 -0.4877696 0.0995379 0.8672791 -0.9415779 0.3349444 0.0352593 -0.06907278 -0.2732648 0.9594557 -0.2263715 -0.0313304 0.9735371 -0.3417674 -0.9391283 0.03511571 -0.7880287 -0.6145893 0.03593063 -0.9393126 0.3417952 0.02946186 -0.1799313 0.1607041 0.9704632 -0.2599018 0.9649703 0.03582608 0.7958556 0.6047177 0.03050351 0.9389961 -0.3426663 0.02943003 0.2292073 -0.9729832 0.0277099 -0.01515358 -0.03830182 0.9991514 3.09756e-6 2.03478e-4 1 -0.9416044 0.3349545 0.03444826 -0.6536906 0.7541282 0.06308323 0.3299286 0.9433513 0.03514951 0.7544165 0.5407803 -0.3720383 0.7914903 0.610259 0.0335744 0.416145 -0.06884247 0.9066885 0.2603436 -0.9648703 0.03530865 0.274817 -0.9610265 0.03006219 -0.0638917 -0.2260426 0.9720199 -0.2610142 -0.7074198 0.6568325 -0.3419929 -0.939478 0.02054321 -0.4890776 0.1424251 0.8605337 -0.01515358 -0.0383017 0.9991514 -1.56158e-6 2.7975e-4 1 -0.8202339 -0.5710148 0.03403592 -0.9394518 0.3414126 0.02946078 -0.6536814 0.7541376 0.06306391 -0.255249 0.966211 0.03583592 0.2981876 0.7457816 0.59573 0.3301715 0.9432808 0.03475946 0.7888587 0.6135541 0.0354048 0.7914668 0.6102887 0.03358483 0.9415842 -0.3349252 0.0352751 0.2748162 -0.9610267 0.03006207 -0.06389385 -0.226056 0.9720166 -0.5755827 -0.4307622 0.6950889 -0.4337454 -0.257678 0.8634044 -0.4907865 0.1429223 0.8594776 -0.01515328 -0.03830111 0.9991514 -1.55661e-6 2.79732e-4 1 -0.8095657 -0.5866469 0.02118569 -0.7914527 -0.6102744 0.0341739 -0.9416139 0.3349279 0.03444755 -0.255243 0.9662119 0.035856 0.33019 0.9432743 0.03475952 0.7544187 0.5407877 -0.3720231 0.7914646 0.6102916 0.03358244 0.2603372 -0.9648708 0.03534233 0.275135 -0.9609351 0.0300762 -0.2610417 -0.7075044 0.6567304 -0.3332014 -0.9422025 0.03509163 -0.01515358 -0.03830182 0.9991514 3.09753e-6 2.03464e-4 1 -0.8202227 -0.571031 0.03403657 -0.9394555 0.3414018 0.02946722 -0.941602 0.3349627 0.03443396 -0.6536357 0.7541745 0.06309902 0.2981742 0.7457364 0.5957932 0.3301708 0.9432809 0.03476428 0.7888585 0.6135542 0.03540623 0.7914727 0.6102812 0.03358346 0.4161368 -0.06883996 0.9066926 0.9389887 -0.3426862 0.02943736 0.9415849 -0.3349235 0.0352751 0.2603433 -0.9648704 0.03530865 -0.2610498 -0.7075214 0.6567088 -0.5772656 -0.4286957 0.6949708 -0.0151537 -0.038302 0.9991513 3.09756e-6 2.0349e-4 1 -0.939453 0.3414086 0.02946722 -0.2745649 0.9610974 0.03009939 0.2981747 0.7457373 0.5957918 0.3299285 0.9433521 0.0351293 0.7544437 0.540803 -0.3719502 0.7888622 0.6135507 0.03538441 0.7914414 0.6103212 0.03359884 0.2603495 -0.9648701 0.03526777 -0.333202 -0.942209 0.03490918 -0.5756163 -0.4308024 0.6950361 -0.8161498 0.323385 0.4788755 -1.55663e-6 2.79836e-4 1 3.10394e-6 2.0351e-4 1 -0.8095436 -0.5866773 0.02118849 -0.7914538 -0.6102741 0.03415507 -0.9394631 0.3413807 0.02946484 -0.9416101 0.3349379 0.03445273 -0.6536967 0.7541223 0.06308919 -0.2552586 0.966206 0.03590494 -0.2745514 0.9611014 0.03009688 0.2981843 0.7457682 0.5957483 0.7544351 0.5407988 -0.3719736 0.9415825 -0.3349305 0.03527158 -0.5772489 -0.4286856 0.6949911 -0.8161437 0.3237456 0.4786422 -1.5566e-6 2.79768e-4 1 0.01386284 0.04624837 0.9988338 -0.8115756 -0.5829058 0.03957331 -0.9416024 0.3349616 0.03443509 -0.2552959 0.966201 0.03577345 0.2982054 0.7458238 0.5956681 0.3299388 0.9433466 0.03517931 0.7888561 0.6135568 0.03541278 0.7914701 0.6102846 0.03358507 0.9389798 -0.3427108 0.02943545 0.2748641 -0.9610128 0.03006821 -0.3331993 -0.9422091 0.03493142 -0.2263808 -0.0313301 0.9735349 1.40115e-5 -1.51109e-4 1 2.92006e-4 0.01577377 0.9998756 -0.3418715 -0.9390961 0.03496515 -0.3416731 -0.9391574 0.03525453 -0.7918405 -0.6098033 0.0335958 -0.1799205 0.1606969 0.9704665 -0.2599218 0.9649651 0.03582245 -0.2745969 0.9610879 0.03011143 0.2442628 -7.05911e-4 0.9697088 0.939 -0.3426556 0.02943068 0.9415902 -0.3349067 0.03529214 0.2106274 -0.9769231 0.03546124 0.2292727 -0.9729685 0.02768558 -0.5762634 -0.4299173 0.695048 -0.4332016 -0.2573916 0.8637627 -0.6536202 0.7542027 0.06291985 -0.01518422 -0.03831732 0.9991503 -1.62549e-6 2.80908e-4 1 2.52691e-6 2.13107e-4 1 -0.9390792 0.3419589 0.03455978 -0.2746403 0.9610756 0.03010809 0.2982325 0.7458291 0.5956479 0.3299251 0.9433522 0.03515905 0.3301665 0.943283 0.03474605 0.7888249 0.6135978 0.03539884 0.4144079 -0.06933486 0.9074463 0.9421952 -0.3337567 0.02957493 0.9383603 -0.3436841 0.03689581 0.2917339 -0.956167 0.02522248 -0.2604745 -0.7078 0.6566371 -0.7857476 0.1759818 0.592985 -0.5337597 0.1930949 0.8232953 -0.5467998 0.1985982 0.8133688 -0.2503655 0.2065876 0.9458534 -0.5031582 0.1636814 0.848552 -0.4931017 0.2134291 0.8433853 -0.5392204 0.1962803 0.8189722 -0.4790944 0.1655424 0.8620117 -0.4918435 0.1637676 0.8551434 -0.5388967 0.196137 0.8192197 -0.540264 0.1966488 0.8181957 -0.5519204 0.2205922 0.8041909 -0.5404507 0.1966586 0.8180699 -0.5408539 0.1969099 0.817743 -0.5538569 0.1871246 0.8113119 -0.4743485 0.181558 0.8614118 -0.3518595 0.09856051 0.9308496 -0.5395673 0.196368 0.8187227 -0.5742527 0.3204926 0.7533381 -0.5361899 0.1842889 0.8237343 -0.5069547 0.2081076 0.8364737 -0.6359899 0.08633267 0.766853 -0.3877366 0.1325588 0.9121888 -0.5024908 0.1850208 0.8445534 -0.4068797 0.1815387 0.8952612 0.62232 -0.05217397 -0.7810222 -0.2410634 -0.05035036 0.9692025 -0.5402447 0.2009836 0.8171545 -0.520411 0.225544 0.8235912 -0.5224915 0.239669 0.8182674 -0.06221652 -0.05524933 0.9965324 0.6109161 -0.25338 0.7500534 0.7180257 -0.4439237 0.5360699 -0.6791805 0.1829077 0.7108155 -0.4926616 -0.6674394 0.5583989 -0.2282516 -0.6952972 0.6815153 -0.09286963 -0.7205777 0.6871266 -0.1882813 0.6688131 0.7191935 -0.2003683 0.6815415 0.7038138 0.2200504 0.6493381 0.7279684 0.2549989 0.7211887 0.6440982 0.003176033 0.00182408 -0.9999934 -0.3863319 0.4066949 0.8278569 -0.1012528 -0.3387587 0.9354093 -0.4498905 0.1076816 0.8865682 0.1611851 -0.4600394 0.8731456 0.4052 -0.1781639 0.8966999 0.4059306 0.3198457 0.856107 0.2595919 0.3055381 0.9161105 -0.1534525 0.38051 0.9119564 -0.340718 0.5258471 0.7793563 -0.598331 0.7937803 0.1091465 -0.320522 0.9433649 0.08560693 0.9684745 0.2187386 0.1192088 0.996893 -0.07876807 0 -0.20363 0.9777146 -0.05107975 0.4805572 0.8754807 -0.05097436 0.6575698 0.7517368 -0.0499376 0.8846318 0.4633846 -0.05197435 0.9974182 -0.07180583 0.001043796 0.9797602 0.1999785 -0.008862555 0.9559755 0.2933439 0.007762372 0.8856906 0.4639509 0.01737767 0.8135623 0.5805975 -0.03198492 0.5717094 0.8100673 -0.1301509 0.3794777 0.9235888 0.05459558 0.3276792 0.9044716 0.2730526 -0.0561347 0.9910283 0.121293 -0.4204942 0.907288 -0.003635585 -0.5589358 0.8292073 0.002448856 -0.6690092 0.7432535 9.08024e-4 -0.8140451 0.5808018 0 -0.5437528 0.8391939 0.009295642 -0.7612318 0.6484797 -3.98555e-4 0.9670007 -0.2547737 -1.47206e-4 -0.9741804 0.2166786 0.06342667 -0.00112009 7.65477e-4 0.9999992 -7.36063e-4 8.47349e-4 0.9999995 -6.45322e-6 6.02766e-5 1 -9.34948e-4 -0.009739339 0.9999522 -0.003297448 -0.0107221 0.9999372 -0.004187583 -0.007646143 0.999962 -0.0116167 -0.009096622 0.9998912 -0.001263618 -3.34946e-4 0.9999992 -1.17573e-4 -6.63594e-6 1 -1.19706e-4 1.76734e-5 1 5.75641e-5 -3.51662e-5 1 1.48391e-4 -1.39172e-4 1 1.02287e-4 -1.45788e-4 1 1.23038e-5 -5.75267e-5 1 9.76918e-5 -1.21814e-4 1 -1.49453e-4 -3.73865e-4 1 -3.13094e-4 -4.55919e-4 0.9999999 -1.76497e-4 -1.70425e-4 1 -6.81143e-4 -1.08184e-4 0.9999998 -3.52686e-4 -4.78409e-4 0.9999999 -0.9579117 0.287061 -0.001068115 -0.9570908 0.2897753 -0.002744972 -0.9371455 0.3488874 0.005998492 -0.9127331 0.4085564 1.61705e-4 -0.9513552 0.3080081 -0.007369875 -0.9456899 0.3249817 -0.00759685 -0.9397123 0.3418835 -0.007524073 -0.9334384 0.3586663 -0.007167637 -0.9599735 0.2800899 8.53477e-4 -0.9637063 0.2666604 -0.01274716 0.9114362 -0.4114408 8.60207e-4 0.9095529 -0.4153785 -0.01320916 0.9095152 -0.415441 -0.01381474 0.9161764 -0.4007751 8.19955e-5 0.9015339 -0.4326924 -0.003761827 0.9178418 -0.3969464 -4.52183e-4 0.9194295 -0.3932458 -0.002687275 0.9512764 -0.3082721 -0.006454408 0.9566199 -0.2912909 -0.005294263 0.9616228 -0.2743538 -0.003387629 0.9618088 -0.2737224 1.97701e-4 0.9248391 -0.3803172 0.005620121 0.9308325 -0.3653943 0.006146669 0.936617 -0.3503003 0.006201982 0.9474488 -0.3198606 0.005484044 0.9524906 -0.3045337 0.004575908 0.9572792 -0.2891499 0.002996325 0.5967793 -0.6523764 0.4671828 0.3525071 -0.3737758 0.8579221 0.6163901 -0.7614175 0.2007656 0.6193261 -0.6086723 0.4959367 0.7267194 -0.6858997 0.03768926 -0.4340173 0.1436393 -0.88938 -0.6814371 0.247586 -0.6887269 -0.4992657 0.1694481 -0.8497183 -0.4996042 0.164231 -0.8505433 -0.4670678 0.1566597 -0.8702329 -0.4549793 0.1635501 -0.8753544 -0.4559492 0.169744 -0.873669 -0.4822649 0.1779998 -0.857751 -0.4590088 0.1737236 -0.8712813 -0.4811077 0.1757416 -0.8588657 -0.467345 0.1755699 -0.8664663 -0.4666509 0.1832063 -0.8652586 -0.4698013 0.1830955 -0.8635755 -0.4664618 0.182289 -0.8655542 -0.4638583 0.19248 -0.8647468 -0.4576633 0.1951075 -0.8674547 -0.4570458 0.1971237 -0.8673243 -0.4579498 0.204636 -0.8651046 -0.4268379 0.1858218 -0.8850309 -0.4565045 0.1968876 -0.867663 0.2217575 0.9711667 0.08751493 0.9330645 -0.3572074 0.04235106 -0.5298895 -0.8480666 -4.46925e-4 0.9395117 -0.3407599 0.03464794 0.2742917 0.957418 0.09008264 0.2074455 0.975717 0.07030367 0.9399319 -0.3396069 0.03457403 0.9428552 -0.3313246 0.03532904 0.94596 -0.3223857 0.03503423 0.4669986 -0.8842549 -0.002395212 0.9494696 -0.3119567 0.03450429 0.9514617 -0.3047218 0.04318958 0.3756875 -0.9259572 0.03823965 -0.01903641 0.01169371 -0.9997504 -0.004393637 0.001401126 -0.9999895 -1.80329e-7 0 -1 -2.07121e-7 0 -1 -2.40793e-7 0 -1 -2.52719e-6 1.32305e-6 -1 0.01717704 -0.006184339 -0.9998334 7.35319e-4 -2.7161e-4 -0.9999997 -0.001325666 9.28216e-4 -0.9999987 -1.51518e-7 0 -1 0.001625716 -4.63647e-4 -0.9999986 -0.08408451 0.03241384 -0.9959314 -0.00259751 8.52102e-4 -0.9999964 0.002282083 -0.001655399 -0.9999961 -1.21044e-6 0 -1 0.001036465 -4.15457e-4 -0.9999994 -0.09008628 0.03081732 -0.9954571 9.93575e-4 -0.001153171 -0.9999989 0.01309722 -0.004767 -0.999903 -0.008481144 0.003086745 -0.9999593 -0.008479952 0.003086447 -0.9999593 0.01494473 -0.005439579 -0.9998735 -0.07628399 0.03518527 -0.9964652 -0.06465798 0.02529364 -0.997587 -0.06699937 0.01910901 -0.9975701 -0.05434995 0.01014721 -0.9984705 -0.0610482 0.01554656 -0.9980137 -0.008487164 0.003089845 -0.9999593 1.8346e-4 7.81952e-4 -0.9999997 0.03561222 0.02385729 0.9990809 -0.9603214 -0.2756457 0.0424537 -0.7935419 -0.6013522 0.09309649 -0.938205 0.3442614 0.03543692 0.01924145 0.9982546 0.0558359 -0.9415369 0.3350831 0.03504019 -0.8988781 -0.4363251 0.04047858 -0.9446675 0.3261228 0.03531944 0.5964745 0.8022696 -0.02411937 -0.4679982 0.8789413 0.09186923 -0.9475309 0.3176711 0.03564131 -0.4124348 -0.9109506 0.008163511 -0.9505009 0.3086863 0.03551036 -0.9506437 0.3081329 0.03647732 0.9804358 -0.1122415 -0.1617019 -0.7869539 -0.6104498 0.08974736 -0.1440995 0.9846379 0.09860849 0.5509971 -0.2586863 0.7934 -0.8092737 0.1637306 -0.564153 0.9462453 -0.3043099 -0.109615 0.9479526 -0.2977541 -0.1128199 0.8061859 0.4817664 -0.3434611 0.9667584 0.08075898 -0.2426027 0.826468 0.4523767 -0.3351212 0.5250514 0.7655655 -0.3717938 0.3703207 0.50628 -0.778809 0.8405678 0.02901798 -0.5409286 0.8751609 -0.06705546 -0.4791628 0.9220255 -0.3176945 -0.2212223 0.9151626 -0.3550227 -0.190883 0.8702828 -0.4917133 -0.0287432 0.8717427 -0.4893835 -0.02384597 0.1116512 0.9208567 -0.3735734 -0.3078966 0.8872626 -0.3434601 -0.6650354 0.7025997 -0.2531436 0.08989065 0.9239531 -0.3717935 -0.688532 0.6836428 -0.2419842 -0.9117817 0.3472152 -0.2193076 -0.7135179 0.5111697 -0.4791635 -0.6086524 0.5710134 -0.5508956 -0.1708839 0.6585987 -0.7328345 0.3192917 0.8768411 -0.3594474 0.2198463 0.6040208 -0.7660461 -0.5736741 -0.8190771 -0.003322243 -0.9055653 -0.4241863 -0.004182636 -0.9996068 -0.02804225 1.71303e-4 -0.996186 0.08716368 -0.004002034 4.07344e-7 0 -1 -2.16759e-6 0 -1 -9.48786e-4 -5.21798e-4 -0.9999995 -1.78319e-4 1.46759e-4 -1 -1.03188e-4 1.43486e-4 -1 0.2208468 0.6040565 -0.76573 0.2198469 0.6040215 -0.7660453 0.2208643 0.6040355 -0.7657417 0.6808591 0.2194414 -0.6987677 0.2208406 0.6040323 -0.7657509 0.9396927 -0.3420199 2.10089e-5 0.9396924 -0.3420211 1.77543e-4 0.6644652 -0.2418456 0.7071045 0.6644744 -0.2418462 0.7070956 0.6644438 -0.2418316 0.7071294 0.664467 -0.2418467 0.7071024 -0.6644221 0.2418442 -0.7071455 -0.6641363 0.2416851 -0.7074682 0.6644452 -0.2418394 0.7071254 0.6648004 -0.2419034 0.7067695 0.66444 -0.2418414 0.7071296 0.6644496 -0.2418413 0.7071205 0.6644633 -0.2418446 0.7071067 0.664459 -0.2418438 0.7071109 0.664486 -0.2418456 0.707085 0.6644511 -0.2418413 0.7071192 0.6644499 -0.241844 0.7071195 0.6644655 -0.241849 0.7071031 0.6874983 -0.1781204 -0.7040023 -0.3516041 -0.9343931 0.0573073 -0.3328076 -0.9419376 0.04464232 -0.09567391 0.9269077 0.3628894 -0.0171824 -0.01101249 0.9997918 6.47258e-4 0.001572608 0.9999986 1.01706e-4 0.001281142 0.9999992 0.007484793 0.009887516 0.9999231 0.02261644 0.01373738 0.9996499 -0.03759068 -0.003406882 0.9992875 -0.04502201 0.1325708 0.9901505 -0.9203598 0.3303936 -0.209232 -0.1047356 0.8514167 -0.5139264 -0.1520535 0.7560505 -0.6366061 -0.1595149 0.9703252 -0.1817258 -0.3638234 0.5780624 -0.7303947 -0.1976451 0.53342 -0.8224352 -0.178077 0.4027637 -0.8978141 -0.179318 0.2048681 -0.9622236 -0.3824484 -0.1353936 -0.9140032 -0.01166874 0.112533 -0.9935795 0.3286356 0.9437571 0.0363481 -0.1282784 0.9689494 -0.2113806 -0.04664528 0.95682 -0.2869143 0.03059083 0.9995309 -0.001536488 0.2464153 0.9685104 0.03559976 0.03943389 0.9992126 -0.004408419 -0.08664619 0.9961099 0.01605135 -0.1323732 0.9911719 0.007453441 -0.253811 0.9630106 0.09050309 -0.314417 0.6208499 -0.7181138 0.9385939 -0.2957952 0.1776143 -0.1612311 -0.8805136 -0.4457582 -0.1805297 0.5654854 -0.804758 -0.2147077 -0.7082558 0.6725135 0.5343407 0.08334857 0.8411499 0.536238 0.07303822 0.8409009 0.6043332 0.4038179 0.6868133 0.5427866 0.8366554 -0.07341945 0.3874201 0.9218953 -0.003849685 0.367904 0.9295368 -0.02465659 0.4566887 0.8741095 -0.1654331 -0.06017893 0.9974002 0.0396437 -0.5841258 -0.5014272 0.6382539 -0.4738187 -0.856811 -0.2033981 0.09381157 -0.01764655 0.9954336 0.7716671 0.603009 0.2022621 0.03507387 0.1254883 -0.9914749 -0.005239009 0.9689629 -0.2471513 0.6966153 0.710427 -0.1001033 -0.5839092 0.811807 0.00442481 -0.4623529 0.8866874 0.003915548 -0.3955445 0.9184413 -0.003176152 -0.2723643 0.9621623 0.00785315 -0.2747765 0.9615029 0.003183603 -0.01469618 0.999854 0.008711695 0.04740804 0.9984385 -0.02954941 0.1952671 0.9804536 0.02411836 0.3181774 0.9479022 -0.01564556 0.4065849 0.9133521 0.02182912 0.4165694 0.9089248 0.01805567 0.7795346 0.6262462 0.01189285 0.8931052 0.4498362 -0.003235876 0.8833292 0.4683687 -0.01898348 0.7329609 0.6787207 -0.04589748 0.9912507 0.1319595 0.002989768 0.9825 0.1862051 -0.004616618 0.292562 0.9560927 -0.01715457 0.2736886 0.9618183 4.87849e-4 0.128207 0.9917029 -0.00940299 -0.2640175 0.9644892 -0.007443308 0.001064419 0.9999779 0.006564736 0.1174356 0.9929963 -0.01293891 0.927908 -0.243246 0.2825213 -0.4736228 -0.8801039 0.03314656 0.4212289 0.9069252 -0.00728023 0.3440657 0.9222816 -0.1761127 -0.2486524 0.6393588 -0.7275935 0.3137831 0.948781 -0.03681218 0.4453051 0.8947475 -0.03362196 0.6157097 0.7878349 -0.0147621 0.7584417 0.6514069 -0.02086561 0.9627185 0.22662 -0.1477046 0.01855462 -0.9948276 -0.09986948 0.7868506 0.6171309 0.00396192 0.6934498 0.4936882 -0.5247852 0.3006824 0.8609307 -0.4103516 0.8904799 0.3295304 -0.313776 0.4984699 0.4540378 -0.7384968 0.2886846 0.107283 -0.9513946 0.1369137 0.09351247 -0.9861593 -0.4727529 0.5463232 0.6914013 -0.514361 0.5491077 0.6587211 0.3419488 0.9394856 -0.0209257 -2.64516e-5 -6.84704e-5 1 -1.99862e-5 -6.19192e-5 1 -2.55315e-7 0 1 0 0 1 -5.80194e-7 0 1 1.1054e-5 -3.56445e-6 1 -2.35385e-7 0 1 6.85701e-5 -6.60493e-4 0.9999998 -4.78679e-7 0 1 9.41609e-7 0 1 0.7483982 0.09157592 0.6568974 0.7073249 0.1166441 0.6971985 0.6302054 -0.3465342 0.6948059 -0.5070754 -0.1752678 0.8438933 -0.4783919 -0.03352421 0.8775063 -0.4997272 -0.3042479 0.8109908 -0.2417681 -0.6643033 0.7072831 0.5444282 -0.444473 0.7113661 0.5513715 -0.4728372 0.6873242 0.3420161 0.9396942 -1.02596e-5 -0.7742839 -0.6325909 -0.0176962 -0.5021587 -0.8647537 -0.006149947 -0.9836428 0.1779547 -0.02791094 -0.9827422 0.182734 -0.02874326 0.181087 -0.9833043 -0.01789265 0.7845259 -0.619205 -0.03323137 0.8364005 -0.5474138 -0.02779287 0.514007 -0.8573603 -0.02702182 -0.6866293 -0.7260528 0.03725051 -0.5616654 -0.8271915 -0.01692116 0.2964411 -0.9548436 -0.01990908 0.9542183 -0.298448 -0.01990759 -0.8883911 0.4576234 -0.03663611 5.06546e-4 1.62061e-4 -0.9999999 -0.001275181 -0.009822785 -0.999951 0.003062605 0.02191126 -0.9997553 4.30094e-4 -2.22462e-4 -0.9999999 5.80016e-5 -1.82022e-4 -1 0.009939849 -0.003108561 -0.9999458 0.02443468 0.01507347 -0.9995878 0.005101978 0.01377171 -0.9998922 1.58773e-4 -3.41027e-4 -1 -0.5613728 -0.8267518 -0.0366339 0.411278 0.9112927 -0.01990795 -0.8888597 0.4578671 -0.01692199 -0.2703245 -0.9611173 0.05637592 0.9595012 -0.2803016 -0.02808243 0.87579 0.4813003 0.03663456 0.3939079 0.9187209 -0.02808094 -0.01484608 -0.004774093 -0.9998784 0.008544862 -0.003086864 -0.9999588 0.005980014 0.02656656 -0.9996293 -0.01337522 0.008721649 -0.9998725 4.27735e-4 -2.22459e-4 -0.9999999 0.008726716 -0.00383377 -0.9999547 1.54647e-4 -3.4103e-4 -1 0.02856671 0.9993904 0.02007526 -0.1603907 -0.986626 -0.02904945 -0.9984826 0.04252177 0.03499323 0.9975893 0.06934756 0.002561271 -0.2887895 -0.9569807 0.02808445 -0.9108805 -0.4088015 -0.05637574 -0.06686747 -0.1652206 0.9839873 -0.4764645 0.8789225 0.02184194 0.9945189 0.08805662 0.05637532 0.6374183 -0.7684529 0.05637508 -0.9133673 -0.4067099 -0.0186342 -0.5613701 -0.8267536 -0.03663712 0.1168884 -0.09990286 0.9881076 -0.254486 -0.03331464 0.9665025 0.264245 0.02339613 0.9641719 -0.07172989 -0.255029 0.9642693 -0.4764532 0.8789285 0.02184188 -0.01342159 0.9999099 0 0.2075769 -0.9780161 0.01990896 -0.6866317 -0.7260507 0.03724724 -0.9866936 0.1525045 0.0563758 -0.8883925 0.4576208 -0.03663474 0.4364736 0.8994181 -0.02319228 -0.5616656 -0.8271913 -0.01692116 -0.9514195 -0.3059028 -0.03499269 -0.005732893 0.00911206 0.9999421 0.005886733 0.004474461 0.9999727 0.05633372 -2.53681e-4 0.9984121 -0.009619414 -0.01111322 0.9998921 -0.01364099 0.003204941 0.9999019 0.004112362 -0.01937538 0.9998039 -0.0110045 -0.01163625 0.9998719 0.03245753 0.9978818 0.05637818 0.921527 -0.3842003 0.05637383 0.3471989 0.9370757 -0.03663522 0.8150992 0.5789097 0.02184188 0.9969804 0.06932199 -0.03499376 -0.6165611 -0.7852861 -0.05637556 -0.9965245 0.06132525 -0.05637592 -2.30688e-4 -4.63325e-4 0.9999999 0.05633628 -2.51975e-4 0.9984118 -0.005742192 -0.00661236 0.9999617 -7.87202e-4 -5.06321e-4 0.9999996 0.009618341 -0.004010021 0.9999457 -0.006171226 -0.0172643 0.999832 5.79354e-4 1.9845e-4 0.9999998 0.5151839 -0.5450846 0.661414 -0.2489997 0.2325471 0.9401708 -0.6091305 0.793069 -0.001351773 -0.4354398 0.900005 -0.01958006 -0.5597151 -0.8284488 -0.01979321 0.5671236 0.8234416 -0.01774311 0.3795947 0.925152 0.001348912 0.9397427 0.3417485 -0.009576201 0.9735959 -0.2281253 0.008361876 0.4249577 -0.9051665 0.009210348 -0.5840308 -0.8114939 0.01964175 0.7909092 -0.611889 -0.007387816 -0.38001 -0.9249813 -0.001450657 -0.9913887 -0.1309454 0.001358628 -0.4101393 0.9118131 0.01956212 -0.5712115 -0.8205335 -0.02102702 0.567112 0.8234497 -0.01774233 0.5308403 0.8473125 0.01643824 0.9397389 0.3417589 -0.009576976 0.9927608 0.1200076 0.004905521 -0.9537315 0.3006564 -0.001349627 0.7908962 -0.6119058 -0.00738734 -0.3800135 -0.9249799 -0.001451194 -0.7362949 -0.6766595 -0.001351177 -0.820837 -0.5700518 0.03560394 0.9417685 -0.3344826 0.03454625 0.7286809 -0.6828355 0.05253487 -0.9392567 0.3418629 0.03043985 -0.9417126 0.3346406 0.03454011 -0.6926128 0.7192338 0.05468386 -0.8305019 -0.5556049 0.03962159 -0.9345487 -0.3518809 0.05290198 -0.9392548 0.3418686 0.03043818 -0.9416959 0.3346907 0.0345112 -0.8268525 -0.5610871 0.03868466 -0.9380226 -0.3425358 0.05275279 0.8161384 0.576643 0.03742992 0.9983725 -0.02906072 0.04907166 0.9417888 -0.3344261 0.03454285 -0.2398474 0.9699368 0.04118281 -0.2474225 0.9678803 0.04461026 0.9458426 0.313201 0.08536463 0.825442 0.5631982 0.03812557 0.9418753 -0.3341304 0.03504014 0.8227527 0.5673168 0.03506797 0.9983888 -0.02903264 0.04875367 0.9392606 -0.3418712 0.03022831 0.9417386 -0.334572 0.03449898 0.783404 -0.619369 0.05157709 -0.0872597 -0.9933487 0.07512843 -0.3362067 -0.9404176 0.05079293 0.6911508 -0.720278 0.0592463 -0.8096319 -0.5856969 0.03814905 -0.8149718 -0.5778156 0.0441612 -0.2193586 0.9748728 0.03879404 -0.1853621 0.9819891 0.0365861 -0.2354537 0.9706537 0.04891878 0.9391171 -0.3418211 0.03489464 0.2779063 -0.9598995 0.0368933 0.8257877 0.5615559 0.05224722 0.9297992 -0.3655583 0.04290217 0.2033187 -0.9784274 0.03662502 0.92728 -0.3726584 0.03574347 0.9232458 -0.3817738 0.04319894 0.2445163 -0.9686324 0.0443058 0.9643163 -0.2590813 0.05450779 0.929925 -0.3671205 0.0214951 -0.2750991 0.9609443 0.03011083 0.9365172 -0.3493697 0.02960586 0.9412761 -0.3353085 0.03959155 -0.2110142 0.9764285 0.04539251 -0.2524974 0.9671695 0.02877837 -0.2249076 0.9738013 0.03358 -0.2103452 0.9769361 0.03675609 -0.241757 0.9692403 0.04611814 0.942693 -0.3319039 0.03420025 -0.312485 -0.9490352 0.0410555 0.689514 -0.7199999 0.07855379 -0.8155496 -0.5759887 0.05582123 -0.9506478 -0.2985701 0.08440929 -0.7965062 -0.6014396 0.06203418 -0.9393751 0.3419042 0.02600038 -0.9426906 0.3319118 0.03419232 -0.578355 0.8130564 0.06667155 0.7565921 0.6529247 0.03546452 0.808331 0.5861598 0.05493593 0.1817128 0.9825919 0.03864932 -0.3048296 0.9518337 0.03303909 0.953929 -0.2970692 0.0420649 0.9557257 -0.2920037 0.03636395 -0.1563906 -0.1905132 0.9691475 -0.561046 -0.02383267 0.8274415 -0.167508 0.09246242 0.9815253 -0.460044 0.3949673 0.7952109 0.7418409 -0.2278539 0.6306779 -0.6720694 0.2379845 0.7012033 -0.9392754 0.3418114 0.03044253 0.1055189 -0.9930003 -0.05306828 -0.1734082 -0.02847892 0.9844383 -0.9401122 -0.3285052 0.09095835 -0.6714981 0.2368271 0.702142 -0.6240279 0.2294149 0.746966 -0.0867027 -0.9140747 0.3961694 0.1190479 -0.9651389 -0.233098 -0.3852575 0.1524016 0.9101377 0.7748851 -0.2564235 0.5777546 0.7324156 -0.2518207 0.6325772 -0.02001959 0.9584049 0.2847092 -0.3204075 0.9466508 0.03451687 0.2078779 0.2878862 0.9348306 -0.4399334 -0.6394371 0.6305386 0.1290454 -0.02301424 0.9913716 0.6347518 0.7285401 0.2575259 -0.500162 0.1813612 0.8467267 -0.6977002 0.2254574 0.6799879 -0.05178642 -0.3778759 0.9244069 -0.6347182 0.2322438 0.7370181 0.4704477 -0.1701768 0.8658631 0.2300323 -0.100974 0.9679304 -0.04881048 -0.01250606 0.9987298 0.1365535 0.04639714 0.9895456 0.07007342 0.9214496 0.3821262 -0.008058726 -0.6539064 0.7565326 0.7776434 0.3208159 0.5406921 0.5501142 -0.1336079 0.8243321 0.2478195 0.9650454 -0.08528178 -0.288596 0.110747 0.9510245 0.6979294 0.03905993 0.7151007 0.2801762 -0.958878 0.04532456 -0.03689771 0.2238712 0.9739201 -0.05977487 0.05056959 0.9969302 0.6111073 -0.3194071 0.7242423 -0.8106217 -0.5837978 0.0455262 0.5275371 -0.8452114 0.08557075 0.2897312 -0.9551986 0.06042844 0.6681473 -0.2368832 0.7053124 -0.06200295 -0.372349 0.9260194 0.2641993 -0.5553032 0.7885665 0.239581 -0.04881435 0.9696485 0.4293546 -0.4936085 0.7563105 0.04958343 0.9005376 0.4319417 -0.1020678 0.07419967 0.9920064 0.5035904 -0.181568 0.8446478 0.6650062 -0.2127995 0.7158793 0.8812008 0.205014 0.4259748 0.1651402 0.1584453 0.9734597 -0.4659013 0.1689156 0.8685641 -0.04947245 -0.9566874 0.2868828 -0.2946971 0.9536303 0.0611788 0.3610417 -0.6425588 0.6758456 -0.6638518 0.2350496 0.7099665 -0.6344881 0.2309169 0.737633 0.3139174 0.324292 0.8923512 -0.6930935 -0.6936441 0.1961612 0.03685748 0.1697234 0.9848024 -0.4590705 0.1670882 0.8725457 -0.08500218 -0.1556395 0.9841499 0.166804 -0.08694976 0.9821488 0.187816 -0.09907317 0.9771949 0.7784012 0.6270032 0.03096187 -0.5312913 0.8428742 0.0853976 0.3386084 -0.6213033 0.7066305 -0.6693886 0.2378301 0.7038152 0.5190417 -0.2618626 0.8136485 0.1826077 0.9180271 0.351967 -0.3428931 0.6078641 0.7161883 0.2914363 0.1382039 0.9465541 -0.4632378 0.1674171 0.8702772 -0.1838818 -0.7665869 0.6152497 -0.6082978 0.1785465 0.773366 -0.05958664 -0.7992947 0.5979778 0.07434707 -0.008001446 0.9972004 0.6969525 -0.3678323 0.6155946 0.5110391 0.7064636 0.489641 0.7975367 0.6024045 0.0323112 -0.59482 0.8004997 0.07341289 -0.03422236 -0.9957482 -0.08552515 -0.5993682 0.4514431 0.6610272 -0.3830393 0.6095237 0.6940906 -0.6245644 0.2309106 0.7460561 -0.6353299 0.2322514 0.7364886 0.6617471 -0.2408483 0.7099879 0.6521125 -0.2394137 0.7193264 -0.155225 -0.2850768 0.9458523 0.8406446 0.1448569 0.5218555 0.8182492 0.1290615 0.5601886 -0.7695705 0.2771649 0.5752746 0.6021801 -0.1765307 0.7785989 -0.7758155 -0.5700712 0.2704244 0.5938851 -0.2980991 0.7472868 -0.01398599 -0.08514052 0.9962709 0.4659482 -0.1690325 0.8685162 0.4594893 -0.1672038 0.8723031 0.03849977 0.9625338 0.2684149 -0.7551814 0.2657641 0.599225 0.5299133 -0.2135037 0.8207363 -0.7698957 0.2669762 0.5796415 0.1181249 -0.8039705 0.5828189 -0.7958895 -0.6036556 0.04647421 0.5807137 0.2467907 0.7758003 0.6697112 -0.2363407 0.70401 0.6426402 -0.2326062 0.7300055 0.5473556 0.2536778 0.7975271 -0.7605815 0.2555571 0.5968302 -0.7851018 0.2734906 0.5557141 0.3956985 -0.1417253 0.9073791 -0.5693746 -0.7668296 0.2962856 0.3373409 -0.9408029 0.03303277 0.2741573 -0.9605913 0.045852 -0.1812304 -0.07561439 0.9805295 0.4681597 -0.1708521 0.8669694 0.4739931 -0.1724811 0.8634702 0.4792789 0.02695089 0.8772488 0.4664039 0.4694132 0.7497458 -0.09772688 0.02132409 0.9949849 -0.2083168 0.04015982 0.9772366 0.09295636 -0.6050375 0.7907521 -0.555714 -0.6283326 0.5444083 -0.7846952 -0.6188098 0.03643989 -0.8050347 -0.5914727 0.04560029 0.01984888 -0.715128 0.6987117 0.02637147 -0.6037834 0.7967122 -0.2535104 -0.6573179 0.709694 0.5739725 -0.8161405 0.06686013 0.4585663 -0.8870282 0.05383402 0.5478004 -0.163719 0.8204334 -0.8343158 0.427535 -0.3480388 0.1784642 -0.09570032 0.9792814 -0.7706412 0.2190689 0.5984322 -0.9553925 0.1133129 -0.2727369 0.482818 -0.2517777 0.838746 0.6089732 -0.2049669 0.7662507 -0.5415659 0.1970722 0.8172324 -0.3639917 -0.4823895 0.79675 0.7111296 -0.3655971 0.6005278 0.8134242 0.5801775 0.04165428 0.8150411 0.5777492 0.04374837 0.6855006 -0.7182837 0.1189857 0.7575692 -0.5366584 -0.3716002 0.2016173 0.5895264 0.7821823 -0.5240525 -0.6556663 0.5435723 0.3115342 -0.7318553 0.6060811 0.7504986 -0.2731572 0.6017783 0.8467205 -0.0864374 -0.5249697 0.7749867 0.23478 0.5867488 0.9392801 -0.3413335 0.03527861 0.5795908 0.2287825 0.7821336 0.7928153 -0.006696701 0.6094253 0.6084145 -0.5561255 0.566177 0.6519353 -0.2323078 0.7218127 -0.06235879 -0.368695 0.9274564 0.2796178 -0.9594375 0.03596591 -0.5483516 -0.4585197 0.6993356 -0.6624318 0.2348798 0.7113477 -0.6442815 0.2329635 0.7284432 -0.136361 0.6647818 0.7344868 0.1747549 0.4798632 0.8597629 0.2174404 0.6599268 0.7191775 0.5826377 0.4696153 0.663321 0.5607834 0.4324653 0.7060424 0.6618881 -0.2352362 0.711736 0.6526476 -0.2342801 0.7205304 0.1492197 -0.6814395 0.7165011 -0.1247617 -0.5605821 -0.8186466 -0.1993447 -0.5987978 0.7756951 -0.6007241 -0.461597 0.6527318 -0.5343189 -0.4452083 0.7185353 -0.181927 0.6705039 0.7192546 -0.2058116 0.6957271 0.68819 0.220317 0.6497374 0.7275313 0.6374685 0.5002987 0.5859482 0.517095 0.4601337 0.7217269 0.6579418 -0.2336185 0.7159156 0.6379024 -0.2315611 0.7344794 0.1913242 -0.6767207 0.710946 -0.3028616 -0.799357 0.5189444 0.001253366 -0.002902746 0.9999951 -0.6001183 -0.4626137 0.6525693 -0.5510548 -0.4508662 0.7021812 -0.6584195 0.2342298 0.7152764 -0.6450137 0.2328756 0.7278231 -0.1823061 0.698728 0.6917685 0.2230049 0.649104 0.7272776 0.6365148 0.4995855 0.5875912 0.6579329 -0.2336171 0.7159242 -0.2573341 -0.679269 0.6872938 -0.04419422 -0.2315168 0.9718266 -0.2755635 -0.09041976 0.957021 -0.657615 0.234093 0.7160608 -0.1965693 0.6735643 0.712511 0.2550689 0.7211993 0.6440586 -0.233139 -0.6333613 0.7379022 -0.5344754 -0.4081649 0.7400929 -0.6497173 0.2330474 0.723572 -0.2155304 0.7529906 0.621733 0.2429589 0.6862897 0.685549 0.529057 0.4497535 0.7195975 0.1910279 -0.6768755 0.7108784 -0.5806922 -0.4034046 0.7071501 -0.5903943 -0.4198873 0.6892963 -0.6530138 0.2330229 0.7206062 -0.6426283 0.2319166 0.7302353 0.6576204 -0.23409 0.7160568 -0.1756954 -0.4883826 0.8547593 -0.2165955 -0.6602472 0.7191385 -0.6466643 0.2330303 0.7263072 -0.1950901 0.6744939 0.7120379 0.551519 0.4497013 0.7025635 0.6450144 -0.2328191 0.7278404 0.1956743 -0.6740986 0.712252 0.2746605 0.7995892 0.5340589 0.5968532 0.4600811 0.6573367 0.5515041 0.4496908 0.702582 0.15962 -0.630205 0.7598442 0.1956977 -0.6740978 0.7122462 -0.2538766 -0.7113659 0.6553665 -0.2136819 -0.5513384 0.8064528 -0.5807228 -0.4033894 0.7071338 -0.5781297 -0.3990505 0.7117055 -0.6425456 0.2323155 0.7301813 0.2550608 0.7211848 0.644078 0.5669434 0.4566995 0.6855661 0.6602657 -0.2347729 0.713394 0.6506778 -0.2337761 0.722473 0.2114143 -0.7995167 0.5622074 0.1240572 -0.6724975 0.729628 -0.6128017 -0.4723853 0.6335033 -0.5475196 -0.4557715 0.7017797 -0.6576491 0.2341033 0.716026 -0.6454508 0.2328725 0.7274363 -0.1965526 0.6735873 0.7124936 0.220066 0.6493868 0.7279202 0.2549806 0.7211602 0.6441373 0.6042656 0.4763739 0.6386948 0.657575 -0.2341293 0.7160857 0.6452478 -0.2328834 0.7276129 -0.2145226 -0.5531134 0.8050129 -0.5807037 -0.403428 0.7071273 -0.5780614 -0.3990265 0.7117745 -0.1142573 0.6537925 0.7479978 0.1774851 0.4871756 0.8550784 0.6550377 0.5040404 0.5629113 0.6388112 -0.2316631 0.7336569 -0.5306872 -0.5000422 0.6843457 -0.6576378 0.2340897 0.716041 -0.1965773 0.6735588 0.7125139 0.2550599 0.7211741 0.6440903 0.5588546 0.4431293 0.7009409 0.6443903 -0.2331511 0.7282869 0.6506674 -0.2338146 0.7224699 -0.9378795 0.3398402 0.06993412 0.7861499 0.6151977 0.05916255 -0.7890931 -0.6113625 0.05973362 0.9259691 -0.3739419 0.05242872 0.5883703 0.8064143 0.05930012 0.811091 0.5738843 0.1130861 0.9155821 -0.3993853 0.04691439 -0.7682788 -0.6376326 0.05632609 -0.3420195 -0.9396929 5.38921e-6 -0.2501922 0.9672586 0.04259842 0.6861566 0.7227203 0.08285242 0.7725247 0.6319871 0.06162822 0.9350169 -0.3509021 0.05110007 -0.7550241 -0.6492287 0.09187418 0.2886321 0.9563017 0.04667431 -0.451123 0.8837215 0.1245973 -0.9207285 0.3875039 0.04582494 0.9436748 0.318185 0.09075462 0.7729504 0.6318978 0.05703437 0.9387111 -0.3416702 0.04564082 -0.1813686 0.9827575 0.0359621 -0.2247802 0.9732958 0.04657721 -0.9306567 0.3630958 0.04516178 0.9387169 -0.3416522 0.04565745 -0.4155547 0.9003094 0.12945 -0.9387137 0.3416632 0.0456385 0.2258588 -0.9726829 0.05362647 -0.8143318 -0.5790114 0.04011923 -0.9391201 0.3418107 0.03491395 -0.9431726 0.329261 0.0448628 -0.234035 0.9708246 0.05222469 -0.1724926 0.9840537 0.04341268 -0.9828164 0.1733024 0.06354719 -0.9746624 -0.2166159 -0.05577415 0.4679768 -0.878239 -0.09845757 0.9151826 -0.399765 -0.05127346 0.1442903 0.9879511 -0.05597364 -0.8477065 0.5241624 -0.08153247 -0.6068929 0.7917109 0.06982082 -0.02652788 0.9964766 0.07956647 0.8658249 -0.499844 0.02243381 0.2761461 0.2969222 0.914101 0.7876203 0.1902785 0.5860447 0.3137944 -0.2856964 0.9054893 -0.3364154 -0.04470402 0.9406521 -0.3486456 0.07889676 0.933928 -0.3342139 0.3113558 0.8895835 0.4026975 0.2096532 0.8909997 0.87426 -0.07771837 0.4791967 0.6233188 -0.05998253 0.779664 0.3455447 -0.3533282 0.8693435 0.2701979 -0.4215949 0.8655928 -0.2595017 -0.5573977 0.7886487 -0.2910783 -0.6008274 0.7444998 -0.4059988 -0.1258987 0.90516 -0.3018811 -0.5622875 0.7698706 -0.2858258 0.8786689 0.3824195 2.51149e-7 -1.89527e-7 -1 -1.76585e-7 1.67548e-6 -1 3.58768e-6 2.12859e-6 -1 -0.5458077 0.8245545 0.1490098 0.3988484 0.3010901 0.8661783 -0.5715008 -0.2069708 0.7940718 0.2553071 0.966068 0.03912633 0.245126 0.9689352 0.03282999 -0.3021245 0.009114027 0.953225 0.5030835 0.177908 0.8457279 0.8203207 -0.5642316 0.093364 0.6256 -0.7782677 0.05407398 0.02240991 0.003711342 0.999742 0.1381135 0.9859797 0.09364157 -0.7998974 0.5988564 0.03918093 -0.4642831 -0.1476239 -0.8732975 -0.4496583 -0.1841397 -0.8740137 -0.4444475 -0.1989421 -0.8734349 -0.459158 -0.2081416 -0.8636268 -0.4565488 -0.2081462 -0.8650077 -0.4568461 -0.1460977 -0.8774663 -0.4996783 -0.1678479 -0.8497934 -0.4863062 -0.1651901 -0.8580318 -0.4637965 -0.153779 -0.8724936 -0.4681244 -0.1543988 -0.8700693 -0.1281326 -0.04416429 -0.9907732 -0.4689677 -0.1660125 -0.8674729 -0.130152 -0.04610133 -0.9904217 -0.4737142 -0.1774728 -0.8626113 -0.1259454 -0.05087321 -0.990732 -0.4816389 -0.1925501 -0.8549552 -0.1180216 -0.05287754 -0.9916023 -0.4795249 -0.1969493 -0.8551415 -0.4633665 -0.1877635 -0.8660464 -0.4688438 -0.1791231 -0.8649281 -0.4646633 -0.1984012 -0.8629746 -0.4500536 -0.1887583 -0.8728241 -0.4697355 -0.2054785 -0.8585612 -0.4163502 -0.1911128 -0.8888916 -0.457316 -0.2043447 -0.8655088 -0.4623143 -0.2022968 -0.8633317 -0.4672815 -0.2003719 -0.8611035 -0.4614032 -0.1803116 -0.8686742 -0.4697752 -0.1782436 -0.8646042 -0.46731 -0.1739744 -0.8668069 -0.4800543 -0.1525477 -0.8638734 6.37296e-4 -0.004416167 -0.9999901 0.01890546 0.01424926 -0.9997198 1.21525e-4 7.5607e-5 -1 -0.01230835 0.005605936 -0.9999086 -0.01865148 -0.004402697 -0.9998164 0.004363358 0.001582384 -0.9999893 -0.04703116 0.002407312 -0.9988905 0.001242697 4.98131e-4 -0.9999991 -0.08757114 -0.04403614 -0.9951845 0.007346212 0.002409756 -0.9999702 -1.202e-7 0 -1 -0.05358481 -0.02851402 -0.9981562 1.72163e-4 -1.48121e-4 -1 -0.06171798 -0.01234954 -0.9980173 -5.89586e-4 4.24469e-4 -0.9999998 -1.45257e-7 0 -1 3.02596e-7 0 -1 -1.80324e-7 0 -1 -0.1092132 -0.03462439 -0.9934152 3.60626e-7 0 -1 7.59712e-4 2.72943e-4 -0.9999998 -1.82035e-4 1.06e-4 -1 -0.008830964 -0.01250135 -0.9998829 1.80312e-7 0 -1 -1.51306e-7 3.34892e-7 -1 -7.65181e-6 -4.07598e-6 -1 4.53887e-7 0 -1 -0.0205518 0.007783532 -0.9997585 0.9396926 0.3420203 5.42535e-5 -0.2205862 0.6032204 -0.7664639 -0.2100929 0.6023807 -0.7700639 0.6541524 0.2276014 0.721306 0.7887023 0.2985337 0.5374256 0.2444447 0.8223732 0.51376 -0.3272991 -0.09388345 0.9402453 -0.510438 -0.1285524 0.8502513 0.2932842 -0.9238216 0.246045 0.4597335 0.1263093 0.8790285 0.1786061 -0.5335067 0.8267229 0.2412008 -0.6674419 0.7045165 -0.5987884 0.3072858 0.7396134 -0.3694041 0.2968228 0.8805889 -0.2391408 0.6699433 0.7028425 0.08944571 0.4995313 0.8616658 -0.8159161 0.5769661 0.03730088 -0.3533031 0.9340206 0.05274856 0.006686747 0.002369761 0.9999749 -0.5730255 0.3680242 0.7322568 -0.3223605 0.2577651 0.9108463 -0.670364 -0.2547929 0.6969166 0.159596 -0.6289357 0.7609003 -0.9407767 -0.337974 0.02670103 -0.9396753 -0.341529 0.01919156 -0.8132832 0.5805797 0.03870016 -0.8267681 0.5625371 0.002554774 1.73149e-5 -6.7804e-4 0.9999998 8.18658e-4 1.9111e-4 0.9999997 -0.8609136 -0.04512763 0.5067458 -0.8318991 -0.2836149 0.4769765 -0.6652162 -0.2489578 0.7039229 0.8039304 0.2415156 0.5434762 -0.2734783 -0.9612346 0.03518366 -0.2680454 -0.9626852 0.03726798 -0.9366242 -0.3489387 0.03125786 -0.9395799 -0.3402107 0.03803139 -0.9581305 0.2828204 0.04470586 0.8116094 0.239241 0.5329672 0.8096249 0.2684884 0.5219402 0.5298736 -0.1863281 0.8273547 -0.7504143 -0.3342459 0.5702264 0.1889045 0.7650965 0.6155831 0.9405288 0.3377189 0.03676527 0.03553694 0.006425738 0.9993478 -0.01975888 0.3515849 -0.9359475 -0.001284658 4.93756e-4 -0.9999991 0.7198387 -0.693865 -0.01959133 -0.8187194 0.5731316 0.0349121 -0.8183546 0.5736664 0.03468257 -0.2912501 0.9518567 0.09561562 0.3720292 0.926169 0.06168836 -0.2151154 0.5876984 -0.779959 -0.007783889 0.00442624 -0.99996 -0.9172158 -0.3970084 0.03315794 -0.9661695 0.2291334 0.1183832 -0.2162107 0.9730296 0.08041548 -0.4756515 0.876174 0.07794219 -0.4946916 -0.8665857 0.06564807 -0.1979833 0.3433518 -0.9181026 -0.03719329 0.01831328 -0.9991403 0.01335823 0.02975052 -0.9994682 -0.1968843 0.585175 -0.7866428 -0.222539 0.5990654 -0.7691536 -0.6771402 -0.7042297 0.2134051 0.8859346 -0.463569 -0.01496195 0.8047356 -0.5738606 -0.1519371 -0.9145097 0.4033731 -0.0310235 0.7254611 0.6715459 0.1507727 0.1068158 -0.9942581 -0.006437242 -0.8894234 -0.4553596 -0.0396707 -0.855058 0.5139102 -0.06908023 0.9707629 -0.229932 -0.06892699 0.6640305 0.7172604 0.2111895 0.4220489 0.9063184 -0.02149003 0.3843584 0.9231801 0.00266242 -0.5669113 -0.7364323 0.36916 -0.9061262 0.4230068 9.48154e-4 -0.9389284 -0.3414044 -0.04308891 -0.9387972 -0.3416962 -0.04362893 -0.9387966 -0.3417001 -0.04361343 -0.9388123 -0.3416529 -0.04364371 0.9387056 0.34192 -0.04384672 0.9388117 0.3416618 -0.04358881 0.9387984 0.341694 -0.04362064 0.9387788 0.3417633 -0.0435009 7.77267e-6 0 -1 0 0 -1 1.93196e-6 0 -1 0.6606417 -0.6696552 -0.3392854 0.3185145 -0.8750949 -0.364359 0.3184874 -0.8751081 -0.3643511 2.43423e-4 -1.17173e-4 -1 2.23017e-6 0 -1 1.36614e-6 0 -1 -1.58029e-6 0 -1 1.3797e-6 0 -1 1.16652e-6 0 -1 -0.9396929 -0.3420194 0 0.08279877 -0.9950536 -0.05488926 0.05103349 -0.5319697 -0.8452242 0.6301675 -0.7761462 -0.02204376 0.005784928 -0.9507695 -0.3098453 0.9396927 0.3420201 -7.62206e-7 0.9398379 0.3416209 -8.54945e-5 0 0 -1 1.59165e-7 0 -1 0.3418547 -0.9397528 -4.09178e-4 0.34202 -0.9396927 0 -0.9803981 0.1916201 -0.04584139 -0.7762255 -0.6302264 0.0169993 -0.03883934 -0.9990356 -0.02048176 0.0271793 -0.9996306 0 -0.2883056 -0.7101933 -0.6422659 -0.9952847 0.09695976 0.002674281 -0.5735691 0.8191539 -0.002331376 -0.9961872 -0.08715021 -0.004001557 0.2837917 -0.7317312 -0.619703 -0.2696579 0.755278 -0.5973607 -0.3262657 0.9019326 -0.2829635 -0.3420216 0.9396922 0 -0.3420137 0.939695 1.91118e-7 -0.34202 0.9396927 -2.48817e-6 -0.1169098 0.4012262 -0.9084877 -0.08852112 0.243209 -0.9659262 -0.320303 0.9337098 -0.1599755 -0.1371589 0.2488703 -0.9587758 0.9396921 0.3420215 0 0.9396923 0.342021 1.10968e-6 0.9396936 0.3420178 2.21807e-6 0.9396922 0.3420214 1.12353e-5 0.6313042 0.7755354 0 0.6557315 -0.3682352 0.6591048 0.3412815 -0.9390286 0.04186213 -0.5152876 -0.2613693 0.8161892 -0.5126374 -0.2641146 0.8169739 -0.5148043 -0.2588187 0.8173062 -0.3541057 -0.1418729 0.9243816 -0.4387944 -0.1070536 0.8921878 -0.3022737 -0.124174 0.9450987 -0.5882987 -0.3057503 0.748613 -0.5463661 -0.1989833 0.8135662 -0.5538693 -0.2588116 0.7913568 -0.54055 -0.1967898 0.8179728 -0.4084394 -0.1524077 0.8999719 -0.4481399 -0.1576756 0.8799483 -0.4559909 -0.1544435 0.8764814 -0.539166 -0.1962416 0.8190174 -0.616727 -0.1643955 0.7698194 -0.5380315 -0.1958841 0.8198485 -0.5390017 -0.1961795 0.8191403 -0.5376973 -0.1954911 0.8201615 -0.5454885 -0.19866 0.8142338 -0.5067614 -0.1802403 0.843034 -0.4374932 -0.3442557 0.8307152 -0.5522286 -0.2590539 0.7924233 -0.5439873 -0.1988087 0.8152013 -0.6610198 -0.1802241 0.7284039 -0.4516021 -0.1843057 0.872976 -0.5466169 -0.2752429 0.7908548 -0.4397774 -0.221214 0.8704369 -0.2163727 -0.8279562 0.5173698 -0.9915827 -0.02735203 -0.1265526 -0.9961081 0.0168659 -0.0865119 0.9436915 0.330731 0.007961273 0.9374164 0.3458037 0.04087048 0.3226969 -0.945348 0.04673129 -0.8061577 0.2447037 0.53873 -0.7673355 0.2566342 0.5876522 -0.4834564 0.7985158 0.3586677 0.3592935 0.1925793 0.9131382 -0.4220054 -0.1327021 0.8968287 -0.6521585 -0.2500374 0.715661 -0.4460881 -0.8927289 -0.06356626 0.05784493 0.008238196 0.9982916 -1.27125e-7 0 1 -5.35391e-7 2.7266e-6 1 3.48696e-4 8.17237e-5 1 -0.003671467 -0.001421093 0.9999923 -0.003622114 -0.001394152 0.9999925 -0.007359802 -0.002872824 0.9999688 3.38468e-4 1.3016e-4 1 0.01058834 0.013929 0.9998469 0.003338813 0.00124228 0.9999937 -3.96885e-4 0.001106262 0.9999994 -3.17571e-4 1.54341e-4 1 -3.38736e-4 -3.69371e-4 1 0.003588259 0.001375496 0.9999926 0.002590358 6.74516e-4 0.9999965 0.003586113 0.001375615 0.9999926 -0.1596463 -0.07806986 0.9840825 0.001136183 1.84296e-4 0.9999994 0.001652479 5.93411e-4 0.9999985 3.50148e-4 1.22255e-4 1 6.5382e-5 -2.56281e-4 1 0.001247644 3.3396e-4 0.9999992 5.6345e-4 1.93049e-4 0.9999998 3.43426e-4 1.13495e-4 1 0.002293825 0.00141412 0.9999964 0.001439392 8.04486e-4 0.9999987 0.002453744 8.70383e-4 0.9999967 3.17402e-4 9.98098e-5 1 -0.09786176 0.1358854 0.9858794 5.46462e-4 1.66663e-4 0.9999999 -0.01480066 -0.005240261 0.9998768 -0.01940548 -0.0101 0.9997608 0.1026153 0.003566622 0.9947148 6.07207e-4 2.34953e-4 0.9999999 0.1028591 0.1365179 0.9852832 -0.07558947 0.1331709 0.9882064 -0.002751469 -0.001289486 0.9999954 -2.87456e-4 -4.0625e-4 0.9999999 0.02451014 0.02305459 0.9994338 0.07339441 -0.02669388 0.9969457 -8.26485e-4 -1.47886e-4 0.9999997 -0.001935601 -8.87936e-4 0.9999978 0.1006441 0.07721543 0.9919217 0.1819579 0.02955698 0.982862 -0.003163993 -0.001163303 0.9999944 -0.002274274 -0.001063525 0.9999969 4.61468e-4 -8.28881e-5 0.9999999 0.1747341 -0.00200659 0.9846136 -0.001085698 -1.45498e-4 0.9999995 0.07535064 0.02983713 0.9967107 0.3845357 0.2414525 0.890973 8.51597e-5 -2.52122e-4 1 2.04576e-4 -2.15715e-5 1 0.007016241 -0.01901036 0.9997947 0.003448784 3.1415e-4 0.9999941 -5.98846e-4 1.17322e-4 0.9999999 0.1169067 0.1371814 0.983623 -7.69651e-4 -6.27885e-4 0.9999995 -0.004881381 -0.001494646 0.999987 3.08907e-4 -5.12834e-5 1 -1.06193e-4 -2.11642e-5 1 0.2107307 0.02436977 0.9772405 0.06869924 0.04603499 0.9965748 -6.9249e-4 -3.62973e-4 0.9999998 0.009888887 0.007976353 0.9999194 0.01014703 -0.008257508 0.9999145 0.03610008 0.01349091 0.9992572 8.0684e-5 8.80313e-4 0.9999997 -0.003481268 -0.001188397 0.9999933 -2.62749e-4 6.51078e-4 0.9999998 0.03659534 0.01340097 0.9992403 0.003295958 0.001183271 0.9999939 8.19846e-4 0.001362025 0.9999988 1.08722e-4 3.22608e-4 1 2.27133e-4 7.7098e-5 1 9.80209e-5 -3.95733e-4 1 -0.01141917 -0.01922935 0.9997499 6.82878e-5 1.08047e-4 1 0.002168297 -4.17234e-4 0.9999976 2.15388e-4 8.19251e-5 1 4.63788e-4 1.71733e-4 1 0.002534687 9.59222e-4 0.9999964 8.94321e-4 0.001359999 0.9999987 -0.003011941 -7.89506e-4 0.9999952 7.49529e-4 2.78642e-4 0.9999997 -1.11436e-4 7.41285e-5 1 -2.40241e-4 -1.45058e-4 1 -1.15234e-6 8.90074e-4 0.9999997 -0.01000773 0.01596558 0.9998224 -0.7357808 0.6504661 0.1884691 0.2614483 0.9379537 0.2277883 0.9396923 0.3420212 -6.66106e-5 0.6763399 0.245272 0.6945546 0.7832804 0.2811368 0.5544673 -0.1247228 -0.04534834 0.9911548 -0.8743284 -0.3106554 0.3728848 -0.9254134 -0.338295 0.1707822 -0.3568091 -0.1348758 0.9243895 -0.9344531 -0.3432205 0.09485399 -0.9387981 -0.3416956 -0.04361724 -0.9387987 -0.3416934 -0.04361969 -0.9387999 -0.3416906 -0.04361629 -0.9387967 -0.3416988 -0.04362189 -0.9387996 -0.3416913 -0.04361778 -0.9387987 -0.3416936 -0.04361867 -0.9387965 -0.3416979 -0.04363262 -0.9388003 -0.341688 -0.04362815 -0.9387971 -0.3416985 -0.04361224 -0.9387934 -0.3417085 -0.04361444 -0.9387946 -0.3417049 -0.04361855 -0.9387959 -0.3417025 -0.04360961 0.9387992 0.3416924 -0.04361593 0.9387972 0.3416981 -0.04361516 0.9387977 0.3416965 -0.04361909 0.9387975 0.3416966 -0.04361951 0.9388009 0.3416876 -0.04361891 0.9387999 0.3416907 -0.04361557 0.9387969 0.3416982 -0.04361975 0.9387957 0.3417024 -0.04361367 0.9350675 0.3536359 -0.02429926 0.9388025 0.3416835 -0.04361552 0.9388001 0.3416895 -0.04361975 -0.9387966 -0.3416996 -0.04361879 0.9388008 0.341688 -0.04361575 0.3417142 -0.938791 -0.04362422 0.3417112 -0.9387924 -0.04361659 -0.3416838 0.9388015 -0.04363495 -0.3416896 0.9388002 -0.04361885 -0.01489502 0.04092276 -0.9990513 0.3416925 -0.9387986 -0.04362881 0.3416875 -0.9387997 -0.04364532 0.3417029 -0.9387949 -0.04362529 -4.35791e-7 0 -1 -0.3416862 0.9388016 -0.04361379 -0.3416897 0.9388006 -0.04360961 -0.3416941 0.9387981 -0.04362797 0.3416947 -0.9387984 -0.04361659 0.3445281 -0.9376289 -0.04639458 -0.3417071 0.9387936 -0.04362434 -0.3417032 0.938795 -0.04362165 -0.3416859 0.9388017 -0.04361426 -0.03249186 -0.01182556 -0.9994021 0.3416875 -0.9388006 -0.04362493 0.3416888 -0.9388008 -0.04361003 -0.3416957 0.9387995 -0.0435853 0.01803046 0.05128234 -0.9985214 -0.01489454 0.04092293 -0.9990513 0.341709 -0.9387928 -0.0436241 -4.35789e-7 0 -1 -4.35787e-7 0 -1 -0.3416843 0.9388023 -0.04361402 -0.3416942 0.9387981 -0.04362797 0.01803129 0.05128288 -0.9985215 -0.03249192 -0.01182609 -0.9994021 0.3417022 -0.9387955 -0.04362183 4.35791e-7 0 -1 -4.35788e-7 0 -1 -0.3416844 0.9388025 -0.04360884 -0.3416894 0.9388005 -0.04361468 -0.341697 0.938797 -0.04362809 0 0 -1 0.01803135 0.05128306 -0.9985214 0.3416842 -0.9388023 -0.04361402 0.3416905 -0.9387993 -0.04362851 0.3416896 -0.9388003 -0.0436142 0.3416889 -0.9388006 -0.04361599 -0.3417162 0.9387911 -0.04360353 -0.3416947 0.9387993 -0.04359745 0.01803034 0.05128222 -0.9985214 -0.0148946 0.04092282 -0.9990514 0.3416923 -0.9387993 -0.04361641 0.341692 -0.9388 -0.04360121 -0.3417116 0.9387924 -0.04361397 -0.3417 0.938796 -0.04362773 -0.3417136 0.9387897 -0.04365587 -0.3416951 0.9387977 -0.04362797 0 0 -1 0.01803052 0.05128252 -0.9985214 -0.0148949 0.04092377 -0.9990513 0.3417057 -0.9387947 -0.04361015 0.3416913 -0.9387985 -0.04364079 -0.3416887 0.9388005 -0.04361933 -0.3416896 0.9388003 -0.04361593 -0.01489478 0.04092293 -0.9990513 -0.3416923 0.9387992 -0.04361927 0.3416914 -0.9387997 -0.04361367 0.3416984 -0.9387966 -0.04362452 0.3416969 -0.9387977 -0.04361492 -0.3416938 0.9387983 -0.04362446 -0.3416939 0.9387986 -0.0436173 -0.341693 0.9387989 -0.04361939 -0.0324918 -0.01182591 -0.9994021 -0.01489478 0.04092282 -0.9990513 0.3416939 -0.9387986 -0.04361921 -0.3416938 0.9387986 -0.04362189 -0.3416947 0.9387983 -0.04361933 -0.3416917 0.9387995 -0.04361557 0.3416949 -0.9387984 -0.04361385 0.3416923 -0.9387992 -0.04361927 -0.3416975 0.9387972 -0.04361915 -0.341695 0.9387986 -0.04361122 -0.0148946 0.04092264 -0.9990513 0.3416941 -0.9387985 -0.04361945 0.3416953 -0.9387982 -0.04361641 -5.40959e-7 0 -1 0.1096346 0.01802116 -0.9938086 -0.341693 0.9387989 -0.04361921 -0.3416932 0.938799 -0.04361665 0.3416957 -0.9387979 -0.04361933 0.3416938 -0.9387986 -0.04362189 0.0324918 0.01182591 -0.9994021 -0.03249174 -0.01182585 -0.9994021 -0.03249168 -0.01182627 -0.9994021 0 0 -1 -0.8683164 -0.3160437 -0.3822869 -0.8683519 -0.3160443 -0.3822055 -0.8682887 -0.3160375 -0.3823549 -0.8683488 -0.3160478 -0.3822098 -0.8681861 -0.3160097 -0.3826106 -0.86842 -0.3160691 -0.3820301 -0.868291 -0.3160331 -0.3823531 -0.8683232 -0.3160483 -0.3822677 -0.8683117 -0.31604 -0.3823006 -0.868325 -0.3160436 -0.3822672 -0.8683117 -0.3160382 -0.3823018 -0.8683589 -0.3160627 -0.3821743 -0.8683168 -0.3160462 -0.3822836 -0.8683186 -0.3160407 -0.3822842 -0.8683183 -0.3160405 -0.3822848 0.8682813 0.3160246 -0.3823822 0.8683606 0.3160638 -0.3821694 0.8683742 0.3160704 -0.3821333 0.8682563 0.3160083 -0.3824526 0.8682839 0.316025 -0.382376 0.8684209 0.316087 -0.3820133 0.8682959 0.3160307 -0.382344 0.868318 0.3160418 -0.3822845 0.8683618 0.3160555 -0.3821738 0.8683594 0.3160514 -0.3821827 0.868263 0.3160287 -0.3824206 0.8683636 0.3160538 -0.3821713 0.8683279 0.3160429 -0.3822612 0.868326 0.3160445 -0.3822643 0.8683255 0.3160422 -0.3822672 0.8683177 0.3160431 -0.3822841 0.8683144 0.3160425 -0.3822923 0.8683209 0.3160419 -0.382278 8.21395e-5 -2.26199e-4 -1 -0.4386667 0.6935403 -0.5714661 -0.4400373 0.6922396 -0.5719892 -0.5446212 0.6125932 -0.5728153 -0.6075823 0.5546437 -0.5685192 -0.7382894 0.3483883 -0.5775418 -0.7960088 0.1898833 -0.5747298 -0.8162685 0.01130157 -0.5775621 -0.7542721 -0.3137443 -0.5767481 -0.7444561 -0.3538265 -0.5662084 -0.8178181 -0.08923202 -0.5685169 -0.5745203 -0.5851121 -0.5723376 -0.4479984 -0.6914198 -0.5667769 -0.309698 -0.7531286 -0.5804176 0.01575946 -0.8131688 -0.5818147 -0.02120548 -0.8216599 -0.5695836 0.04481631 -0.818108 -0.5733156 0.4002884 -0.7362986 -0.5455582 0.5471781 -0.6113926 -0.5716603 0.4417514 -0.6896438 -0.5738007 0.4351999 -0.6954766 -0.5717634 0.06745874 -0.8169916 -0.5726902 0.1037334 -0.816317 -0.568213 0.08638966 -0.8179324 -0.5687914 0.6488382 -0.4977859 -0.5755158 0.7940829 -0.1863573 -0.5785356 0.8211485 0.07335895 -0.5659804 0.8181033 0.05891966 -0.5720452 0.7855931 0.2371142 -0.5715071 0.6881638 0.4511296 -0.5682543 0.6863059 0.4555954 -0.5669366 0.6472781 0.50104 -0.5744476 0.5890123 0.574096 -0.5687515 0.1345839 0.808201 -0.5733221 -0.01575124 0.8131585 -0.5818293 -0.159581 0.8181581 -0.5524052 -0.08511078 0.829459 -0.5520455 0.1192122 0.8122234 -0.5710356 -0.5181663 0.6405637 -0.5667292 -0.04387789 0.8205962 -0.5698217 0.3443723 0.7542127 -0.5590805 0.4611237 0.6897898 -0.5581712 0.5764721 0.5927487 -0.5624313 0.3763428 0.7337 -0.56573 0.4848631 0.6686347 -0.5637691 -0.7568366 0.3154759 -0.5724276 -0.8218019 0.08497297 -0.5634016 -0.8047442 0.2610902 -0.5331217 0.9002709 0.4353196 -0.003038167 0.8294928 0.5585088 0.00315541 0.6990373 0.7150786 0.003106415 0.1067864 0.9942781 -0.002812504 -0.09558206 0.9954175 -0.002864599 -0.8953022 0.4454524 -0.002499759 -0.8516071 -0.5241758 -0.002265989 -0.7286739 -0.6848575 -0.002117514 -0.005631446 -0.999983 -0.001525223 0.3576476 0.9338518 0.003024041 -0.4355709 0.9001501 0.002829551 -0.9950751 0.09909194 0.002525806 -0.6047687 -0.7963981 0.002217411 -0.01198065 -0.9998761 0.01021504 0.108134 -0.9941363 3.44405e-4 0.566639 -0.8239515 -0.004931688 0.7209049 -0.6930264 -0.003245174 0.8068786 -0.5907078 0.003371 0.969466 0.2452054 -0.003195822 0.9750224 -0.2220821 0.003329813 0.9998019 -0.01963651 0.003271818 0.9829455 0.1838686 0.003248631 0.5664824 -0.824059 -0.00495851 0.9165807 0.3386908 -0.2125287 -0.6127079 -0.2719016 -0.7420638 -0.2310413 -0.08410745 -0.9693018 0.3076903 0.1122071 0.9448473 0.08883917 0.02667599 0.9956887 0.007464051 0.02803474 0.9995791 -0.0269199 -0.007314801 0.9996109 -0.1476327 -0.2581452 0.9547595 -0.0304442 -0.008420825 0.999501 0.1688752 -0.01988846 0.9854369 -0.2782708 -0.9592725 -0.04859757 0.3145816 -0.5713127 0.7580504 0.4874246 0.3519841 0.7990772 -0.7560079 -0.3002238 0.581651 -0.2825834 -0.9591388 -0.01412343 -0.4814417 -0.8764769 0.001457273 -0.597714 -0.8004671 -0.04461401 -0.03557008 -0.9990222 0.02626103 -0.02064758 -0.9713402 0.2367948 0.9918619 -0.08715581 0.09281021 0.009975969 0.005331456 0.9999361 0.02633273 0.007453441 0.9996255 0.04130589 0.004513442 0.9991363 -0.01619911 0.9749594 0.2217921 0.7454348 -0.6538647 0.1295689 -0.3769855 -0.9261828 0.008203864 -0.9953083 0.02072912 0.09450906 -0.669574 -0.7340789 -0.1131325 -0.9989498 -0.02865511 -0.03575122 0.1207731 -0.8038387 0.5824579 -0.2639986 0.3479899 0.8995598 0.08626544 0.2021467 0.9755486 0.3229944 0.4816064 -0.8146961 0.04124766 0.01053881 0.9990934 0.01344621 0.4916667 0.8706797 0.5336225 0.8449432 0.03630673 0.752976 0.2657483 0.6020008 0.5478599 0.1878905 0.8151974 0.9446451 0.3207042 -0.0692439 0.7858998 0.1934519 0.5873142 0.5738359 0.8186248 0.02378654 0.7047629 -0.6869989 -0.1770367 0.634862 0.7634155 0.1189419 0.8255557 -0.5642755 -0.007155239 0.3768599 0.8969126 -0.2313537 0.3601586 0.9328883 -0.002296566 0.8214355 -0.5564896 0.1247525 -0.625934 0.7711116 -0.1165912 -0.2314505 -0.9260722 0.2980288 -0.1471455 -0.9847318 0.09301376 -0.7024632 -0.7114534 -0.01948153 -0.8283417 -0.4950199 0.2623079 -0.08201456 -0.9866747 0.1405229 -0.1229847 0.9906097 -0.05972599 -0.8679929 0.4796348 0.1286033 -0.9989588 -0.03064203 -0.03379893 0.8980141 0.2161996 -0.3831821 0.1107291 0.7514836 0.6503934 -0.1430908 -0.9887222 0.04419875 -0.2103737 -0.9776203 0.001263618 0.8714055 0.4444404 0.2076668 -0.7904958 -0.4295817 -0.4365502 -0.9322042 0.2803198 -0.2289458 -0.9730292 0.2245042 0.05302965 -0.4213129 -0.8552553 -0.301718 0.9315037 0.360131 0.05105572 -0.3133828 0.9379697 0.1483383 0.7507468 0.6423299 -0.1542451 -0.5885002 -0.5363864 0.6049439 -0.5637291 -0.5962538 0.5715689 -0.2345654 -0.7803881 0.5796324 -0.2138946 -0.8018943 0.5578662 -0.6583925 -0.4126362 0.6294845 -0.8188609 0.06403803 0.5704087 4.99194e-6 -1.88512e-6 -1 2.77384e-5 1.93685e-5 -1 1.27204e-5 3.94582e-6 -1 1.23261e-4 1.83969e-5 -1 0.02222192 0.009121239 -0.9997115 0.04230028 -0.05133342 -0.9977853 2.37953e-4 -1.90279e-5 -1 -0.001222252 -0.001159489 -0.9999986 -5.18649e-4 1.21437e-4 -1 -0.07120645 -0.06621623 -0.9952614 1.19478e-4 2.89661e-5 -1 0.5413593 0.5995062 0.5895103 0.2067564 0.7891973 0.5782903 -3.18518e-5 -8.34482e-6 -1 -1.98424e-5 -6.75401e-6 -1 -3.02673e-5 -1.79606e-5 -1 -1.23262e-4 -1.8398e-5 -1 0.0274899 0.01135635 -0.9995577 0.0228244 -0.008961558 -0.9996994 -0.01313316 -0.002254128 -0.9999113 0.002192676 -0.05060732 -0.9987162 -0.01695054 -0.1851711 -0.9825601 0.04310071 -0.02443134 -0.998772 -2.36763e-4 1.8875e-5 -1 0.001240253 0.001173198 -0.9999986 -0.004105806 -0.002356648 -0.9999889 0.07115101 0.06616431 -0.9952688 -0.5210471 -0.7956654 -0.3089119 0.8592769 -0.1694405 -0.4826316 -0.8786468 0.434263 0.1984832 -0.7891372 -0.5470058 0.2793697 0.8640476 -0.4978857 -0.07437562 0.8971 0.4340246 0.08266967 0.003992259 0.005898714 -0.9999747 -0.001137554 3.42351e-4 -0.9999993 -6.34296e-4 0.001533389 -0.9999987 -9.93979e-4 3.78754e-4 -0.9999995 -5.40066e-4 -6.44597e-5 -1 -7.26079e-4 -0.001460075 -0.9999988 -0.002172768 -0.002068817 -0.9999955 -0.001844942 0.003895163 -0.9999907 -0.8592892 0.1694204 -0.4826167 -0.5355759 -0.7848441 -0.3117346 -0.8636102 0.498884 -0.0727474 -0.1315367 -0.9376864 0.3216245 0.8786501 -0.4342597 0.1984757 5.39059e-4 6.8731e-5 -0.9999999 7.24876e-4 0.001456558 -0.9999987 -0.003674447 -4.86137e-4 -0.9999932 0.005194365 -4.4824e-4 -0.9999864 0.001846909 -0.003896653 -0.9999907 0.001136124 -3.4196e-4 -0.9999993 6.34929e-4 -0.001536965 -0.9999987 -0.9265507 -0.3360615 -0.1690163 0.3438119 0.9363431 -0.0710985 0.9993732 -0.01970016 0.0294153 0.9193621 0.3832786 -0.08871793 0.2515352 0.9433259 0.2164863 0.128376 0.9910739 0.03594559 6.28853e-5 7.18576e-5 1 -0.006647169 0.002119719 0.9999757 -0.003773093 -0.005461752 0.999978 -0.003740012 -0.007092058 0.9999679 -0.05382627 -0.05384778 0.9970974 -0.0321654 -0.01771348 0.9993256 -0.04117208 -0.00854367 0.9991157 -0.001638412 0.001539289 0.9999975 0.008169591 -0.01438033 0.9998633 -0.005712211 -0.01533418 0.9998662 0.02566432 0.0303114 0.999211 0.01429826 0.00947231 0.999853 -3.53927e-4 -2.30899e-4 1 -3.96147e-6 -2.74655e-6 1 0.03053325 0.01166069 0.9994658 -6.18425e-4 -3.11634e-4 0.9999998 -1.29995e-4 -1.39249e-4 1 -0.002130031 -5.15743e-4 0.9999977 -0.01205176 0.01415401 0.9998272 -1.33092e-5 1.79433e-6 1 0 7.08292e-5 1 0.9982432 0.0214008 0.05525165 0.1317237 -0.9908554 -0.02923297 -0.8445117 -0.5353921 0.01246947 0.07053709 0.9971794 0.02565157 0.05362367 -0.9985607 0.001101732 -0.9826341 -0.1640593 -0.08668804 -0.07051849 -0.9971824 0.02558523 -0.9982193 -0.02141559 0.05567526 -0.1318503 0.9912697 -1.35522e-4 0.1419765 -0.9894402 -0.02916944 -0.7847265 -0.6164075 -0.06516432 -0.9274492 0.371083 -0.04621058 0.7858294 0.6177542 -0.02918934 0.6644634 0.2418466 0.7071058 0.9396925 0.3420204 2.32046e-5 0.9396924 0.3420211 2.55636e-5 -0.6644645 -0.2418457 0.7071052 0.3412749 -0.9389244 -0.04418689 0.6645181 0.2418583 0.7070505 0.6639779 0.2417424 0.7075974 0.6643175 0.2418242 0.7072505 0.6644905 0.2418467 0.7070803 0.66447 0.2418252 0.7071071 0.6644723 0.2418439 0.7070984 -0.7168667 -0.2609178 -0.6465478 -0.6411472 -0.3054677 -0.7040027 -0.7168667 -0.2609212 -0.6465464 -0.6411495 -0.3054672 -0.7040008 -0.6411477 -0.3054715 -0.7040006 -0.6411464 -0.3054704 -0.7040023 -0.7168655 -0.2609186 -0.6465488 -0.6411501 -0.3054676 -0.7040001 -0.7168647 -0.2609172 -0.6465504 -0.7168674 -0.2609173 -0.6465473 -0.7168706 -0.2609161 -0.6465442 -0.6411477 -0.3054674 -0.7040024 -0.6411491 -0.3054682 -0.7040008 0.6644642 0.2418414 -0.7071068 0.6644619 0.2418442 -0.7071081 0.664453 0.2418707 -0.7071074 0.6648851 0.2422693 -0.7065646 0.7168663 0.2609193 -0.6465476 0.6874992 0.178121 -0.7040013 0.7168688 0.2609179 -0.6465455 0.716867 0.2609191 -0.646547 0.6874988 0.1781178 -0.7040024 0.7168681 0.2609153 -0.6465474 0.6874992 0.178118 -0.7040021 0.6875016 0.1781351 -0.7039954 0.7168611 0.2609105 -0.6465569 0.7168598 0.2609252 -0.6465526 0.6874932 0.1781326 -0.7040042 0.7168616 0.2609228 -0.6465514 0.6874372 0.1783077 -0.7040146 0.6875001 0.1781215 -0.7040003 0.7168683 0.2609158 -0.6465469 -0.4052683 -0.1880655 0.8946446 -0.6022366 -0.2903808 0.7436331 -0.6721644 -0.1127671 0.731764 0.5086058 0.6004106 0.6171121 0.5061836 0.2687891 0.8194698 0.6676806 0.5402158 0.5122203 0.5840315 0.4961874 0.6424215 0.5228304 0.6912144 0.4988698 0.7111304 0.7005696 -0.05912595 0.0146563 0.3345648 0.9422588 -0.1045432 0.3927255 0.9136944 0.01538288 0.3455445 0.9382763 -0.1556263 0.2751086 0.9487338 -0.2432351 0.1687671 0.9551724 -0.618438 -0.4224568 0.6626196 0.4161084 0.04272371 0.9083108 -0.3571782 -0.5869655 0.7265641 0.584043 -0.8087002 0.06998401 0.9588914 0.2807007 0.04164868 0.9574731 0.2858311 0.03931719 0.9582442 0.2835794 0.03675293 0.4488751 -0.1589226 0.8793491 0.04813951 -0.2133495 0.9757893 0.01012212 -0.02781033 0.999562 0 0 1 -0.00510025 0.01601159 0.9998589 -1.3445e-4 1.74302e-4 1 0.3536217 -0.9347284 0.03513807 0.3534155 -0.9348192 0.03479468 -0.1251494 -0.503107 0.8551148 -0.2139962 -0.9762571 0.03358322 -0.8331521 -0.2769133 0.4787241 -0.985499 0.1575216 0.06307733 -0.04629909 0.2166342 0.9751543 -0.3534095 0.9348214 0.03479564 0.1223428 0.4987295 0.85808 0.214044 0.9762468 0.03357708 0.9391633 0.3422061 0.02945041 0.9367625 0.3482709 0.03440022 0.3418821 -0.9391739 0.03269547 -0.4556077 -0.1786944 0.8720608 1.08925e-4 -1.07599e-4 1 -0.004209041 0.005224645 0.9999775 -0.2099039 -0.9770818 0.03537887 -0.2139776 -0.9762613 0.03357905 -0.936594 -0.3486722 0.03492003 -0.2313091 8.04937e-4 0.9728801 -0.8283483 0.5594019 0.03014349 -0.3534821 0.9347804 0.03515785 -0.3534076 0.9348129 0.03504484 0.2209576 0.9748066 0.03049546 0.2140155 0.976253 0.03357881 0.1875919 0.1566383 0.9696772 0.9395736 0.3410794 0.02943551 0.9365896 0.3486499 0.03526145 -0.01389712 0.0413354 0.9990488 -0.3417525 0.9391392 0.03497028 0.2086076 0.9773386 0.0359447 0.213999 0.9762563 0.03358995 0.4058004 0.1535281 0.9009746 0.4889346 0.1681007 0.8559703 0.05399471 -0.2028927 0.9777113 0.3534153 -0.9348192 0.03479534 -0.1251491 -0.5031099 0.855113 -0.2099485 -0.9770725 0.0353679 -0.9365948 -0.3486357 0.03526145 0.1666546 0.6993838 0.6950457 0.1680241 0.4795274 0.8612906 -0.01301193 0.03908264 0.9991513 0.01252317 -0.03971022 0.9991328 0.939118 0.3423289 0.02946668 0.936617 0.3486576 0.03444886 0.8165955 -0.5760923 0.03591156 0.8281138 -0.5597516 0.03009808 0.04811406 -0.2134134 0.9757765 -0.2099708 -0.9770674 0.03537899 -0.2140451 -0.9762467 0.03357589 -0.9365819 -0.3486691 0.03527462 -0.8196361 0.5717953 0.03531128 -0.828269 0.5595238 0.03005927 -0.09632921 0.2141752 0.9720337 -0.2547819 0.7097229 0.656795 0.1666603 0.4762275 0.8633838 -0.01301151 0.03908145 0.9991514 1.93724e-4 -2.51123e-4 1 0.2139762 0.9762409 0.03417366 0.9391028 0.3423715 0.0294556 0.04810667 -0.2133767 0.975785 0.3536171 -0.9347301 0.03513801 -0.1251575 -0.5031034 0.8551155 -0.4371434 -0.2378013 0.8673848 -0.09632718 0.2141692 0.9720353 -0.2547838 0.7097235 0.6567936 0.4662059 0.2052693 0.8605327 0.8333126 0.2765939 0.4786292 1.93711e-4 -2.51114e-4 1 0.2470222 0.9682013 0.0395779 0.261313 0.9646542 0.03402888 0.9391193 0.3423261 0.02946364 0.9366156 0.3486613 0.03444737 0.9854979 -0.1575282 0.06307834 0.8166151 -0.5760681 0.03585493 0.8282004 -0.5596225 0.03011441 0.04810559 -0.213375 0.9757853 0.3536144 -0.9347296 0.03517645 -0.125158 -0.503108 0.8551128 -0.2099418 -0.977073 0.03539741 -0.21402 -0.9762517 0.03358674 -0.4371414 -0.2378003 0.867386 -0.9395812 -0.3410585 0.02943509 -0.8196336 0.5717989 0.03531306 -0.82827 0.5595225 0.03006023 -0.09634619 0.2142108 0.9720243 -0.3503978 0.9359495 0.03492897 0.1680328 0.4794796 0.8613154 0.4662211 0.2052764 0.8605228 0.8333144 0.276599 0.4786232 1.23471e-4 -1.60059e-4 1 0.01252138 -0.03970378 0.9991331 0.2470186 0.9682019 0.0395841 0.2613179 0.964653 0.03402286 0.9854952 -0.1575349 0.06310385 0.8280873 -0.5597897 0.03011673 -0.2099386 -0.9770751 0.03535932 -0.9395832 -0.3410536 0.02943021 -0.8196477 0.5717789 0.03530937 -0.8282793 0.5595086 0.03006118 -0.09634643 0.2142083 0.9720248 -0.3503938 0.9359513 0.03492116 0.1666408 0.6994642 0.6949681 0.01252442 -0.03971332 0.9991326 0.2470229 0.9682011 0.03957813 0.939117 0.3423321 0.02946412 0.9854954 -0.1575415 0.06308364 0.8165951 -0.5760926 0.03591525 0.8281109 -0.5597556 0.03010153 0.04811108 -0.2133904 0.9757817 -0.1251414 -0.5031014 0.8551191 -0.2139406 -0.9762687 0.0336008 -0.4371418 -0.2378048 0.8673846 -0.8280286 0.5598787 0.03007668 -0.3418709 0.9395225 0.02053743 0.1666415 0.6994844 0.6949477 0.1680079 0.4794839 0.861318 0.4662039 0.2052643 0.8605351 -0.01301097 0.03907918 0.9991515 1.23451e-4 -1.60047e-4 1 0.01252341 -0.03971087 0.9991328 0.2470139 0.9682034 0.03957754 0.2612787 0.9646633 0.03403323 0.9855002 -0.1575129 0.06308013 -0.4370807 -0.2377719 0.8674244 -0.9395865 -0.3410444 0.02942949 -0.9365825 -0.3486674 0.03527474 -0.8196665 0.5717529 0.03529375 -0.09635931 0.214236 0.9720174 0.4678341 0.2059835 0.8594778 -0.01301139 0.03907972 0.9991515 1.93811e-4 -2.51231e-4 1 0.01252311 -0.03971034 0.9991328 0.2140072 0.9762342 0.03417277 0.9391022 0.3423731 0.02946007 0.936613 0.3486689 0.03444093 0.0481131 -0.2134097 0.9757773 0.353625 -0.9347271 0.03513813 -0.9395789 -0.341064 0.02944493 -0.8196583 0.5717622 0.03533136 -0.8283473 0.5594069 0.0300824 -0.3503847 0.93595 0.03504848 -0.1227673 0.2537927 0.9594361 -0.0138964 0.04133367 0.9990488 0.2146243 0.9761188 0.03359538 0.4889556 0.1681045 0.8559576 0.9365975 0.3486632 0.0349152 0.6831147 -0.5033173 -0.529175 0.8202094 -0.5709745 0.03528171 0.8281064 -0.5597611 0.03012424 0.1461538 -0.4073514 0.9015009 0.3535596 -0.9347562 0.03502213 0.3534153 -0.9348195 0.03478634 -0.2139726 -0.9762616 0.03360587 -0.4377101 -0.2371513 0.8672769 -0.9395775 -0.3410698 0.02942138 -0.9365758 -0.3486832 0.03529512 -0.8010398 0.5979713 0.02767455 0.1656185 0.6995635 0.6951125 0.2645486 0.9638021 0.03315973 0.4565392 0.1778208 0.8717522 0.2238267 -0.007835447 0.9745975 -0.003101289 0.01825886 0.9998285 0.9390048 0.3420881 0.03529411 0.8281577 -0.559686 0.03010737 0.0480743 -0.213474 0.9757652 -0.2140547 -0.9762443 0.03358137 -0.4373313 -0.236547 0.8676331 -0.8199898 0.5712875 0.03531998 -0.09853357 0.2191041 0.9707135 -0.2554295 0.7096321 0.6566416 0.5061351 -0.4210733 0.7526783 0.580385 0.2086687 0.7871534 0.4304881 0.1634755 0.8876687 0.009505271 -0.2596936 0.9656444 0.4676073 0.1986491 0.8613258 0.5214803 0.2216406 0.8239744 0.540138 0.1616414 0.8259074 0.5384957 0.196012 0.819513 0.4575961 0.1621347 0.874253 0.5157579 0.1664438 0.8404108 0.4723724 0.1039366 0.8752495 0.5111814 0.2049028 0.8346907 0.4238298 0.1492299 0.8933637 0.3329201 0.1506807 0.9308381 0.4941833 0.1770188 0.8511447 0.5395334 0.1963904 0.8187397 0.6111013 0.3326103 0.7182796 0.5325291 0.2462317 0.809804 0.5291929 0.203478 0.8237425 0.3822478 0.14769 0.9121811 0.488851 0.1771644 0.8541883 0.5385102 0.1959732 0.819513 0.5060818 0.1697325 0.8456194 0.5689172 0.1861848 0.8010422 0.2963668 0.2209458 0.9291662 0.2055479 0.09076702 0.9744288 0.485521 0.2824797 0.8273298 0.4921231 0.2827462 0.8233283 -0.8179793 -0.1131809 0.5640035 0.6378491 0.2964757 0.7108098 -0.224081 0.6955707 0.6826194 -0.3919715 0.6116763 0.6871759 0.5911306 -0.3947679 0.7033655 0.2717927 -0.7256392 0.6321206 -0.508298 -0.09226256 0.8562248 2.11275e-4 1.78658e-4 -1 0.5665732 0.1486853 0.810486 0.4537513 0.03267592 0.8905292 0.337067 -0.005447089 0.9414649 0.2537555 -0.1967305 0.9470508 0.1423786 -0.3067456 0.9410822 0.1340389 0.3631459 0.9220405 0.3945772 0.1970713 0.8974809 0.3846734 0.4328529 0.8152697 0.4067674 0.5247648 0.7477715 0.1340623 0.3628283 0.9221621 -0.6422668 -0.3035127 0.7038278 -0.582902 -0.4216722 0.6945632 -0.2833652 -0.4373331 0.8534893 0.1941878 -0.5290279 0.8260875 0.2236421 -0.9733878 0.0500046 -0.3205237 -0.9433699 0.08554518 -0.8102135 -0.5861088 -0.005546629 -0.8140505 -0.5807943 0 0.7844435 -0.6180905 -0.05111473 0.6575668 -0.7517452 -0.04985326 0.480561 -0.8754843 -0.05087661 -0.02047634 -0.9985437 -0.04991257 -0.2036392 -0.9777102 -0.05112648 -0.3798036 -0.9236087 -0.05192542 -0.669151 -0.7431259 9.37233e-4 -0.5589393 -0.829205 0.002416551 -0.5437488 -0.8391968 0.009284853 -0.3802694 -0.9247391 0.01590144 0.5712964 -0.8101317 -0.1315566 0.8794839 -0.4754332 0.02171027 0.9611673 -0.2759556 0.002458035 0.993615 -0.1127059 0.005171239 0.997401 0.07183659 -0.005554735 0.9969238 0.07837855 0 -0.2038087 -0.9785193 0.0310198 0.9559632 -0.2933398 0.00928688 0.9997729 -0.02130752 4.93659e-4 0.9915324 -0.112481 -0.06489598 -0.9916886 -0.05631309 0.1156842 -0.9594528 -0.2818694 9.17466e-5 0.9063971 0.4223161 0.009674549 6.15703e-4 1.55866e-4 0.9999998 -0.02704548 9.58882e-4 0.9996338 -0.02899825 -0.001307427 0.9995786 -0.03011649 0.004787683 0.999535 1.08068e-4 -1.56731e-4 1 1.03344e-4 -2.44673e-4 1 -0.02263104 -0.002178847 0.9997416 -1.21739e-5 -5.6731e-5 1 1.39079e-4 3.19308e-4 1 1.86925e-4 2.66408e-4 1 -6.62536e-5 -9.84672e-6 1 -5.34404e-4 4.18113e-4 0.9999998 1.60647e-4 5.77313e-5 1 1.14751e-4 2.49901e-4 1 -3.02701e-6 6.33952e-5 1 -2.00638e-4 4.13652e-6 1 6.07884e-5 5.64563e-4 1 3.78758e-4 2.90013e-4 0.9999999 2.40858e-4 1.1038e-4 1 0.918663 0.3950378 -0.00191003 0.9146527 0.4042402 -5.53903e-4 0.9126436 0.4087564 -6.07216e-5 0.9253928 0.3790097 7.70018e-5 0.9195024 0.3930705 -0.003310859 0.9248365 0.3803237 0.005606532 0.936617 0.3503 0.006206154 0.9421555 0.3351225 0.006011068 0.9524903 0.3045343 0.004583954 0.939619 0.3421398 -0.007517278 0.9512719 0.3082854 -0.006472408 0.9114924 0.4113154 0.001190304 0.90964 0.4151987 -0.01285266 -0.07121229 0.1183441 -0.9904158 -0.9637631 -0.2664059 -0.01374137 -0.9752091 -0.2212784 -0.00176388 -0.9582532 -0.2859212 -4.52519e-4 -0.9456837 -0.3249994 -0.007596313 -0.9397059 -0.3419014 -0.007521927 -0.9334315 -0.3586845 -0.007157325 -0.9200518 -0.3917613 -0.005296111 -0.9426597 -0.3336977 0.006206631 -0.9371455 -0.3488873 0.005993425 -0.9313909 -0.3639793 0.005488216 -0.7792259 0.01972883 0.6264325 -0.8060204 0.004851639 0.5918679 -0.9260202 0.1744472 0.3347457 -0.9292558 0.1592661 0.3333438 0.4615111 0.1811614 -0.86844 0.4671109 0.1921263 -0.8630729 0.4607536 0.18755 -0.8674855 0.4914475 0.1910422 -0.8496954 0.4958862 0.2009122 -0.8448262 0.46912 0.1803514 -0.8645229 0.4584816 0.1802129 -0.8702401 0.4755606 0.1802968 -0.8610084 0.4536594 0.1671669 -0.8753563 0.4993416 0.1867572 -0.8460377 0.4838973 0.1736416 -0.8577249 0.463279 0.1619546 -0.8712884 0.4708671 0.1659075 -0.8664635 0.4752444 0.1596224 -0.8652535 0.4769955 0.1618546 -0.8638741 0.4775848 0.1617302 -0.8635717 0.4473038 0.1323688 -0.8845326 0.4752362 0.154475 -0.8661917 0.4767929 0.1524429 -0.8656962 0.5131446 0.1708179 -0.8411326 0.4975364 0.1425359 -0.8556525 0.4009091 0.1259647 -0.9074166 0.4866891 0.1351668 -0.8630549 -0.9443703 -0.3261319 0.04246032 -0.944232 -0.3265886 0.04202377 -0.5673409 0.8208072 0.06633305 -0.6863054 0.7256004 0.0498901 -0.9387332 -0.3428719 0.03491556 -0.9541424 0.2992978 0.005761027 0.4052596 -0.9097532 0.09007662 0.4690892 -0.8803696 0.07003515 -0.9383248 -0.3440219 0.03457498 -0.1985617 0.9752764 0.09700185 -0.9351566 -0.3524484 0.03552925 -0.1954923 -0.9746423 0.1088815 -0.9317816 -0.3613135 0.03515344 -0.1817491 -0.9799331 0.08184343 0.04146206 -0.9980921 0.04575234 -0.8594421 0.5072903 0.06337147 -0.8769505 0.4756102 0.06894111 0.01266425 -0.002774119 -0.999916 1.80309e-7 0 -1 -3.79481e-5 -1.79623e-5 -1 -2.8288e-6 -1.31879e-6 -1 1.28852e-6 8.64139e-7 -1 -7.38153e-4 -2.6483e-4 -0.9999997 1.23168e-4 -1.16071e-4 -1 0.09598994 0.02186226 -0.9951423 -6.40979e-4 -2.10171e-4 -0.9999998 0.08525055 0.02921766 -0.9959311 -4.54596e-7 0 -1 -0.001065611 -3.49539e-4 -0.9999994 0.03130191 -8.48575e-4 -0.9995096 -0.001500129 2.45555e-4 -0.9999989 -0.0130946 -0.004765987 -0.999903 0.008479714 0.003086507 -0.9999594 -0.01493811 -0.005436837 -0.9998736 -0.005652189 -0.001478493 -0.999983 0.0396319 0.009726285 -0.9991671 0.001049995 0.003206729 -0.9999943 0.06579238 0.02218496 -0.9975867 0.008480608 0.003086805 -0.9999594 0.008482038 0.003086984 -0.9999593 0.008416652 0.003068864 -0.9999599 0.056755 0.02733159 -0.998014 0.06143397 0.02725958 -0.9977388 0.1037004 0.03552114 -0.9939741 0.008532166 0.003099858 -0.9999588 0.008481204 0.003086805 -0.9999593 0.001695871 -9.65363e-4 -0.9999981 -0.006085336 -0.001995742 -0.9999796 0.008793592 0.003458678 -0.9999554 0.5585229 0.8284023 0.04244923 0.2213151 0.970748 0.09310263 0.9397718 0.3400025 0.03503221 0.9398335 0.3398145 0.03520381 0.08331817 -0.9964307 0.01356685 0.9256348 -0.3692391 0.08284235 0.936702 0.3483852 0.03488838 0.2062249 0.9759687 0.07040148 0.923443 -0.3725731 0.0918821 0.9300475 0.3657108 0.03559732 0.9266393 0.3743292 0.0348913 0.8154296 -0.5765702 0.05139493 -0.8222689 -0.5433983 -0.1690927 0.7433509 -0.6621815 0.09457856 -0.9204806 -0.3751003 -0.1096136 -0.9159712 -0.3845469 -0.114545 -0.6697145 -0.6987569 -0.2514387 -0.3079074 -0.8872591 -0.3434596 0.1122678 -0.9207625 -0.3736205 -0.6886135 -0.683427 -0.2423613 -0.379392 -0.626003 -0.681309 -0.6051367 -0.5725247 -0.5531954 -0.71352 -0.5111679 -0.4791624 -0.97905 -0.2001198 -0.03759026 -0.9836428 -0.1779549 -0.02791106 0.5065361 -0.7770943 -0.3735582 0.525048 -0.7655677 -0.3717942 0.9667581 -0.08075845 -0.2426042 0.9151596 0.3550334 -0.1908776 0.9216532 0.3200945 -0.2193056 0.875157 0.06705808 -0.4791695 0.8415409 -0.02708941 -0.5395138 0.6385686 -0.3083183 -0.7051028 0.3703178 -0.5062801 -0.7788101 0.3056585 -0.8801586 -0.3631718 0.2982059 -0.2842876 -0.9111827 0.4649624 -0.3150126 -0.8273918 0.9837837 0.1466646 -0.1032443 0.2198345 -0.6040263 -0.7660452 0.4210392 0.9070328 -0.004183292 0.7477176 0.664017 1.71006e-4 0.8191401 0.5735797 -0.004001319 0 9.87534e-6 -1 -1.66473e-5 5.22777e-6 -1 0.001549184 -0.00548011 -0.9999838 -1.58786e-6 0 -1 -3.0596e-6 0 -1 0.002022147 9.93697e-4 -0.9999976 -0.001695334 0.001307725 -0.9999978 9.53693e-7 0 -1 1.48491e-6 0 -1 2.21405e-4 -8.95634e-7 -1 2.00522e-4 -1.39937e-5 -1 0.2197774 -0.6040843 -0.7660157 0.2198457 -0.6040287 -0.76604 0.2197744 -0.6040841 -0.7660169 -0.04783511 -0.482208 -0.8747498 -0.380563 -0.6057418 -0.698748 0.2190902 -0.6046693 -0.7657508 -0.9396926 -0.3420203 0 -0.9396924 -0.3420211 -1.18362e-4 -0.9396927 -0.3420202 1.12964e-4 -0.6644618 -0.2418444 0.7071081 -0.6644599 -0.2418426 0.7071105 -0.6644656 -0.241846 0.707104 -0.6644535 -0.2418461 0.7071154 -0.6644589 -0.2418443 0.7071109 -0.6644843 -0.2418445 0.7070869 -0.6644744 -0.2418339 0.7070997 -0.6644558 -0.2418441 0.7071138 0.6645071 0.2418578 -0.707061 0.6642979 0.2417741 -0.7072861 -0.6644766 -0.2418516 0.7070917 -0.6644561 -0.2418421 0.7071142 -0.6644492 -0.2418291 0.7071251 -0.6644631 -0.2418449 0.7071067 -0.6644597 -0.2418421 0.7071108 -0.6644671 -0.2418515 0.7071007 -0.6644653 -0.2418437 0.707105 -0.6644618 -0.2418459 0.7071076 0.01334017 0.02974468 -0.9994685 -0.3312472 0.9418012 0.05732214 -0.3505279 0.9354883 0.04463243 0.8617303 -0.3086056 0.40272 -0.00125128 -0.003355681 0.9999936 2.68836e-4 3.79979e-4 0.9999999 0.002934932 -0.002952933 0.9999914 6.21702e-4 -0.01236295 0.9999234 8.87562e-5 1.47251e-4 1 0.04165208 0.05094224 0.9978327 0.02665114 0.02681767 0.999285 -4.80323e-5 6.66649e-5 1 2.35703e-4 0.003268897 0.9999946 0.6814252 -0.6443203 -0.3471472 0.4904224 -0.6077497 -0.6246008 0.6240751 -0.5810823 -0.5223732 -0.2734757 -0.9588142 -0.07672452 0.4800053 -0.4807171 -0.7338297 0.3952774 -0.1942557 -0.8977864 0.136128 0.6100948 -0.780547 0.1050165 -0.1637898 -0.9808896 0.348772 -0.9360711 0.04614311 0.5484215 -0.8356173 -0.03126686 0.6209948 -0.7838123 -0.001943409 0.614125 -0.7891937 -0.004895687 0.7345491 -0.6784703 -0.01075744 0.7618419 -0.6477215 0.007341504 0.733286 -0.4555431 -0.5047497 0.3801599 0.05942302 -0.9230101 -0.9500235 -0.2611786 0.1710004 -0.6436141 -0.7540364 0.1311107 0.8497678 -0.2725098 -0.4512572 0.837474 -0.08462953 -0.5398844 0.6287983 -0.5192825 -0.578756 0.9546134 0.1140932 -0.2751291 0.3480865 -0.9357547 -0.05655962 -0.3883371 -0.3624807 0.8472321 -0.374179 -0.3754135 0.847971 -0.2033206 -0.6978499 0.6867796 0.3141931 -0.7546691 -0.5759838 -0.2072493 -0.7036918 0.6796069 0.1219901 -0.9898127 -0.07341116 0.366468 -0.9300732 0.02578926 0.2120728 -0.9631378 -0.165502 0.6320163 -0.7537899 0.179879 0.1623978 -0.4029862 0.9006826 -0.2175938 -0.5572778 0.8013079 -0.06613767 -0.116167 0.9910253 -0.1114119 -0.979898 0.1654915 0.0561428 -0.9983565 0.01150918 -0.1036692 -0.9941586 0.03002226 0.9691092 -0.2465934 0.004362702 0.9241234 -0.3820745 0.003917276 0.8946456 -0.4467672 -0.002905905 0.8280192 -0.5606976 0.001596331 0.6547539 -0.755743 0.01224118 0.5985689 -0.8004515 -0.03150629 0.3461493 -0.9379651 -0.02005332 -0.2741059 -0.9616994 -5.92189e-4 -0.3446448 -0.9387271 0.003381609 -0.375633 -0.9265693 -0.01921367 -0.1252331 -0.9913819 -0.03845554 -0.4623283 -0.8867003 0.003917336 0.2953867 -0.9546418 0.03749352 0.4873213 -0.8731793 0.008713722 0.7231091 -0.6904543 -0.01965361 0.8247131 -0.5655025 -0.007441163 0.6108416 -0.7915926 0.01593405 0.5483111 -0.8360565 -0.01909887 0.02561825 -0.7688498 -0.6389161 -0.1792559 -0.842491 0.5080122 -0.2029502 0.9786289 0.03311759 0.5254088 -0.8508471 -0.002210676 0.04944789 -0.9985451 -0.02150875 -0.1461088 -0.9881949 0.04607737 -0.1632705 -0.9865535 -0.007419764 -0.1907692 -0.9816062 0.007517755 -0.2139153 -0.8239443 -0.524744 -0.4937425 -0.8126173 -0.3096313 -0.2810111 -0.6845464 -0.6726285 -0.3492085 -0.5138857 -0.7835655 -0.1191191 -0.5197923 -0.8459472 -0.3866775 -0.2960573 -0.8734019 -0.152031 -0.2679316 -0.951367 -0.05121648 -0.1482355 -0.987625 0.3396959 -0.9333017 -0.1164249 -2.57335e-5 1.11981e-4 1 0.1707472 -0.03131705 0.984817 1.27492e-7 0 1 0.06880444 0.2075425 0.9758033 2.63369e-7 0 1 1.54801e-7 0 1 0 0 1 2.16991e-7 0 1 0 0 1 1.79114e-5 1.07962e-5 1 2.59351e-5 4.02611e-6 1 1.43446e-5 2.94972e-5 1 1.93311e-5 -1.43077e-5 1 0.02047187 -0.1183692 0.9927586 -3.74001e-7 0 1 0.6302063 0.3465339 0.6948052 -0.5079415 -0.5503391 0.6626632 0.6884723 0.2274193 0.6886845 -0.108891 0.6384305 0.761938 0.1680281 0.7464083 0.6439265 0.06981998 0.5948584 0.8007925 -0.4762865 0.03387999 0.8786373 -0.3850781 0.6584125 0.6466899 -0.5796864 0.2821 0.7644497 -0.7151347 0.3268187 0.617877 -0.1711692 0.9852225 -0.006150007 0.8757408 0.4815481 -0.03448873 0.875556 0.4824151 -0.02602893 -0.9436437 0.3298451 -0.02718275 -0.5048764 0.8631706 -0.006048381 -0.9448502 0.3263863 -0.02702164 0.4349977 0.8986651 -0.05637514 0.98758 0.1526379 -0.0372489 -0.9689416 0.2467103 0.0169205 -0.2960301 -0.9535136 0.05637532 0.6171157 -0.7859904 0.03724896 -9.95682e-4 0.007982432 -0.9999676 -2.72596e-4 -5.64911e-4 -0.9999999 4.04685e-4 -1.32196e-4 -1 -0.001022636 -0.008704423 -0.9999616 -1.04768e-4 1.87856e-4 -1 -0.0111106 9.84102e-4 -0.9999379 0.01104748 -0.01017069 -0.9998873 -0.05139386 0.9986786 0 -0.1014435 0.9946974 -0.01692122 -0.9996727 0.019189 -0.01692092 -0.6383142 -0.7695185 -0.01990777 0.162658 -0.9866825 0 0.1129107 -0.9934611 0.01691949 0.9979135 0.06141924 0.01990765 0.009221732 0.004006385 -0.9999495 -0.008528113 -0.003122389 -0.9999588 -0.001733124 0.006676316 -0.9999762 0.008981645 -0.002525329 -0.9999566 0.01396745 0.00215882 -0.9999002 0.002064049 -0.01252448 -0.9999195 0.01104557 -0.01017057 -0.9998873 0.9075972 -0.4158372 0.05785155 0.6860157 -0.72541 -0.05623966 -0.3616197 -0.9319211 0.0274648 -0.9528914 -0.2980268 0.05637508 -0.7872767 0.6154739 0.03724944 -0.1395244 -0.9898378 -0.02746367 -0.8150858 0.5789287 0.02183943 0.4349897 0.8986567 -0.0565713 -0.1345666 -0.00470978 0.9908934 0.02229529 -0.3095026 0.9506372 -0.2186866 0.1709632 0.9607017 0.999491 -0.01357233 0.02887046 0.9298816 -0.3670052 -0.0250526 -0.7467127 -0.6639809 0.03936517 -0.9822425 0.1789458 0.05637532 -0.5081045 0.8605733 0.03526294 0.1138374 0.9930611 0.02950811 -0.2075809 -0.9780153 -0.01990878 -0.921527 -0.3842006 -0.05637359 0.5322018 0.8458941 -0.03499132 0.0731706 -0.01333016 0.9972304 0.9660317 -0.257869 -0.01692116 0.1811495 -0.9827198 0.03803598 -0.6233974 -0.7811218 0.03499311 -0.9726026 -0.2318574 0.01692146 0.2332351 -0.9721907 0.02113825 -0.9223479 -0.384561 -0.03724867 -0.03249996 0.9992734 -0.01990878 -3.93873e-4 1.76847e-4 1 -6.53034e-4 1.7222e-4 0.9999998 -1.38607e-4 6.86865e-4 0.9999998 0.01797598 0.001733005 0.9998369 -3.8488e-4 -2.33333e-4 1 -1.22454e-4 6.64183e-4 0.9999998 4.81484e-4 6.03416e-4 0.9999997 9.50112e-4 0.01598453 0.9998719 0.7194096 -0.6937291 -0.03449505 -0.7062267 -0.7077059 0.01990658 -0.9975925 0.06934982 0 -0.7431288 0.6685846 0.02746349 -0.05136436 0.9980667 0.034994 0.984769 0.1728227 -0.01903611 -0.2522414 -0.9673209 -0.02578365 -0.8152802 0.5790666 0 0.435392 0.89947 -0.03725016 -6.5367e-4 1.71714e-4 0.9999998 -1.3687e-4 6.84594e-4 0.9999998 -0.006893694 -0.02048528 0.9997665 -0.006670892 -0.03304219 0.9994317 -0.02440625 0.059367 0.9979379 0.009023189 0.01608228 0.99983 -3.01122e-4 -1.67258e-4 1 -1.22564e-4 6.64577e-4 0.9999998 -0.05175834 0.003598332 0.9986532 2.27035e-5 -4.41624e-4 1 0.525068 0.432615 0.7329038 0.1614364 -0.4973531 0.8523956 0.906287 -0.4221512 0.02079725 0.818945 0.5735787 -0.01835012 -0.9966252 -0.08137392 -0.01079797 0.09485656 -0.9953328 -0.01774311 0.1379816 -0.9902984 0.01643896 -0.892466 -0.4510374 0.008361935 -0.873036 -0.4876455 0.003161191 -0.9073663 0.4202401 0.009209334 0.7935959 -0.6084437 0.001336872 0.8107036 0.5851284 -0.01960909 -0.08986663 0.9957319 -0.02102702 -0.9966259 -0.0813657 -0.01079869 0.09485876 -0.9953327 -0.01774251 0.1379849 -0.990298 0.01643842 -0.1028794 -0.9946938 -4.62572e-4 -0.5002043 -0.8658545 -0.009575664 -0.6833304 -0.7300928 0.004904925 -0.907377 0.4202169 0.009210109 -0.08818918 0.9959338 0.01840132 0.923859 0.3827306 0.001349925 -0.3034835 0.9528356 -0.001450717 0.2612561 0.9643399 0.04235446 0.3070088 0.9511324 0.03306084 0.9364275 0.3491309 0.03480112 -0.2798487 -0.9592435 0.03919982 -0.2464423 -0.9682083 0.04288196 -0.7835093 -0.6196195 0.04674524 -0.939265 -0.3418554 0.03026717 -0.9364419 -0.3491173 0.03454923 0.3043671 0.9519832 0.0329948 0.9392623 0.3418633 0.03026461 0.936448 0.3491026 0.03453308 0.2804149 0.9591023 0.03860455 0.5062028 0.8608083 0.05261081 0.9364884 0.3489924 0.03455287 0.2614974 0.9645499 0.03553509 0.7842046 0.6200284 0.02425026 0.5134368 0.8565214 0.05247712 0.9392384 0.3419131 0.03044313 0.9365119 0.3489073 0.03477329 -0.2545757 -0.9663283 0.03742909 -0.9392637 -0.3418676 0.03017485 -0.9364176 -0.3491833 0.03454518 -0.5232408 -0.8478988 0.08536237 -0.9354859 -0.351706 0.03419125 -0.9362924 -0.3494695 0.03504055 -0.2729218 -0.961318 0.03716856 -0.7835252 -0.6194447 0.04875022 -0.9392621 -0.3418674 0.03022557 -0.9364669 -0.3490551 0.03450131 -0.9982466 -0.02904343 0.0515778 -0.5716578 0.817045 0.07513213 -0.9924384 0.1074995 0.05924588 0.2528877 0.9664874 0.04415822 0.9160408 0.3993852 0.03689098 0.7732557 -0.6330378 0.03659152 -0.9391215 -0.3418084 0.03489875 -0.9392827 -0.3413883 0.03467106 -0.236854 -0.9705666 0.04359692 -0.9446642 -0.3261197 0.03543257 -0.8091744 0.5856331 0.04765325 -0.9370781 -0.3424805 0.06776225 -0.9556135 -0.2926058 0.03442114 0.8287927 -0.558786 0.02934134 0.3535229 -0.9347023 0.0367853 -0.2518256 -0.967446 0.02514094 -0.2140727 -0.9759915 0.04016929 -0.9419777 -0.3343673 0.02960652 -0.9365941 -0.3481752 0.03956758 0.8040007 -0.5931419 0.04202157 0.8158476 -0.575443 0.05708056 0.9488579 0.3136832 0.03566235 -0.538784 -0.8382236 0.08422052 -0.9393751 -0.3419041 0.02599942 -0.9354904 -0.3516939 0.03419536 -0.9645802 0.2551859 0.06682258 -0.3706657 0.9278587 0.04105019 0.2544611 0.9654714 0.05580776 0.9952747 -0.08079153 0.05385988 0.9354866 0.3517035 0.03419804 0.9656732 -0.2510581 0.06667417 0.9906376 -0.1123262 0.07758998 -0.1598685 -0.9865015 0.03545516 0.9591875 -0.2653506 0.09771597 -0.2002428 -0.9790702 0.03639352 -0.2478961 -0.9674381 0.05109828 0.8397689 -0.5419508 0.03282624 0.8321624 -0.5533019 0.03691411 -0.9169148 -0.3976352 0.03396522 0.651511 0.2361499 0.7209484 0.5943605 0.1365461 0.7925218 -0.6483777 -0.1847527 0.7385613 0.5073735 0.08228886 0.8577883 0.1200307 -0.89657 0.4263274 -0.5721465 0.7720676 0.2766948 0.18514 0.02661883 0.9823516 -0.6818063 -0.2824743 0.6747952 0.4585652 -0.8251515 0.3299137 0.8092049 -0.3464828 0.474486 0.7919567 -0.354496 0.4971289 0.9364889 0.348966 0.03480315 0.1128467 -0.6574906 0.7449643 0.09523922 0.4391067 0.8933727 -0.3653746 0.7116679 0.6000252 -0.7310292 -0.3567223 0.5816748 0.08259904 0.08614969 0.9928523 0.7233927 0.09003806 0.684541 -0.315836 0.02122694 0.9485764 -0.6269348 0.7781359 0.03817462 -0.0787568 0.2580226 0.9629236 0.6655089 0.2485366 0.7037951 0.6300948 0.2270306 0.7425885 -0.1227956 -0.4420109 0.8885648 -0.7543752 -0.3003951 0.5836787 0.5953509 -0.7909313 0.1413684 0.1264265 -0.5427289 0.8303384 0.216117 -0.3598924 0.9076183 0.4982113 0.183102 0.8475018 0.6584408 0.2686287 0.7030608 -0.2181714 0.3240447 0.9205413 -0.1863191 0.2519129 0.9496448 0.6290827 0.2269132 0.743482 0.7602478 -0.5883681 0.275402 0.9392603 0.3418703 0.03024947 0.9364461 0.3491073 0.03453809 0.7272617 0.684432 0.05141216 -0.5182954 -0.1764461 0.8368015 -0.7928649 -0.3031215 0.5286612 -0.01842063 -0.1147893 0.9932191 0.07276278 -0.7032886 0.707171 0.1881269 0.07562881 0.9792286 0.1502827 0.05278557 0.9872329 -0.3742257 0.4824101 0.7919821 -0.948427 0.3136627 0.04584896 0.207809 -0.3451695 0.9152451 -0.5037223 -0.2402563 0.8297837 0.4305953 -0.8984956 -0.08540201 -0.6134655 -0.5357966 0.580157 -0.8858574 0.462745 0.03352177 -0.8319866 0.552989 0.04473811 -0.5544027 -0.6833537 0.4750427 -0.01279044 -0.6132572 0.7897799 0.5374444 -0.6356745 0.5541403 0.04261362 -0.01220852 0.9990171 -0.3632276 0.4083473 0.8374475 -0.6734547 -0.148155 0.7242299 0.2249947 0.9736018 0.03843164 -0.326003 -0.6471047 0.6891862 -0.6825327 -0.2598527 0.6831001 -0.5592997 0.2555529 0.7885916 0.5408319 -0.7217062 0.4320198 0.4386865 -0.6540967 0.6162075 0.1258166 0.008743643 0.9920151 0.6493079 0.2759067 0.7087135 -0.5024645 -0.1846025 0.8446605 -0.5432482 -0.7234922 0.4259584 0.1041095 -0.3146476 0.9434819 0.9480904 -0.306294 0.08549082 0.8385614 -0.5413645 0.06115168 -0.05261373 0.3438977 0.937532 0.6593255 0.2461569 0.7104201 0.3285054 0.1214414 0.9366623 -0.7547097 -0.2615192 0.601682 -0.7044267 -0.2258582 0.6728828 0.8569266 -0.5143624 0.03328877 0.1128975 -0.128746 0.9852303 0.8937452 -0.3590987 0.2688266 0.4590851 0.1670928 0.8725371 0.4594765 0.1672785 0.8722954 0.1862854 0.6534198 0.7337169 -0.1716197 -0.01403999 0.9850633 -0.01362603 -0.8486123 0.52884 -0.193301 -0.9806507 0.03096634 -0.2411695 -0.9694018 0.04580003 0.8238942 -0.5637727 0.05795723 -0.7512347 0.2311144 0.6182497 0.670423 0.2507166 0.6983368 0.6358605 0.230499 0.736581 0.5553764 0.459934 0.6928332 -0.0957058 -0.01919293 0.9952247 0.8294996 -0.5566422 0.04560744 -0.165217 -0.3077825 0.9370024 0.4618598 0.1688845 0.8707259 -0.02041554 0.5286255 0.8486096 0.5317526 0.3474545 0.7723436 -0.769625 -0.1658576 0.6165782 -0.2237368 -0.9741139 0.03231328 0.9463718 -0.3122087 0.08310347 0.1608259 0.1086955 0.9809793 -0.7422769 0.2442266 0.624002 0.8266731 -0.5614441 0.03731322 -0.4867743 0.2805448 0.8272517 0.9255981 0.2854284 0.2485939 -0.3847482 -0.1635 0.9084255 0.2278521 0.9353789 0.270462 -0.6465541 -0.1533833 0.7472893 -0.7843114 -0.6200821 0.01881384 0.2142323 0.1177748 0.9696565 0.7493102 0.2818338 0.5992528 -0.3271826 -0.1203442 0.9372667 0.7315275 0.2695015 0.6262879 -0.2450002 0.8902536 0.3839578 -0.286203 -0.5623199 0.775812 -0.6649653 -0.2494385 0.7039898 -0.6418109 -0.234893 0.7300029 -0.2562443 -0.5461655 0.7975226 0.7469229 0.2931351 0.5968066 -0.05671739 0.9534084 0.2963036 -0.899025 0.2160199 0.3809064 -0.4684459 -0.1700443 0.8669737 -0.4739611 -0.1725468 0.8634748 0.009907603 -0.5296843 0.848137 0.2058404 0.1173655 0.9715221 0.203382 0.9784179 0.0365262 -0.8251984 0.5618379 0.0581873 -0.5156911 0.05081474 0.8552665 0.788532 -0.6016185 0.127564 -0.2558598 0.6253775 0.737183 -0.9642907 0.256268 0.0668587 -0.589621 -0.6442573 0.4871136 0.7050601 0.2955092 0.644643 0.4078364 0.9130233 0.007621765 0.5361388 0.6782928 0.5024681 -0.1536253 0.1688345 0.9735987 -0.7167868 -0.1086518 0.6887754 0.02440792 -0.02105295 0.9994804 0.6566981 0.06484907 0.7513602 0.03376835 -0.8750422 0.4828675 -0.2530782 -0.9664566 0.04374158 0.8330609 -0.5498873 0.06027913 -0.9868397 0.1095653 0.1189244 -0.9252871 -0.07585299 -0.3716048 0.2244811 -0.5811992 0.7821867 -0.02001416 0.839116 0.5435844 -0.7090733 0.3603994 0.6060755 -0.7041832 -0.4780511 -0.5249698 -0.442754 -0.6780031 0.5867544 -0.09638673 -0.9912202 0.09051138 -0.4090946 -0.9113451 0.04573738 -0.4336678 -0.6346002 0.6396991 -0.2921119 -0.09063261 0.95208 -0.3610806 -0.1152422 0.9253865 -0.5486007 0.8021023 0.235943 -0.830915 0.5552359 0.0359652 -0.2961611 0.7630176 0.5745372 0.1249279 0.7031204 0.7000105 0.5909171 0.2208169 0.7759234 -0.1442569 -0.6583126 0.7387927 -0.2657229 0.5114763 -0.8171801 -0.2321943 0.5868483 0.7756899 -0.007016241 0.01334214 0.9998865 0.658546 0.2470515 0.7108324 0.6373275 0.2326373 0.7346385 0.5703577 -0.3966975 0.7192518 0.6048638 -0.4006678 0.6881898 -0.1667377 -0.7929931 0.5859699 -0.4961651 0.3801131 0.7805987 -0.2306022 0.5820416 0.7797758 -0.2818064 0.807004 0.5189699 -0.002826154 0.001417815 0.999995 0.1323216 0.6995816 0.7021942 0.5887799 -0.4180694 0.6917777 0.2464053 -0.6405879 0.7272769 0.2736253 -0.7550798 0.5958052 -0.1664744 -0.7918567 0.5875794 -0.1001228 -0.6837723 0.7227938 -0.6382402 -0.2331507 0.7336826 -0.495932 0.3806703 0.7804753 -0.581256 0.3962665 0.7107141 -0.2421985 0.6847493 0.6873561 0.6542388 0.2433861 0.7160552 0.6437633 0.2362613 0.7278389 0.5758695 -0.388711 0.7192206 0.5835369 -0.3896327 0.7125105 -0.1407394 -0.7142544 0.6855897 -0.1432561 -0.6986636 0.7009615 -0.6569684 -0.2442725 0.7132486 -0.5950075 0.4859676 0.6401575 -0.2024745 0.5737899 0.7935801 0.1542609 0.67903 0.71772 0.65419 0.2436588 0.716007 0.5830228 -0.3910979 0.7121285 0.2469923 -0.627444 0.7384504 0.2718082 -0.7256884 0.6320574 -0.1162038 -0.6846402 0.7195586 -0.637492 -0.2327609 0.7344565 -0.5831959 0.3905928 0.7122638 -0.1793312 0.487048 0.8547658 -0.2584772 0.645004 0.719138 0.1447249 0.7342922 0.6632268 0.1518846 0.6939157 0.7038552 0.6569628 0.2446596 0.7131211 -0.6542478 -0.2433913 0.716045 -0.6486544 -0.2395806 0.722391 -0.5831975 0.3905956 0.7122611 -0.2368909 0.6362376 0.7342237 -0.1550029 0.6793031 -0.7173016 0.1747199 0.64217 0.7463851 0.5830478 -0.3910184 0.7121517 0.1803326 -0.5161063 0.8373259 0.2835198 -0.7264677 0.6259881 -0.1490247 -0.6792306 0.7186359 -0.6542566 -0.2433922 0.7160367 -0.5629604 0.4035177 0.721283 -0.198429 0.5767774 0.7924353 0.1855376 0.6822421 0.7071927 0.1865562 0.6758928 0.7129977 0.6416783 0.2349216 0.7301102 0.716059 -0.4843959 0.5026133 0.5264734 -0.4373023 0.7291039 0.2223714 -0.6364288 0.7385861 0.1863375 0.6772485 0.7117673 0.6542197 0.2436791 0.7159729 0.641577 0.2350744 0.73015 0.5758621 -0.3887049 0.7192298 0.2454588 -0.6261797 0.7400331 -0.5890448 0.4762466 0.6528518 -0.542688 0.3995414 0.738821 -0.1984531 0.5768345 0.7923878 0.6419667 0.235342 0.7297212 0.575869 -0.3887032 0.7192252 0.2682235 -0.7163394 0.6441382 -0.1451061 -0.7151991 0.6836917 -0.5273771 0.3801688 0.7598323 -0.583225 0.3905973 0.7122376 -0.2306111 0.5820924 0.7797353 -0.2818068 0.807032 0.5189262 -0.002826094 0.001416683 0.999995 0.1323291 0.6995934 0.7021811 0.7272212 -0.4919427 0.4786877 0.2345567 -0.6216678 0.7473369 -0.10101 -0.6832608 0.723154 -0.654148 -0.2439292 0.7159532 -0.6382596 -0.2331581 0.7336634 -0.4958357 0.3806722 0.7805356 -0.5812442 0.3962876 0.7107118 -0.2279331 0.6900644 0.6869189 0.08511912 0.7241662 0.6843523 0.6437938 0.2362746 0.7278076 0.5758776 -0.3887231 0.7192075 0.2454786 -0.6262242 0.7399889 0.2681878 -0.7164301 0.6440522 -0.1407417 -0.7143051 0.6855363 -0.1858069 -0.9809293 0.05703955 -0.2069299 -0.9765658 0.05915498 0.5206935 0.8489191 0.09063571 -0.5312736 0.8452404 0.05759364 -0.9501446 -0.308892 0.04255837 -0.9527192 -0.299233 0.05278146 0.2822691 -0.9592593 0.01206922 -0.559236 -0.8274055 0.05153095 0.5087418 0.8560754 0.09119689 0.1786565 0.982298 0.05632585 -0.3420205 0.9396925 0 -0.3420201 0.9396927 2.43267e-6 0.820816 -0.5688753 0.05140161 -0.9418333 -0.3321784 0.05106568 0.1180216 0.989076 0.08831614 0.9059809 -0.4040541 0.1262503 0.9517707 0.3047351 0.03562623 -0.518442 -0.8502838 0.09075015 -0.1859313 -0.9809065 0.0570268 -0.938713 -0.3416642 0.04564422 -0.9387131 -0.3416647 0.04563987 -0.9387057 -0.3416833 0.04565334 0.7978298 -0.6010804 0.04658508 0.9463158 0.3200736 0.04515856 -0.9387066 -0.3416809 0.04565435 0.2728047 0.9604393 0.05598253 0.8970741 -0.4224954 0.129444 0.9459691 0.3223329 0.03527325 0.3054336 0.9516937 0.03145599 0.9387423 0.3415817 0.04565984 -0.8044295 0.5921619 0.04730361 0.9387127 0.3416652 0.0456435 0.2526961 0.9667231 0.03989094 0.9391196 0.341812 0.03491503 0.9341568 0.3540313 0.04486417 0.9387801 0.3414828 0.04562282 0.9387004 0.3416792 0.04579246 0.8881148 -0.4582106 0.03598904 0.8053798 -0.5904567 0.05219519 0.864259 0.4990175 0.06354355 0.6073967 0.792438 -0.05578082 -0.3782758 0.9120901 -0.1581118 -0.9580366 -0.2820252 -0.05126249 0.5244933 -0.8495734 -0.05596464 0.8644114 -0.4970923 -0.07544654 0.983444 0.1733534 -0.05278784 0.6608501 -0.7462869 0.0795812 -0.6263817 0.7736485 0.09546726 0.6124683 -0.4693614 0.636068 -0.2070629 -0.2536758 0.9448671 -0.4850951 0.1489067 0.8616899 -0.1287026 0.1180298 0.9846343 0.1202056 0.3102605 0.9430213 0.2300084 0.3147491 0.920885 0.5014224 0.1793377 0.8464123 0.8300255 -0.272055 0.4868716 -0.1737263 -0.4194744 0.8909885 -0.240334 -0.3559948 0.9030545 -0.7196967 -0.5024446 0.4791516 -0.5620138 -0.1797729 0.8073552 -0.5665547 -0.05999797 0.821837 -0.491794 0.04855829 0.8693565 -0.163204 0.6472721 0.7445828 0.07954394 0.5080901 0.8576231 0.1276519 0.3198149 0.9388415 0.2301019 0.357403 0.9051609 0.3794043 0.3889888 0.839488 0.5436545 0.3716732 0.7525284 0.1796237 -0.1179715 0.9766361 0.292323 -0.4209132 0.858708 0 4.07348e-7 -1 -1.50519e-6 -7.32435e-7 -1 -2.51157e-7 3.81611e-7 -1 0.9854847 -0.00921154 0.1695141 -0.002710223 -0.999544 -0.03007477 -0.003105938 -0.9994997 -0.03147876 -0.865366 0.5010707 0.008360385 -0.8612278 0.5082192 0 -0.001960456 0.9999977 -0.001020669 0.8828785 -0.09355902 0.4601874 -0.9601325 0.1603543 0.2289804 -0.05842852 -0.9922719 0.1094661 -0.3194513 0.9476028 0 -0.3194507 -0.9476029 0 -0.3194507 0.9476029 0 -0.3194509 -0.9476028 0 0.308775 0.9511351 0 0.3087762 0.9511348 0 0.3087748 -0.9511352 0 0.810098 -0.09331995 0.5788201 -0.6388089 -0.7693656 0 0 -1 0 0.7595694 0.6442611 -0.08934277 -0.9996631 -0.00363326 0.02570319 0.6876867 0.7257279 -0.02015268 -0.0659886 0.9634715 -0.2595538 -0.3758494 0.7620283 0.5273046 -0.9852168 -0.1713122 0 0.05106365 -0.9986954 0 -0.55475 -0.3827452 0.7387548 0.8256218 0.564224 0 0.9697348 0.08469778 0.2289996 0.951698 0.1044004 0.2887414 0.09850096 0.9599016 0.2624626 -0.5617297 -0.3198475 0.7629923 -0.6297905 0.5452687 -0.5532142 0.9999655 0.007742166 0.003038644 0.9998655 -0.001178205 -0.0163604 -0.004314482 -0.999928 -0.01120579 0.5434514 -0.03223496 -0.8388215 -0.00688678 0.01890939 0.9997975 -0.001957774 -0.001092493 0.9999976 -0.004117667 0.005785346 0.9999749 0.001147449 -0.003118336 0.9999946 0 0 1 -0.02424734 0.05783784 0.9980315 -0.105999 0.2349188 0.9662182 7.51777e-5 -7.24206e-5 1 -0.01371437 0.1118419 0.9936314 -2.28665e-7 0 1 -0.02437126 0.05285465 0.9983048 -4.22232e-6 1.7575e-6 1 0.004834651 -0.007842838 0.9999576 0.004088342 -0.008238613 0.9999578 9.24069e-4 0.004921078 0.9999875 0.002651453 -0.008755624 0.9999582 -0.101332 0.3066262 0.9464207 0.02703171 -0.06000548 0.997832 8.41727e-4 -0.003145337 0.9999947 1.70921e-5 -0.003316819 0.9999945 2.99909e-5 1.00253e-4 1 8.18387e-6 3.72932e-5 1 0 0 1 4.63045e-7 0 1 -4.63052e-7 0 1 0.03466451 0.1152713 0.9927291 1.57781e-5 -8.58311e-6 1 -2.07508e-6 -2.5329e-6 1 -0.001744091 -8.09461e-4 0.9999982 -0.001718461 -6.06987e-4 0.9999984 0.482414 -0.8560719 0.1855198 -7.79286e-4 -0.01135671 0.9999352 2.96473e-4 -0.003987908 0.999992 0.1031753 -0.2794841 0.9545907 0.001418352 0.00167936 0.9999977 7.58932e-7 0 1 -0.05283206 -0.1474984 0.9876503 0.002058029 0 0.999998 -0.01340317 5.43902e-4 0.9999101 -0.0130124 -0.002629756 0.9999119 -0.001532137 -0.001273095 0.9999981 0 0 1 0 0 1 -0.004752576 0.003264963 0.9999834 -0.004180252 -0.004180014 0.9999826 -0.004099488 0.06803375 0.9976747 -0.002359747 0.001598536 0.999996 0.0508868 -0.04273104 0.9977899 0.02099239 -0.02345257 0.9995046 -4.63139e-7 0 1 -0.03264355 -0.0760467 0.9965698 0.003657281 -0.004112303 0.9999849 0.4817873 0.8344832 0.2674306 -8.1898e-4 -0.001418471 0.9999987 -0.00114727 -1.00217e-4 0.9999994 -0.001173019 0 0.9999994 -5.87974e-4 -0.001666367 0.9999985 -1.28017e-4 -5.09688e-6 1 4.27853e-5 -8.99367e-5 1 -1.3849e-6 -2.8993e-6 1 7.84214e-7 0 1 -0.003639161 -0.003056049 0.9999888 -8.85557e-4 0.007762432 0.9999696 0.04356843 0.08627194 0.9953186 1.75393e-5 3.38682e-5 1 -0.05115884 -0.06454902 0.9966024 -0.007600426 0.005149781 0.9999579 0.01594269 0.10123 0.9947353 0.001307547 0.001309454 0.9999984 -0.04167866 -0.04173988 0.9982588 -0.01748359 0.02690225 0.9994853 0.05741316 0.04269295 0.9974373 -0.05012065 -0.09885907 0.9938384 3.19479e-4 0.00379616 0.9999928 0.001134335 -0.00172019 0.9999979 -0.04455089 0.2390125 0.969994 -0.00478661 0.003310024 0.9999831 -0.007139325 0.01580601 0.9998497 0.02391666 -0.04623162 0.9986444 0.01042425 -0.0180726 0.9997823 0.006767451 -0.01554268 0.9998564 -0.01157718 0.0229761 0.999669 0.06428569 -0.0414859 0.997069 -8.48227e-4 -0.008039653 0.9999674 -0.009883821 -0.01520794 0.9998356 -0.002479135 0.009258925 0.9999541 -5.80663e-7 -1.14305e-5 1 -0.003965735 -0.004614114 0.9999815 0.02492189 0.1218886 0.9922308 6.77653e-4 -3.26833e-5 0.9999998 -8.77021e-5 6.33112e-5 1 0.1311796 -0.001871645 0.9913569 -5.17085e-4 -0.00708723 0.9999748 -1.31489e-4 5.7429e-4 0.9999999 -0.04728025 0.1182346 0.9918594 0.06334143 -0.04081827 0.9971568 1.96645e-5 -4.54579e-5 1 0 0 1 -0.002639293 -0.03336095 0.9994399 -0.01727652 -0.04695141 0.9987478 0.173561 0.4716785 0.8645207 -0.03641951 -0.117937 0.9923531 -0.001988053 -0.002639651 0.9999946 0.01522201 0.06082588 0.9980323 0.0192309 -0.02194917 0.9995741 -0.01557672 -0.03814709 0.9991508 -0.008094429 0.008582651 0.9999305 -0.01320624 4.20486e-4 0.9999128 -8.53266e-7 0 1 0 0 1 1.29919e-7 0 1 0 0 1 -0.002247393 0.001777529 0.9999959 -0.001119971 -7.65012e-4 0.9999991 2.30529e-5 -1.68979e-4 1 1.19438e-5 5.39259e-5 1 -4.93936e-7 0 1 0.001981258 -6.76367e-5 0.999998 0 1.9114e-5 1 -1.27655e-5 0 1 1.80505e-7 0 1 1.0993e-5 2.63022e-4 1 -3.63773e-5 -4.35637e-5 1 -2.98453e-5 0 1 -5.22198e-6 -2.70545e-4 1 0 5.77262e-6 1 4.51522e-7 0 -1 2.76112e-5 4.48146e-4 -1 4.93344e-6 -1.4107e-5 -1 -5.95632e-6 5.28112e-5 -1 -5.92645e-6 -2.87706e-6 -1 3.92034e-6 -7.13348e-6 -1 0 0 -1 4.85569e-5 1.74005e-6 -1 -4.444e-6 -6.548e-6 -1 1.73882e-6 5.29514e-7 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -3.11104e-7 0 -1 4.22561e-7 0 -1 -3.68024e-5 -2.75042e-5 -1 -2.47689e-6 1.52526e-5 -1 -8.06826e-5 -1.09141e-4 -1 0 0 -1 0 0 -1 0 0 -1 -1.36255e-4 8.20387e-5 -1 0.02208638 -0.05564928 -0.9982061 -8.42894e-5 -2.38603e-5 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 1.011e-6 -4.0206e-6 -1 4.61033e-7 1.29927e-7 -1 1.97888e-5 6.23382e-5 -1 0 7.00159e-7 -1 1.60275e-7 0 -1 -2.99229e-6 1.01872e-5 -1 -6.35203e-6 1.02594e-5 -1 4.60228e-6 -1.22365e-5 -1 -8.73736e-5 -1.67884e-4 -1 1.25951e-5 8.73715e-5 -1 1.3335e-4 2.84123e-4 -1 0 0 -1 -7.99006e-5 5.95551e-5 -1 4.25869e-6 3.95081e-5 -1 2.35067e-6 -2.63425e-5 -1 -2.64874e-6 1.47525e-7 -1 -1.00749e-6 -4.62487e-6 -1 3.63754e-7 -3.53089e-7 -1 1.43858e-7 0 -1 0 0 -1 -5.24892e-6 -1.0306e-5 -1 2.86323e-6 5.36679e-6 -1 9.3979e-7 1.87842e-6 -1 -1.16538e-5 7.65554e-6 -1 0 0 -1 0 0 -1 1.89278e-6 -1.34003e-5 -1 -1.92016e-6 -7.0179e-7 -1 1.37031e-5 7.10313e-6 -1 2.736e-7 4.68881e-7 -1 7.42438e-4 -0.001132726 -0.9999992 -1.22845e-6 6.39384e-6 -1 -2.15932e-6 -1.24402e-6 -1 6.429e-6 -7.55859e-6 -1 0 0 -1 5.47965e-7 0 -1 0 0 -1 0 0 -1 -7.51833e-5 4.51132e-4 -1 1.3628e-5 3.89587e-5 -1 -6.80272e-6 1.03402e-5 -1 0 0 -1 -5.19673e-6 1.53891e-5 -1 3.1369e-4 5.62902e-4 -0.9999999 -3.02979e-5 -3.07309e-5 -1 -3.74709e-6 0 -1 -6.35447e-6 0 -1 2.93377e-6 0 -1 -6.48745e-6 0 -1 0 0 -1 0 0 -1 5.44893e-5 3.11845e-5 -1 -1.52639e-5 2.4612e-5 -1 7.0281e-5 -1.45354e-4 -1 0.4048521 -0.7211499 0.5621724 -0.9503512 0.2276699 -0.2121296 0.944158 -0.329493 0 0.6318241 -0.4781114 -0.6100884 0.6624134 -0.6046242 -0.44231 0.01653563 -0.7260754 -0.6874163 -0.3638194 -0.9074099 0.2103394 -0.8141807 -0.3264356 -0.4801558 -0.9102754 0.4140033 2.01442e-6 -0.3196465 -0.944313 0.07809793 0.6643017 0.4496917 0.5970602 0.8102651 0.5814429 -0.07344835 0.8034496 0.2455962 0.542357 0.004620969 0.9965564 0.08278918 -0.4700866 0.02786684 0.8821803 -0.8278794 -0.5315816 -0.1789879 0.9999284 -0.004411935 -0.01111859 0 0.9999996 -9.51842e-4 -0.3203336 -0.9473048 0 -0.3203384 -0.9473032 1.86245e-4 -0.437959 -0.8953856 -0.08047759 -0.7070385 -0.6836458 0.1809003 -0.8051791 -0.5854691 -0.09440696 -0.9851266 -0.1694737 -0.02836257 -0.9885671 -0.1126171 -0.1002634 -0.1371273 0.1177466 0.9835303 8.43097e-4 -0.8143925 -0.5803139 -0.5788587 0.5077511 0.6380528 -0.9723009 0.2331933 -0.01587367 -0.1924999 0.9485152 0.2515209 -2.37684e-4 -0.9999988 -0.001575291 1.77398e-7 -1 0 0.9999972 0.002363502 0 -4.45297e-7 1 0 -0.3116596 -0.8930647 0.3245055 -0.9102754 -0.4140033 0 -0.6912937 0.6912947 0.2102968 -0.3506372 0.8745099 0.3350909 0.01997339 0.8769733 -0.4801238 0.3713127 0.8163998 -0.4422876 0.8468117 0.2955355 -0.4422318 -0.9877557 -0.1560085 0 0.1147556 0.5896387 -0.7994732 -0.320477 0.9472563 0 0.9994983 0 0.03167426 0.9999698 -0.007766842 0 0.4913538 -0.5178464 -0.7002905 -0.6447284 0.1107215 0.7563505 -0.9999751 -1.36669e-4 0.007059454 -1 -2.00036e-6 0 -0.9635779 0.2674279 0 -0.9632626 0.1979686 0.1814764 -0.4507044 0.8926734 0 -0.3203343 0.9473047 4.93488e-5 -1.65876e-7 0 1 0.2588201 0.9659256 0 0.2588202 0.9659255 0 0.9070728 0.420974 0 0.4209716 -0.9070739 0 -0.3267825 -0.9450997 0 -0.9697502 -0.2341657 0.06892889 0.9070728 -0.420974 0 -0.9837849 -0.1793527 0 -0.7071062 0.7071074 0 0.3143262 0.949065 -0.02178639 -0.3150304 -0.9489301 0.0169593 0.2087205 0.952327 0.2225068 0.7270879 0.6498636 -0.2214059 0.9290914 0.2953979 0.2225521 -0.912004 -0.28992 0.2901641 0.8685703 -0.400161 -0.2923302 -0.1993359 0.954585 -0.2214336 0.6397773 0.7680264 -0.02864474 0.9757244 0.1885438 -0.1114144 0 -0.9750173 0.2221294 -0.959105 -0.2827364 0.01334297 -0.6427173 0.7569981 0.1177651 0.2587779 -0.9657687 0.01802736 0.2345882 0.9714941 0.03416985 0.9570565 -0.05503082 0.2846302 0 -0.9520231 0.3060265 -0.9484078 -0.296133 -0.11326 0.3439441 0.9255211 0.1584709 0.4317468 -0.9012858 -0.0357601 -0.5207058 -0.8482605 -0.09653854 0.7071022 0.7071114 0 0.9493615 0.01133036 0.3139816 0.1874904 -0.9822609 -0.003301858 0.8413038 -0.5198335 -0.1482608 -0.3662653 -0.9170426 -0.1577424 -0.9804507 -0.1775788 0.0847488 0.4845486 0.8728315 -0.05812036 0.8595417 -0.3960754 -0.3229742 -0.9818528 -0.053469 0.1819509 -0.8947727 0.361912 -0.261537 0.171235 0.9852303 1.72896e-4 -0.8890707 0.3615821 0.2807344 0.3673607 0.8959373 0.2496852 0.5661909 -0.8054777 0.1750248 -0.08895987 -0.9960352 0 -0.8872482 0.3637917 0.2836305 -0.3327771 0.9430023 -0.002484381 -0.03180629 -0.9533038 0.3003336 -0.9539853 -0.03570216 0.2977206 0.818694 -0.4803637 0.3146286 0.4751952 -0.8727362 -0.1118975 -0.8613233 -0.5024712 -0.07513308 -0.8167367 0.5229547 -0.2438433 0.4409301 0.8471016 0.2966476 0.9321196 0.3618566 -0.01459568 0.9703013 -0.1869368 0.1535254 0.9436482 -0.2528414 0.2135401 0.4760743 -0.8779724 -0.05017864 -0.9932367 -0.1161082 0 0.9617255 0.2249961 0.1564003 -0.7054575 -0.7054605 0.06823033 0.3674814 0.929619 0.02767723 0.2563578 -0.9567859 0.1372644 -0.5168119 -0.8526114 -0.07719719 -0.9302587 -0.3350303 -0.1495777 -0.5185964 0.8042985 0.2901064 -0.7004145 -0.7004126 0.1372656 -0.987941 -0.1473672 0.04749161 -0.7588979 0.6468941 0.07484632 -0.008063137 0.9986211 -0.05187624 0.9458763 -0.00467503 0.3244938 -0.6810136 -0.7237471 -0.1114028 -0.5724646 0.8144265 0.09483569 0.01618009 -0.999764 0.01449918 -0.6792325 -0.7250491 -0.1137853 -0.9748833 0.1828484 -0.1271574 0.9828352 0.156827 0.09716147 0.05489808 0.9793057 0.194799 -0.05551874 -0.9542834 -0.2937021 -0.1930739 0.852676 0.4854544 -0.1145567 -0.9905297 0.07568293 0.4587499 0.8690608 0.1851541 -0.5214356 -0.8513824 -0.05703723 -0.9401297 -0.2519176 0.2295514 -0.8532746 0.5157652 -0.07686841 -0.5135389 0.8546782 -0.07617723 0.7071133 0.7071003 -2.60429e-6 0.9567804 0.2563803 0.13726 -0.7034206 0.7034217 -0.1019676 0.8860024 -0.4598416 -0.05954527 0.6220165 -0.7809243 0.05703246 -0.154792 -0.9766505 -0.1489736 -0.7973122 -0.5910239 -0.1224099 -0.4789056 0.8559785 0.1948086 0.8144271 0.5724633 0.09483814 0.178107 -0.9769389 0.1177644 0.2563744 0.9567797 0.1372768 0.3324213 -0.9431195 -0.004672884 -0.6937043 0.6937133 0.1937428 -0.2588169 0.9659265 0 0.700412 0.7004141 0.1372706 0.9972209 0.04477703 -0.05954605 0.8374692 -0.4538391 0.3044267 0.5264145 -0.8500924 -0.01519566 0.2584131 -0.9644195 -0.05583626 -0.3588773 -0.9153111 0.1827915 -0.9838086 -0.1789957 0.009012162 0.6648728 0.7084378 -0.2367704 0.9908538 -0.1179977 -0.0654627 -0.4642783 -0.8771432 0.1227419 -0.03924787 0.9550995 0.2936742 -0.01669442 -0.9909452 -0.1332247 -0.9253091 0.3553557 0.1323841 -0.3917543 0.9175516 -0.06802612 -0.9186924 -0.3949739 0 -0.5253444 -0.5366738 -0.6602989 0.3525727 -0.8448229 -0.402451 0.8448176 -0.3525885 -0.4024483 0.6712269 0.4828444 -0.5624196 0.3731445 0.8678945 0.3279063 0.7070975 -0.7071161 4.37015e-6 0.9999857 -0.005366504 -6.17967e-6 0.3769524 0.152615 -0.913573 0.6265658 0.6133148 -0.4808954 -0.5 -0.8660254 0 0.5449314 -0.8384808 -1.33352e-4 0.2358449 -0.9717582 -0.007954001 0.2130022 -0.9568722 0.1975494 0.1955607 -0.9798393 -0.04087859 0.1707584 -0.9757003 0.1372973 0.1437529 -0.9895963 -0.005858898 0.113085 -0.9930174 -0.03358918 -0.009968042 -0.9971737 0.07446724 -0.1970108 -0.9804014 0 -0.207116 -0.9523341 -0.2239707 -0.2614875 -0.9598596 0.1014585 -0.2968378 -0.9539659 -0.04285514 -0.3048408 -0.9520727 0.0250948 0.9688165 -0.2477796 0 0.9921734 -0.1248686 0 0.9980415 -0.06255596 0 0.9980415 0.06255614 0 0.9824191 -0.1866893 0 0.9980416 0.06255459 0 0 1 0 -0.1391069 0.343572 -0.9287667 0.9447667 0.005056202 0.3277046 0.7318779 -0.2963101 -0.613641 0.377632 0.5868368 -0.7162519 0.4553922 -0.2776842 -0.845878 0.9739739 -0.02325153 0.2254649 0.3420135 0.9396951 0 -0.6603327 0.746692 -0.08007496 -0.2963454 0.9526188 0.06853377 -0.2215591 0.9584682 0.1795842 -0.1501776 0.9839305 -0.09657937 0.006895601 0.995468 -0.09484767 0.0272758 0.9181742 -0.3952371 0.1045505 0.9911361 -0.08196526 0.2222903 0.9727767 0.06551784 0.2445043 0.9680067 -0.05639714 0.5449312 0.8384809 0 -0.3216921 0.9098787 -0.2619829 -0.3988627 0.9170107 0 -0.3203347 0.9473046 0 -0.3203337 0.9473049 0 0.9621737 -0.2724372 0 0.9770604 -0.2129626 0 0.9882743 -0.1526896 0 0.9957731 -0.09184747 0 0.9995301 0.03065174 0 0.9882737 0.152693 0 0.9621738 0.2724367 0 0.9623253 0.2718491 -0.005292654 0.9882737 -0.1526927 0 0.9957733 -0.09184569 0 0.9995301 -0.03065168 0 0.9995301 0.03065341 0 0.9770604 0.2129626 0 0.453427 -0.8912935 0 0.3883905 -0.9025259 -0.1860109 0.3420208 -0.9396905 -0.001868426 0.342068 -0.9396753 0 -0.6848632 -0.7284823 -0.01660978 -0.139832 -0.9898424 0.02567106 -0.1649771 -0.9855212 -0.03912252 -0.1000161 -0.9946495 0.02587121 -0.06088447 -0.9981037 0.009058833 0.006413638 -0.9973184 0.07290458 0.05449759 -0.9910496 0.1218635 0.08364772 -0.9964522 -0.009281158 0.1270202 -0.9907575 0.04759752 0.172576 -0.9848866 0.01469939 0.2194114 -0.9737848 0.0600152 0.5454211 -0.8381617 9.30392e-4 0.5445638 -0.8387123 -0.003467261 -0.4999706 -0.8660424 -6.70477e-5 -0.4951475 -0.8640695 0.09062582 -0.4592101 -0.8883234 -0.002776682 -0.3684253 -0.9275666 -0.06231552 -0.368169 0.9276817 -0.06211507 -0.5000346 0.8660055 -5.21376e-5 -0.499364 0.8651263 0.04682123 -0.4984676 0.8669084 -1.52364e-4 0.2034447 0.9628274 0.1776903 0.09752947 0.9901354 0.1005975 0.006527185 0.9979387 -0.06384319 -0.1188452 0.975838 -0.1833475 -0.1606383 0.9552848 0.2482466 -0.267152 0.9628257 -0.03995728 -0.6836476 0.7298122 -3.90071e-4 -0.6822549 0.7310628 -0.008694052 0.3420209 0.9396924 0 0.3420193 0.9396929 6.65097e-5 0.7587229 0.6011587 0.2508943 0.7602071 0.6009019 0.246986 5.8574e-4 0 0.9999998 8.38322e-4 5.9953e-4 0.9999995 6.62003e-6 3.08316e-4 1 9.91256e-5 5.96679e-4 0.9999998 -4.37017e-4 1.75369e-4 0.9999999 1.74109e-4 5.79201e-4 0.9999999 -3.10031e-7 0 1 -5.3811e-4 0.001355469 0.9999989 -2.74811e-4 -4.8274e-4 1 1.97312e-7 0 1 -3.58759e-6 1.04106e-4 1 2.12318e-5 1.66593e-4 1 -7.12929e-6 -5.65652e-5 1 2.42389e-5 -1.26765e-4 1 -5.82256e-5 -5.77178e-5 1 1.94181e-5 -2.82006e-4 1 1.39052e-7 0 1 -2.50419e-4 1.07879e-4 1 -2.29121e-4 6.51981e-4 0.9999998 7.60951e-4 0 0.9999997 1.73466e-5 2.15665e-4 1 -3.00444e-4 -2.88597e-4 1 6.92286e-4 3.70316e-6 0.9999998 4.77951e-4 4.77564e-4 0.9999998 5.3335e-7 0 1 0.002193152 -2.92585e-4 0.9999976 0.001160562 -0.001098215 0.9999988 0.007581651 -0.004481196 0.9999613 0.001556098 -0.007589995 0.9999701 -0.001680254 -0.006138265 0.9999797 5.38787e-5 2.89213e-4 1 1.77276e-4 3.63957e-4 1 -5.87837e-7 0 1 1.17678e-6 0 1 -4.79078e-4 4.49129e-4 0.9999999 1.21749e-4 3.37282e-4 1 -3.80364e-4 -9.3852e-4 0.9999995 -5.76893e-6 1.54535e-5 1 1.37254e-4 3.93948e-4 1 -9.31924e-5 -2.4192e-4 1 -1.50562e-6 2.00987e-4 1 2.62643e-4 6.82908e-4 0.9999998 7.71763e-6 5.9909e-5 1 -1.62094e-4 -5.11294e-4 1 8.08902e-5 -3.24267e-4 1 0 0 1 -2.54644e-5 1.45618e-4 1 2.74549e-4 -0.001649498 0.9999986 -7.05811e-4 3.81892e-4 0.9999997 -3.64129e-5 7.98776e-5 1 5.40377e-7 0 1 0 0 1 -3.61655e-6 -9.9319e-6 1 1.24012e-6 0 1 -0.00140196 -0.001402318 0.9999981 -1.0414e-4 -2.59319e-4 1 1.29759e-4 -2.85503e-4 1 0.001334726 4.08061e-4 0.9999991 0.001296758 9.30762e-4 0.9999988 -6.85266e-7 0 1 -0.03800773 -0.001859009 0.9992758 2.6418e-7 -7.75559e-7 1 3.59094e-7 0 1 -0.99379 0.004829466 0.1111668 -0.7673026 -0.6412853 0 1.47202e-4 -1 0 0.6790516 0.540526 -0.4967097 2.42521e-6 0 1 6.3835e-7 3.33395e-6 1 -1.07821e-6 -7.64992e-7 1 -0.7094937 0.7047119 0 -0.6899916 0.5964977 0.4100027 0.6781995 -0.7085297 -0.1950159 0 0 1 -0.001163721 0.00156784 0.9999981 9.73491e-4 3.3058e-4 0.9999995 -0.01254498 -0.01416635 0.999821 -6.65803e-5 -3.93983e-4 1 2.94802e-4 -3.54166e-6 1 -0.008680701 -0.01018607 0.9999105 -0.01080429 0.01395589 0.9998443 2.21453e-5 0.03606224 0.9993496 0.02187079 -0.0183227 0.9995929 -3.40321e-4 0.004577815 0.9999895 0.02045696 -0.02812004 0.9993953 -2.61633e-5 -2.85952e-6 1 1.5114e-4 -2.22323e-4 1 4.87967e-5 4.59185e-5 1 -1.4141e-6 -3.0094e-5 1 -0.01242929 0.004360854 0.9999133 -0.04145896 0.001405417 0.9991393 -0.06206744 -0.09161305 0.9938585 -2.11786e-4 -0.1444578 0.989511 -0.002009987 0.1200509 0.9927657 0.005666673 0.2142022 0.976773 0.003175914 -0.05028748 0.9987298 1.67368e-4 -0.06152945 0.9981054 -0.003130435 0.004065811 0.9999868 0.06080228 -0.0688697 0.9957711 1.51244e-7 0 1 -1.31546e-7 0 1 0 0 1 -2.01324e-6 0 1 2.95205e-7 0 1 -1.39671e-7 0 1 -5.39093e-7 0 1 0 5.05561e-7 1 -1.62062e-7 0 1 -4.13118e-7 0 1 1.59108e-6 0 1 -1.59967e-7 0 1 4.35143e-7 0 1 -2.34437e-6 -3.84254e-6 1 -2.68969e-7 0 1 1.28801e-6 0 1 8.26626e-7 -5.29034e-6 1 0.002397775 2.88413e-4 0.9999971 -1.43434e-7 0 1 3.75051e-7 0 1 1.85425e-7 0 1 0 0 1 3.53045e-7 0 1 -0.001113474 3.10341e-4 0.9999994 -1.01057e-5 2.33371e-5 1 -7.03007e-5 -0.01052796 0.9999446 3.44934e-6 4.60587e-6 1 -8.2671e-6 1.42091e-7 1 -7.18422e-6 1.94227e-6 1 1.2535e-6 0 1 -1.195e-5 -3.59403e-5 1 1.08612e-4 -1.10553e-4 -1 -3.17633e-5 -4.34717e-5 1 -2.17185e-7 -7.49516e-6 1 1.72654e-7 0 1 0.8413361 -0.5403671 -0.01253342 0.4014606 0.9051592 0.1397011 0.1074287 -0.9934426 0.03912681 0.2887696 0.9523775 0.09792482 0.9933239 -0.1152773 -0.004331409 0.9696406 -0.2145632 -0.1173028 0.9681892 -0.249763 -0.01510566 0.9919719 0.09828311 0.07957649 0.9892398 0.1452995 0.01710724 0.9993035 0.03731733 0 0.9983557 0.0447129 -0.03587257 0.9732156 0.2298124 -0.006137013 -0.7383928 -0.6523246 -0.1710224 -0.8866717 -0.4398032 0.1427817 0.987664 0.05978834 -0.1447252 -0.978611 0.2041646 -0.02525097 0.4198441 0.9008865 0.1101576 0.9627832 0.1058037 -0.2487054 -0.880852 -0.4640349 0.09365612 -0.7675461 0.286862 0.5732218 -0.01378852 0.9342359 0.3563894 0.8023128 0.5431309 0.2475948 0.1387296 -0.9901676 0.01795142 0.2976489 -0.8971263 -0.32645 0.1950903 0.9807854 0 0.6462302 0.7631427 0 -0.8041459 0.5919848 0.05388599 -0.24527 0.9694549 0 -0.8317715 0.554103 -0.03355914 1.71127e-4 0.9999998 -6.0065e-4 0.8524354 -0.5228325 0 0.5555718 -0.8314687 0 0.7950856 -0.6056609 -0.03184443 9.90553e-4 -0.9999839 0.005613923 -0.001151859 -0.9999577 -0.009121119 -0.7926592 -0.6086246 0.035604 -1.14711e-5 -6.17979e-5 -1 1.77731e-6 -4.48038e-6 -1 6.71034e-4 1.31376e-4 -0.9999998 -3.2031e-4 -4.6384e-4 -0.9999998 1.0652e-5 -3.74604e-5 -1 -1.76077e-6 7.36007e-6 -1 2.01369e-6 -1.11616e-5 -1 3.94525e-7 0 -1 0 6.12879e-7 -1 -4.51642e-4 3.25114e-4 -0.9999999 1.41012e-4 1.47216e-4 -1 3.50222e-6 -1.77974e-4 -1 -5.85328e-5 8.68819e-5 -1 2.75241e-4 -0.001871824 -0.9999982 -4.31463e-4 2.64506e-4 -1 1.97399e-4 5.88971e-4 -0.9999999 -5.35834e-4 4.08254e-4 -0.9999998 5.43044e-7 3.93577e-4 -1 1.79782e-4 1.51946e-4 -1 1.88399e-4 7.32914e-4 -0.9999997 2.18093e-5 -0.0010131 -0.9999995 6.99916e-5 4.58881e-5 -1 2.38219e-5 -8.60112e-5 -1 -2.29993e-6 4.11202e-7 -1 0 5.00532e-7 -1 -3.49437e-6 -2.45283e-6 -1 -3.21492e-6 -1.84633e-4 -1 -5.35889e-4 -4.0035e-4 -0.9999998 -2.52852e-6 -5.10931e-6 -1 -2.44695e-4 -0.001707851 -0.9999986 -9.41613e-4 0.008046865 -0.9999672 0 0 -1 -2.54957e-5 7.21441e-6 -1 -7.55203e-7 1.05308e-6 -1 6.61509e-7 -1.38321e-6 -1 -5.91661e-6 1.21634e-5 -1 -5.83562e-4 1.58225e-4 -0.9999999 4.40678e-5 2.18507e-4 -1 8.03863e-5 4.68185e-5 -1 3.17039e-4 3.1249e-4 -1 -1.57083e-4 -3.56503e-4 -1 -4.37905e-4 3.49824e-4 -1 -6.26988e-5 3.26069e-4 -1 0 -7.63316e-7 -1 0 5.66492e-7 -1 0 -6.057e-7 -1 2.17586e-6 0 -1 -4.9997e-7 0 -1 -1.21493e-6 0 -1 -1.9532e-7 0 -1 1.89237e-5 -3.88325e-5 -1 -1.70014e-7 -5.16773e-7 -1 -1.52723e-6 -7.08962e-6 -1 -3.94289e-6 -7.98006e-6 -1 2.18229e-5 -6.57098e-6 -1 -5.44388e-5 4.55392e-5 -1 -5.9259e-4 -2.47624e-4 -0.9999998 -1.19789e-4 2.09521e-4 -1 1.96149e-6 5.72309e-6 -1 1.28997e-6 -4.22252e-6 -1 -2.7098e-6 -1.00246e-5 -1 -7.39138e-7 0 -1 9.48859e-5 -1.07731e-4 -1 -2.48519e-7 0 -1 0.002157211 -0.001347303 -0.9999968 -0.003760635 -1.68454e-4 -0.9999929 -0.003280043 0.003985583 -0.9999867 -5.75655e-7 0 -1 1.93894e-4 2.51779e-4 -1 1.32508e-6 6.97994e-6 -1 -6.03616e-6 3.59187e-6 -1 -4.38802e-6 0 -1 0 0 -1 0 0 -1 -2.81747e-7 2.49499e-7 -1 -4.22776e-6 -1.0611e-4 -1 8.25665e-7 1.79999e-4 -1 4.25941e-7 0 -1 -7.9758e-6 -1.20482e-5 -1 1.80219e-6 -5.15395e-6 -1 -0.9998677 -0.01201844 0.01097327 -0.9998677 -0.01201832 0.01097327 -0.2834738 -0.9579784 0.04381906 -0.8358644 -0.5479239 0.03332221 -0.7617772 0.6423769 0.0839501 -0.7949863 0.6055889 -0.03548347 -0.9998677 0.0120185 -0.01097357 0.7617765 0.6423777 -0.08395075 1.30193e-4 -1 0 -0.9390403 -0.3438072 0 -0.3320969 -0.9432453 0 -0.5622419 -0.8029635 -0.1978231 -4.32125e-7 1 0 -0.9151423 0.387763 0.1102482 -0.9337056 0.3580419 0 0.8583332 0.5124623 0.02542525 0.3507933 0.9115716 0.2144326 0.2694761 0.9626047 -0.02783817 -0.3215323 -0.9444435 0.06814318 -0.3024398 0.9528793 0.02347922 -0.9512471 0.3066939 0.03267908 -1 -1.97887e-6 0 0.2795557 -0.9600152 -0.01481157 0.8394053 -0.5387898 0.07144635 0.999859 -0.01201802 -0.01173377 0.001152217 0.9999676 -0.007967293 0.841936 0.5345495 -0.07348966 0.8237666 0.5665429 0.02091991 -0.2249079 0.9563913 0.1863655 0.1076136 -0.9940562 0.01647889 0.3880129 0.8714873 0.2999265 0.819692 -0.4732624 -0.3226884 0.5790801 -0.79704 -0.1714455 0.7285677 -0.6849739 0 -0.9773528 0.09582233 0.1886789 -0.5062931 0.8039917 0.311873 -0.8728876 0.4664372 0.143191 -0.9225981 0.3857627 0 -0.8054806 -0.5661871 0.1750238 -0.258821 -0.9659253 0 0.5568321 0.8172362 -0.1485368 0.08856362 -0.9915454 0.09483796 0.7642929 -0.5542053 -0.3297166 0.6783204 0.7248938 0.1200441 -0.9918743 -0.1272218 0 -0.4209815 -0.9070693 0 0.08789795 0.9847204 -0.150332 -0.9891619 -0.03250235 0.1431866 -0.4209774 -0.9070712 0 0.3267793 -0.9451008 0 -0.9918751 0.1272161 0 -0.9891619 0.03249526 -0.1431878 0.3372547 -0.9027811 -0.2669188 0.3779163 0.9248464 0.04287689 -0.7071075 0.7071061 0 0.08896309 0.996035 0 0.3351019 0.9421568 0.006890475 0.9301158 0.2629913 -0.2563594 -0.967861 -0.2456817 -0.05371892 -0.767906 0.6299443 0.1161489 -0.9699717 -0.2390719 -0.04471671 0.9914506 0.1271677 -0.02922803 0.7077587 -0.6603549 0.2510157 -0.7209661 0.6728399 0.1658146 -0.9440038 0.1813485 -0.2756262 -0.2917945 0.9556151 -0.04069185 -0.9652127 0.2586273 -0.03842478 0.2563742 0.9567812 -0.1372667 0.7071127 0.7071009 2.60427e-6 0.9803026 0.1822648 -0.07606774 0.7660877 -0.6063925 -0.2130674 0.1812213 -0.9744338 0.1328061 0.6922506 -0.7207036 -0.03708881 -0.5778053 -0.8056049 -0.1309273 -0.9591335 0.2827374 -0.01107239 0.67282 0.7209782 0.1658425 -0.2584248 -0.9644443 -0.05535155 -0.7575307 -0.6477779 0.08081555 -0.966721 0.2235369 0.1244261 -0.2913404 0.9541978 0.06802624 0.06972461 0.9340623 -0.3502374 0.9512213 -0.2523044 -0.1775405 -0.9621186 -0.1132428 -0.2479997 0.8600417 0.414488 -0.2975364 0.9344726 -0.3303285 0.1328307 -0.7007313 0.6538596 -0.2853827 0.2696439 -0.9471049 -0.1740242 0.7950422 0.6058484 -0.02925324 0.6538705 0.700731 -0.2853583 -0.2554012 -0.9531673 -0.1619955 -0.753775 -0.643491 0.133202 -0.4075936 -0.9131634 0 -0.9761577 0.1568555 -0.1500418 0.9290618 0.3685365 0.03201645 0.9401012 -0.3323012 -0.07606434 -0.6750765 -0.7234938 0.1443207 -0.6294461 0.7360212 0.2491393 -0.8996098 -0.09829819 -0.4254879 -0.4999802 0.8660368 -3.59164e-4 0.947133 0.3208412 0 0.987733 0.1561434 0.001665651 0.9936837 0.1122049 0.001675128 0.9977118 0.0675891 0.001682877 0.9997436 -0.0225836 0.001685798 0.9448088 -0.3276224 0 0.9546458 -0.2977414 -0.001239895 0.9628896 0.2698892 -0.001911997 0.9704988 0.2411018 -0.001534044 0.9594984 0.2816948 0.003332972 0.9746553 0.2237038 -0.001899778 0.9746544 0.223708 0.001899778 0.9936837 0.1122049 -0.001675188 0.9909017 0.1345778 0.001698017 0.9959363 0.09004545 -0.001687943 0.9977115 0.06759393 -0.001682877 0.9989795 0.04513561 0.001684904 0.9999986 9.66552e-6 -0.001686334 0.9989808 -0.04510647 -0.001684367 0.9977116 -0.06759393 -0.0016824 0.9989806 -0.04511129 0.001684367 0.9909486 -0.1342318 0.001668334 0.9799627 -0.1991745 -0.001652598 0.9840878 -0.1776749 0.001650512 0.9654967 -0.2604111 0.001524806 3.00945e-7 0 -1 -1.53226e-7 0 -1 -1.38847e-7 0 -1 4.40539e-7 0 -1 0 0 1 0 0 1 0 0 1 0.9994429 0.003531813 -0.03318715 -4.53639e-5 0.9996317 -0.02714025 -0.00117737 0.03040969 0.9995369 -2.85396e-4 4.12421e-5 1 -7.90035e-5 -8.47336e-5 1 3.00408e-5 -3.9936e-5 1 -0.9994574 0.003468096 -0.03275877 -0.9996473 3.62653e-4 -0.02655583 0.9995926 0.00367093 0.02830725 0.9995425 0.002738416 0.03012049 -0.7414002 -0.07844287 -0.6664627 -0.001758098 -0.2507923 -0.9680393 -0.02193659 -0.9991234 -0.03565436 -0.7456594 -0.6304032 -0.2158332 -4.65182e-4 -0.9934955 -0.1138713 0.07148212 -0.9929767 -0.0942738 0.9985378 0.01488167 0.05196952 0.9987325 -0.004011571 -0.05017399 5.99151e-4 -0.002709209 -0.9999963 -8.45817e-4 0.001525104 -0.9999985 -0.9993907 -4.18081e-6 -0.03490412 -0.9964745 0.02500414 -0.08008438 0.7045607 -0.7087165 -0.03626418 0.7950767 -0.6063722 -0.01288509 -0.8290866 -0.5591133 -0.002802371 2.79929e-5 -0.9996592 -0.02610784 -1.69184e-5 -0.9996572 -0.0261864 -0.9981349 0 0.06104773 0 2.85759e-4 1 7.72328e-5 0 1 1.65885e-6 0.9996575 0.02617496 5.60621e-4 0.9996423 0.02673912 0.2227903 -0.9725451 -0.06723624 0.1786291 -0.9812858 -0.07190161 0.14166 -0.9873389 -0.07137501 0.1617227 -0.9845126 -0.06768274 0.1941861 -0.9786512 -0.06733173 0.1942782 -0.9782479 -0.07271331 0.1473174 -0.9864698 -0.07193922 0.1116311 -0.9911555 -0.0717585 0.1283417 -0.9894479 -0.06724172 0.1122279 -0.9910733 -0.07196325 0.07074421 -0.9949206 -0.07161259 0.04547655 -0.9965904 -0.06884342 0.0479533 -0.9965677 -0.06747823 0.06966274 -0.9950439 -0.07095706 -0.004969537 -0.9977144 -0.06739127 -0.1415591 -0.9871482 -0.07415986 -0.1643392 -0.984012 -0.06865274 -0.2788849 -0.9577605 -0.07012939 -0.3015802 -0.9502937 -0.07740497 -0.2886269 -0.9550048 -0.06826651 -0.2877212 -0.9553231 -0.06763452 -0.2284563 -0.9714253 -0.06434893 -0.1963863 -0.9783292 -0.06560939 -0.0286259 -0.996666 -0.07640397 -0.05533319 -0.9962918 -0.06588649 0.02232325 -0.9975958 -0.06560677 0.02373176 -0.9970235 -0.07335507 -0.1117351 -0.9909213 -0.0747686 -0.1395131 -0.9875866 -0.07217395 -0.1108768 -0.9917024 -0.06505835 -0.1697908 -0.983335 -0.06498718 -0.1686224 -0.9828105 -0.07516664 -0.1421431 -0.9877326 -0.06465089 0.01070743 -0.9974542 -0.07050234 0.2022347 -0.9767623 -0.07096898 0.2261158 -0.9717016 -0.06832045 0.2268941 -0.9718637 -0.06324708 0.229536 -0.9706593 -0.07165068 0.2295297 -0.9707541 -0.07037442 -0.08474975 -0.9943037 -0.06463503 0.07150632 -0.9952648 -0.06584024 0.01908898 -0.8272007 -0.5615823 0.2000735 0.05846917 0.9780348 -0.141125 -0.9810608 -0.132678 -0.05873614 0.7361129 0.6743055 0.08671736 0.5170636 0.851543 -0.005834043 0.3093873 0.9509182 -1.29054e-4 0.3834708 0.9235531 8.36017e-4 0.5051292 0.8630433 -7.72281e-4 0.5504531 0.8348657 0 0.3981257 0.9173309 -4.26469e-4 0.3713039 0.9285114 -9.01163e-4 0.3276588 0.9447958 3.35923e-4 0.3030059 0.9529886 -3.73469e-4 0.2762992 0.9610716 -2.59158e-4 0.2625566 0.9649167 9.64327e-5 0.3076345 0.9515047 -2.25011e-4 0.3418093 0.9397693 3.98729e-4 0.3392537 0.9406949 -1.0146e-4 0.4102846 0.9119576 0.006678521 0.4623864 0.8866534 -0.005234777 0.492975 0.8700277 -3.47353e-4 0.4004808 0.9163051 6.5841e-5 0.4480677 0.8939997 0.001389443 0.4586659 0.8886078 0.002273142 0.5576812 0.8300521 0.007374823 0.5621159 0.8270258 -0.006032943 0.514575 0.8574241 0.005177378 0.6330387 0.774103 0.005912661 0.4719393 0.8816112 -0.003600955 0.8410333 0.5409715 -0.01161718 0.8771465 0.4800825 -0.004810988 0.5881671 0.8087251 1.90454e-4 0.3647315 0.9311128 -0.003743469 0.6912142 0.7226403 0.003213047 0.6684657 0.7437362 1.61011e-5 0.07767808 0.9969786 -0.001524806 0.01674336 0.9998587 0.001551926 0.00279957 0.9999949 7.82006e-4 0.06344479 0.9979851 -0.004552841 0.05351948 0.9985565 -2.78603e-4 0.0951029 0.9954674 0 0.09296232 0.9956697 0 0.1943084 0.9809405 4.00213e-4 0.1917158 0.9814504 -1.89401e-4 0.1693319 0.9855591 4.01632e-4 0.1535074 0.9881474 -1.48762e-4 0.1956805 0.9806678 1.39138e-4 0.2266678 0.9739721 0 -0.6475956 -0.7619844 -0.008922398 0.6603577 0.7508982 -4.40009e-4 0.617357 0.786683 -0.00357753 0.6284564 0.7778366 -4.22483e-4 0.7057677 0.7084433 -0.01003408 0.7482827 0.6633042 -0.001832008 0.6851719 0.7283791 3.12749e-4 0.7120293 0.7021498 -0.002625048 0.6620406 0.7494635 -0.002226829 0.7060638 0.7081449 -2.47441e-4 0.3673898 0.9300671 -0.004311025 0.1742493 0.9846922 -3.29761e-4 0.1131862 0.9935737 -0.01459717 0.06528389 0.99776 0 0.02538371 0.9996778 5.98912e-4 0.01394492 0.9999026 -1.19321e-4 0.006567895 0.9999785 2.92016e-4 0.03750133 0.9992966 -4.02021e-5 0.2249196 0.9743773 0.1259893 0.3608446 0.9240767 0.009279549 0.6619904 0.7494549 0.002416253 0.7354952 0.6775256 -0.005320966 0.7578671 0.6523874 0.002733528 0.6818992 0.7314411 -7.51725e-4 0.6767983 0.7361682 0.006453573 0.7468379 0.6649748 5.34435e-4 0.7306255 0.6827783 2.91245e-4 0.7210332 0.6929005 0.01054644 -0.4784816 -0.8780344 -0.001804351 -0.4623206 -0.8867111 0.001757204 -0.40912 -0.9124789 0.02867877 -0.5019295 -0.8644331 4.38536e-4 -0.4530664 -0.8914767 -0.001927852 -0.4770392 -0.8788799 4.17355e-4 -0.51294 -0.8584245 9.38729e-4 -0.5493738 -0.8355763 1.04853e-4 -0.5906098 -0.8069573 7.46688e-5 -0.6180014 -0.7861772 3.02111e-4 -0.7002345 -0.7139129 -8.90317e-4 -0.6387551 -0.7694097 0.004353225 -0.565491 -0.8247431 -9.43083e-6 -0.5988737 -0.8008436 4.52181e-4 -0.6260294 -0.7797994 -9.11198e-4 -0.6258086 -0.7799761 1.6568e-4 -0.5956494 -0.8032447 -0.006293237 -0.566249 -0.8242103 0.002361893 -0.6441559 -0.7648907 -7.91295e-4 -0.7031651 -0.7110263 0.003500044 -0.7776492 -0.6286887 0.01419305 -0.8449708 -0.5346242 0.00458467 -0.5010254 -0.8654206 -6.54329e-4 -0.421094 -0.9070169 -0.009120225 -0.3585711 -0.9334579 -0.01134777 -0.2515193 -0.9677857 2.90578e-4 -0.3275243 -0.9448428 9.28217e-5 -0.2957404 -0.9552683 -6.42304e-4 -0.2619908 -0.9650702 -0.001177251 -0.1627153 -0.9866724 8.89785e-5 -0.1527507 -0.9882648 -2.80462e-4 -0.1286336 -0.9916923 -0.001267731 -0.1204971 -0.9927129 2.31895e-4 -0.1178277 -0.9930341 -2.23625e-4 -0.1329226 -0.9911264 -0.00107789 -0.08182895 -0.9966459 -5.79566e-4 -0.07891327 -0.9968814 2.19263e-4 -0.06233745 -0.9980552 -8.73827e-4 -0.04771596 -0.9988606 -2.16222e-4 -0.04405081 -0.9990293 2.07012e-4 -0.04339164 -0.9990582 0.003834784 -0.05402117 -0.9985325 0.003342151 -0.01378315 -0.9998995 0.001188397 -0.01929706 -0.9998131 0.003926217 -0.05416452 -0.9985244 0.001328766 -0.08910483 -0.9960213 0 -0.09544271 -0.995435 3.20966e-5 -0.09467929 -0.9955078 -1.40403e-4 -0.18945 -0.9818904 5.30377e-4 -0.2023519 -0.9793127 3.13458e-4 -0.2023574 -0.9793117 -1.89322e-4 -0.1726031 -0.9849914 2.03485e-4 -0.3508485 -0.9364323 1.81083e-4 -0.4049066 -0.9143581 -4.71867e-4 -0.5365373 -0.8438766 -0.006453454 -0.8123307 -0.5831614 0.01033645 -0.8398678 -0.5426924 -0.01290738 -0.845665 -0.533558 -0.00815761 -0.795188 -0.6063081 0.001431703 -0.7500826 -0.6613427 -4.00029e-4 -0.5828831 -0.812556 0 -0.1285815 -0.991699 0 -0.1905612 -0.9816753 -3.20963e-4 -0.4930664 -0.8699917 -9.13116e-5 -0.3487389 -0.93722 -0.00391525 -0.3645556 -0.9311734 3.50278e-4 -0.2875733 -0.9577586 2.05061e-4 -0.5223975 -0.8527022 -8.46005e-5 -0.6011387 -0.7991447 -0.003749608 -0.5263186 -0.8502792 -7.4717e-4 -0.07466679 -0.9972082 0 -0.04523205 -0.9989765 7.63398e-4 -0.3566201 -0.9342492 -4.98572e-4 -0.3669565 -0.930238 4.14688e-4 -0.3989145 -0.9169881 0.002492666 0.9975051 0.07055103 0.07618182 0.9944807 0.07214337 0.114634 0.9910257 0.06875455 -0.02120059 0.9973742 0.06924796 -0.03938907 0.9966403 0.07181054 -0.03879714 0.9969607 0.06755864 -0.07441174 0.9948367 0.06901377 -0.1427536 0.9873822 0.06854039 -0.172318 0.9826341 0.06882321 -0.1773517 0.9816214 0.07046937 -0.1789873 0.9814549 0.06862932 -0.1891298 0.979372 0.07113772 -0.2114289 0.9749591 0.06893926 -0.2095232 0.9753015 0.06990897 -0.2285558 0.971036 0.06965196 -0.2283266 0.9710951 0.06958001 -0.08059215 0.9942052 0.07114136 -0.09798884 0.9926155 0.07150357 -0.1181405 0.9904519 0.07104849 -0.1325384 0.9886149 0.07123398 -0.1505582 0.9860637 0.07078695 -0.1628843 0.9840884 0.07098406 -0.2328124 0.9702252 0.06679493 -0.2099854 0.9751728 0.07031542 0.1390467 0.9879428 0.06808209 0.1788801 0.9814954 0.06832742 0.1781256 0.9814851 0.07041692 0.2410616 0.9677833 0.07269597 0.2490913 0.9659742 0.06962436 0.2740832 0.959213 0.06920355 0.2499673 0.9657362 0.06978541 0.2988948 0.9517845 0.06905251 0.2365021 0.9689885 0.07161074 0.09966695 0.9924402 0.07161641 0.07603472 0.994835 0.06724727 0.6038257 -0.7527389 0.262257 0.4663274 -0.865096 0.1847913 0.6252123 -0.763342 0.1625379 0.4207992 -0.8759915 0.2357262 0.3185642 -0.9279591 0.1934134 0.4418714 -0.8636918 0.2424589 -0.2954064 -0.9410636 -0.1647253 0.629541 0.7623858 0.1498205 0.5434864 0.8223972 0.168183 0.5340848 0.8230063 0.1934269 0.6941029 0.7040053 0.1503255 0.7027734 0.6863125 0.1873095 0.4167821 0.8782637 0.2344051 0.4423242 0.8634095 0.2426387 0.3581703 0.9102497 0.2077492 0.652208 -0.1309158 0.7466497 0.471808 0.8562194 0.2104413 0.3144543 -0.929898 0.1908093 0.3145564 -0.9298624 0.1908149 0.3139533 -0.9300487 0.1909005 0.3150346 -0.9297096 0.1907706 0.4497052 -0.8917515 0.05044585 -0.001980245 0 0.999998 -0.002083003 0.006160259 0.9999789 -0.3203582 0.9467194 -0.0330612 -0.3201614 0.9467939 -0.03283637 -1 5.3679e-6 0 -1 -1.15754e-5 0 0.5972453 0.3804197 0.7061013 0.6611443 0.1412723 0.7368381 -0.9927978 -0.1197308 0.004139482 -0.9854029 -0.1209329 0.1198183 -1 0 8.90056e-6 0.3144552 0.9298981 0.1908077 0.314444 0.9299014 0.1908096 0.3145656 0.929862 0.1908017 0.4886651 0.8358864 0.2500008 0.3143405 0.9299328 0.1908275 -1 0 9.06246e-6 -0.9819483 0.1867216 0.0302118 -0.9999845 2.18792e-5 0.005565404 -0.3907265 -0.006893992 0.920481 0.08726382 -0.006322979 0.9961652 0.8740381 0.005308628 0.4858283 0.9711524 -0.005106031 0.2384052 0.3983497 0.00670284 0.9172092 0.6798257 7.40496e-4 0.7333734 -0.8820515 0.003049135 0.4711432 -1 -1.07358e-5 0 -0.3544465 -0.9118341 -0.2071864 -0.2785665 -0.9032648 -0.3263639 -0.1720317 -0.7515618 -0.6368359 -0.07605069 -0.4977699 -0.8639684 -0.08955526 -0.6664628 -0.7401401 -0.1645444 -0.7756564 -0.6093295 -0.8403376 3.82528e-6 0.5420634 -0.5277677 -0.06188887 0.847131 0.03326499 0.9987925 -0.03615266 -0.1116602 -0.00379157 0.9937393 -0.1133517 -0.01518118 0.993439 -0.1225531 6.97936e-4 0.9924618 -0.1617083 -0.01683896 0.9866949 -0.2627917 -0.02857476 0.9644294 -0.1181685 -0.01969492 0.9927983 -0.1200661 -0.01591908 0.9926384 -0.2232286 -0.05754441 0.9730661 -0.2212779 -0.06630688 0.972954 -0.1917666 -0.04984474 0.980174 -0.5042893 -0.1925819 0.8417865 -0.4872888 -0.1262096 0.8640722 -0.4918524 -0.1359987 0.8599917 -0.4259814 -0.08295518 0.9009208 -0.6504004 -0.1689815 0.740557 -0.6574898 -0.1758425 0.7326572 -0.4475397 -0.08086764 0.8906002 -0.6430057 -0.1025269 0.7589678 -0.1013107 0.7055079 0.7014235 -0.7964408 -0.06428825 0.6012896 -0.9739637 0.160897 0.1597089 -0.971479 0.2086011 0.112757 -0.9677155 0.2464031 0.05303084 -0.9811286 0.1849693 0.05632978 -0.9821258 0.1067921 0.1549981 -0.97795 0.07404631 0.1952713 -0.9107393 -0.06624752 0.4076337 -0.9121789 0.09555715 0.3984953 -0.9102006 0.1117053 0.3988195 -0.8080955 0.09941732 0.5806014 -0.7449876 0.08221352 0.6619929 -0.7534238 0.1194694 0.6465908 -0.864411 0.2002052 0.4612067 -0.9041047 0.2444449 0.3504873 -0.9175131 0.2657201 0.2959095 0.8085924 0.5719034 -0.138221 -0.6214208 0.09059077 0.7782222 -0.1725213 0.02738523 0.9846251 -0.2351589 0.04510581 0.9709097 -0.1812763 0.03174901 0.9829196 -0.6155341 0.1030131 0.7813489 -0.1169745 0.0183376 0.9929656 -0.1033905 0.02025496 0.9944346 -0.1197161 0.008990347 0.9927675 -0.1231055 0.01665478 0.9922539 -0.1186103 2.02597e-4 0.992941 -0.7607586 -0.1976279 0.6182149 -0.5961546 -0.3592917 0.7179896 -0.6516473 0.1898707 0.7343739 -0.8721323 -0.1585863 0.4628559 -0.896784 -0.1179779 0.4264503 -0.9198507 -0.1358232 0.368004 -0.9614212 -0.1449825 0.2337721 -0.9785664 -0.184486 0.09150314 -0.9677023 -0.2463964 0.05330121 -0.9630058 -0.1460488 0.2264726 -0.3834061 -0.1112376 0.9168566 -0.145297 -0.05153626 0.9880449 -0.1030887 -0.0301544 0.994215 -0.127393 -0.03208839 0.9913331 -0.1198718 -0.01904141 0.9926068 -0.1468217 -0.03562182 0.9885214 -0.1409524 -0.03888165 0.9892526 -0.1808305 -0.04991084 0.9822471 -0.09861177 -0.03195899 0.9946127 -0.143795 -0.02162146 0.9893714 -0.09944283 -0.03099906 0.9945603 -0.1525136 -0.006005644 0.9882832 -0.1398517 0.0170347 0.990026 -0.1020921 0.02947765 0.9943381 -0.1977285 0.05467301 0.978731 -0.2174556 0.07042849 0.973526 -0.3533997 0.09666186 0.930465 -0.5300178 0.1056081 0.8413847 -0.21432 0.07069993 0.9742015 -0.4689306 0.1691133 0.8668938 -0.7041896 0.1684362 0.6897436 -0.7990214 0.1889444 0.5708457 -0.9847568 0.1043455 0.1391625 -0.995198 0.06189405 0.07583022 -0.9946924 0.01592075 0.1016539 -0.9831839 -0.08600729 0.1610973 -0.9423053 -0.1050058 0.3178592 -0.9885414 -0.09429121 0.1178779 -0.9882065 -0.123396 0.09067201 -0.9612073 -0.1451106 0.2345709 -0.9473637 -0.2103191 0.2413876 -0.9006414 -0.1557332 0.4056997 -0.9125975 -0.1385309 0.384675 -0.9198351 -0.2564066 0.2969162 -0.919494 -0.2368558 0.3137357 -0.9198579 -0.2342457 0.3146275 -0.9480826 -0.24744 0.1997823 -0.1039042 -0.00482887 0.9945756 -0.1058838 0.02403742 0.9940879 -0.09836983 0.02758902 0.9947675 -0.1001052 0.03369969 0.994406 -0.1306464 0.03175932 0.9909203 -0.1039135 -0.02167904 0.99435 -0.09621089 -0.01708251 0.9952145 -0.115844 -0.03659421 0.9925931 -0.9630783 -0.2435588 0.1147141 -0.9906411 0.0618804 0.1216599 -0.9909988 -0.01166796 0.1333619 -0.9955082 -0.06191533 0.0716232 -0.338181 -0.05652272 0.9393821 -0.980921 -0.1380778 0.1368525 -0.8347318 -0.05209589 0.5481868 -0.8704509 -0.05889284 0.4887198 -0.9565759 -0.07847917 0.2807196 -0.9630849 -0.07505381 0.2585234 -0.9693145 -0.09048616 0.2285646 -0.9843428 -0.06893014 0.1622282 -0.9940959 -0.0452488 0.09862107 -0.8234907 -0.0136401 0.5671659 -0.9486698 -0.01521366 0.3159024 -0.9945591 0.01592886 0.102949 -0.9934508 0.07051479 0.08990603 -0.9189926 0.02568751 0.3934371 -0.8980639 -0.003562986 0.4398508 -0.9186676 0.02564352 0.3941982 -0.9421255 0.07149392 0.3275489 -0.9562639 0.1185779 0.2673926 -0.9655826 0.2251006 0.1303076 -0.8898864 0.05941194 0.452297 -0.9635667 0.01413398 0.2670946 -0.939208 0.04786199 0.3399963 -0.9900318 0.04881238 0.1321156 -0.9492295 0.07712268 0.3049845 -0.9571402 0.104583 0.270084 -0.9799616 0.1015704 0.1713442 -0.826309 0.1264654 0.548835 -0.9878855 0.1233562 0.09415692 -0.9776801 0.1665003 0.1281377 -0.1245742 -0.02397817 0.9919205 -0.532997 -0.1104589 0.838876 -0.1786744 -0.05140846 0.9825644 -0.977026 -0.1887551 0.09895408 -0.9713348 -0.2148451 0.1017364 -0.9498963 -0.213106 0.2286543 -0.865013 -0.2022423 0.4591849 -0.357625 -0.02095991 0.9336301 -0.4801532 0.1411758 0.8657497 -0.4457792 0.1186973 0.8872384 -0.2030914 0.04696476 0.9780329 -0.4230389 0.085496 0.9020691 -0.7163898 0.1856396 0.6725502 -0.8545711 0.2050971 0.4771202 -0.9520767 0.2122632 0.2202144 -0.9660485 0.2244067 0.1280311 -0.9272536 0.1676594 0.3348003 -0.8603169 0.1491798 0.4874425 -0.9560134 -0.2541468 0.1464512 -0.9460189 0.2354301 0.2227573 -0.4819524 0.09766197 0.8707377 -0.1529091 0.04422277 0.9872504 -0.2280848 4.00168e-4 0.9736413 0.3487969 0.9307348 0.1098806 0.1861395 0.9825232 5.70335e-4 -0.3772293 0.02202123 0.9258581 -0.3008874 -0.9526372 0.04415041 -0.2876726 -0.2109244 -0.9342138 -0.2328028 -0.4595247 0.8571115 -0.3702059 -0.481247 0.7945748 -0.272485 -0.601995 0.7505691 -0.2252246 -0.9123303 0.3419463 -0.1675277 -0.6285574 0.7595066 -0.274186 -0.6379134 0.7196448 -0.3244356 -0.8282135 0.4569509 -0.3850933 -0.5487963 0.7419743 -0.1707285 -0.007605791 0.9852888 -0.3009915 0.4410798 0.8454897 -0.7005982 -0.01345908 0.7134291 -0.3829426 0.4583003 0.8020699 -0.2472767 0.4141741 0.8759647 -0.2676732 0.5572917 0.785988 -0.2641314 0.5659734 0.7809666 -0.5323857 0.5495804 0.6438377 0.005155444 -0.9275478 0.3736691 0.5864276 -0.4956041 0.6406865 -0.8274784 -0.3409048 0.4461653 -0.9997573 -0.02181398 0.003109335 -0.9999997 -8.45801e-4 2.81262e-4 -1.40721e-6 -0.9253165 0.3791959 2.75951e-5 -0.9253153 0.3791986 0.7912494 -0.6099773 0.04303973 0.4780482 -0.5839667 0.6560891 -0.8736146 -0.2922058 0.3891189 -0.842169 -0.4113346 0.3486477 -0.3043822 0.4428877 -0.8433279 -0.8839199 -0.4658128 0.04128205 -0.007688462 -0.5568226 0.8305959 0.008728563 -0.5844015 0.8114178 -0.005980968 -0.6246666 0.7808687 0.005523681 -0.74464 0.6674435 4.57892e-4 -0.6748797 0.7379276 -0.01681298 -0.5391637 0.8420332 0.01247382 -0.4749919 0.8799018 0.002402842 -0.4496066 0.8932235 0.003716886 -0.3948207 0.9187507 -3.49074e-5 -0.3863203 0.9223648 -4.06061e-4 -0.5360465 0.8441885 3.4964e-4 -0.6210119 0.7838011 0.001604318 -0.6616342 0.7498251 -8.92538e-5 -0.3382061 0.9410721 -3.6671e-4 -0.3188911 0.9477914 -2.35027e-4 -0.2864624 0.9580915 -3.9169e-4 -0.2762559 0.9610841 -4.75283e-6 -0.3093537 0.9509472 -1.6072e-4 -0.2573066 0.9663299 -9.26626e-5 -0.2250897 0.9743381 -3.45895e-4 -0.2084943 0.9780236 9.14454e-5 -0.1941824 0.9809655 1.39428e-7 -0.1937168 0.9810576 -0.00198847 -0.1393624 0.9902395 0 -0.1357495 0.9907432 -1.15983e-4 -0.1364844 0.9906423 -1.23606e-5 -0.09539097 0.99544 -9.67609e-4 -0.09223461 0.9957368 -0.002132117 -0.06458961 0.9979097 -1.5414e-4 -0.07748955 0.9969933 -3.41826e-4 -0.04979074 0.9987596 4.52776e-4 -0.05185353 0.9986546 -0.001008331 -0.06196552 0.9980778 2.71655e-4 -0.01064532 0.9999434 -1.29869e-5 -0.01652729 0.9998635 -0.001852154 -0.001387834 0.9999974 2.00474e-4 -0.02762913 0.9996182 1.07786e-4 -0.1147916 0.9933896 9.97789e-6 -0.1164383 0.993198 2.14365e-4 -0.25789 0.9661743 -0.001442372 -0.3695443 0.9292121 5.17907e-4 -0.4276292 0.903954 0.01186746 -0.461492 0.8870651 -0.00829029 -0.5073112 0.8617231 -0.00550121 -0.5145715 0.8574299 0.004674851 -0.5221616 0.8528339 0.0238502 -0.5827746 0.8122838 -0.01911228 -0.6396238 0.7684506 -0.04216271 -0.6374715 0.7693195 5.92436e-4 -0.7320894 0.6812084 0.01047497 -0.7914916 0.6110905 0.01070493 -0.7899619 0.6130626 -0.00265789 -0.8350495 0.5501683 0.008814811 -0.8610612 0.5084251 0.004560232 -0.7012731 0.7128782 -0.001358091 -0.5267111 0.8500434 1.05061e-4 -0.4875143 0.873115 -1.6336e-4 -0.4819515 0.8761979 -5.94446e-4 -0.5386467 0.8425316 6.8818e-4 -0.5591886 0.8290402 -0.006375849 -0.5964558 0.8026208 -7.92367e-4 -0.6292973 0.7771643 3.88135e-4 -0.662793 0.7488026 -0.007368743 -0.6924648 0.7214141 -0.003012299 -0.5999978 0.799996 2.44999e-4 -0.5145549 0.8574575 -5.26525e-4 -0.4408848 0.8975635 -6.87448e-4 -0.4886226 0.8724951 -0.00135535 -0.6099805 0.7924152 -9.32374e-4 -0.6644771 0.7473081 2.73101e-4 -0.3146922 0.9491938 -0.06359845 -0.9956647 0.06787616 -0.0241428 -0.9973037 0.06930112 0.009095489 -0.997624 0.06829112 0.04570358 -0.9966861 0.06729024 0.08719378 -0.9938782 0.06784886 0.1258403 -0.9897171 0.06800192 0.1675956 -0.9835554 0.06730967 0.2084856 -0.9758666 0.06494778 0.1937259 -0.9781823 0.07503169 -0.09536427 -0.9928615 0.07163745 0.2075894 -0.9757779 0.06902313 0.165853 -0.9834898 0.07239258 0.1380746 -0.9880989 0.0677945 0.1206171 -0.9900287 0.07276523 0.2934994 -0.9535744 0.06748342 0.2565248 -0.9642486 0.066482 0.2557298 -0.9641283 0.07112562 0.02995955 -0.9969561 0.07198035 0.02437072 -0.9971442 0.07148063 -0.1147924 -0.9911616 0.06649422 -0.1325223 -0.9885044 0.07278054 -0.1486449 -0.9866568 0.06643098 -0.2189634 -0.9731549 0.07088416 -0.2369304 -0.9685239 0.07632601 -0.2278797 -0.9712484 0.06890112 -0.21116 -0.9750317 0.06873679 -0.2096399 -0.975322 0.06926971 -0.2112002 -0.97489 0.07059723 0.1730175 -0.9824507 0.06968182 -0.1146776 -0.9908222 0.07155847 -0.1524195 -0.9857002 0.07185804 -0.04070991 -0.9966447 0.07100766 0.1392216 -0.9876753 0.07151883 0.2082822 0.975536 0.07034367 -0.7044814 0.7071723 0.06011241 -0.8079246 0.3498932 0.4741651 -0.4388947 -0.3424392 -0.8307266 0.04463505 0.6637904 0.7465856 -0.1891633 0.8902655 0.4143001 0.6195525 0.7830712 0.0543549 0.7936657 0.6060364 0.05305469 -0.9720556 0.230822 0.04276883 -0.5444412 0.8364225 0.06309682 0.999791 -0.0203731 0.001724958 0.9998873 0.01151543 0.009644269 0.999852 0.01521199 0.008040487 0.9976416 -0.06632989 0.017654 0.9999012 -0.01045542 0.009399056 -1.23722e-5 -0.9253193 0.3791888 -3.39821e-5 -0.9253209 0.3791849 -0.9999092 -0.004870831 0.01256865 -0.9996387 -0.02368086 0.01271992 -0.9998512 0.0169937 0.003008604 -3.50701e-4 0.04835611 -0.9988301 5.33894e-4 0.05767887 -0.9983351 0.005974888 0.06825631 -0.99765 0.002297401 0.147731 -0.989025 0.001809358 0.1747267 -0.9846153 1.93222e-4 0.2458047 -0.9693194 -5.66597e-4 0.2519029 -0.9677523 2.91445e-4 0.2312039 -0.9729053 0 0.09948271 -0.9950394 -2.66565e-4 0.1202866 -0.9927393 -8.92498e-4 0.08438378 -0.996433 -2.45588e-4 0.04389429 -0.9990362 1.39395e-4 0.02510362 -0.9996849 2.28149e-4 0.007489264 -0.999972 -2.27601e-4 0.3483287 -0.9373725 -3.94136e-4 0.3006715 -0.9537277 -0.00497955 0.3607261 -0.9326585 -0.004306197 0.3613464 -0.9324217 -1.62269e-4 0.6723175 -0.7402629 0.001463592 0.6564354 -0.754381 2.53694e-6 0.6109389 -0.7916778 -0.002365171 0.6356949 -0.7719369 -5.72225e-4 0.6476848 -0.7619083 -8.91598e-4 0.7352718 -0.6777718 -0.001891136 0.7814533 -0.6239609 4.17764e-4 0.7929078 -0.6093417 5.42882e-4 0.551676 -0.8340584 -4.59027e-4 0.4425684 -0.8967346 0.002990305 0.5172115 -0.8558525 -4.12806e-4 0.5345628 -0.8451287 1.18564e-5 0.4992498 -0.8664582 -1.49837e-4 0.4671623 -0.8841716 1.78556e-4 0.4058902 -0.9139219 -4.52195e-4 0.3930692 -0.9195088 -7.59087e-4 0.5063897 -0.8623045 4.70084e-4 0.4425002 -0.8967683 -6.28518e-5 0.4313515 -0.902184 1.16039e-4 0.3972415 -0.9177142 4.52769e-4 0.3989526 -0.9169715 -7.99764e-4 0.4236502 -0.9058256 -0.005468964 0.4529677 -0.8915101 -2.92127e-4 0.5434795 -0.8394225 -2.02722e-6 0.5787506 -0.8155047 -0.003592014 0.5607721 -0.8279625 0.004587471 0.4959682 -0.8683286 -1.9932e-4 0.4618957 -0.8869343 4.1202e-4 0.5300847 -0.8479447 -5.62121e-4 0.1216515 -0.9925727 0 0.1252292 -0.9921279 -4.81583e-4 0.1578532 -0.9874625 7.64916e-4 0.7073704 -0.7068427 0.003759562 0.8181577 -0.5749817 4.10266e-4 0.1165052 -0.99319 -2.73539e-5 0.08297502 -0.9965517 4.65527e-4 0.03508883 -0.9993842 -9.96908e-4 0.02303975 -0.9997341 0.003432571 0.002530157 -0.999991 -0.002487003 0.1131284 -0.9935773 0.006492018 -0.1504997 -0.9885888 -6.11744e-4 0.03874588 -0.9992489 7.00222e-5 0.6405438 -0.7679217 -8.23694e-5 0.6106938 -0.791867 -0.9999064 0.006634473 0.01196461 -0.9999312 0.008068859 0.008513152 -0.1920477 0.8716163 0.451002 -0.008456289 0.925583 0.3784505 0.999945 0.001512706 0.01038253 0.9999117 0.00992155 0.008852779 -0.2388176 0.9679545 -0.07765465 -0.1708446 0.950836 -0.2583085 -0.08726423 0.9281291 -0.3618862 -0.007485687 0.9317762 0.362956 -0.1105347 0.9193485 -0.3775985 -0.9999436 0.006501972 0.008400917 -0.03178155 0.9886971 0.1465198 0.007538497 0.9251702 0.3794777 -0.819777 0.4101265 0.3997023 0.09710586 0.7411838 -0.6642416 0.4272011 0.8506195 -0.3065059 0 0.755347 -0.6553251 -0.5255593 0.6426157 -0.5575236 0 -0.6406058 -0.76787 0 -0.6406102 -0.7678664 0.3725849 0.7009602 -0.608141 -0.6212363 -0.7836233 0 -0.5756688 0.8176831 0 -0.7530933 -0.5323525 -0.3865897 0 1 0 1.3205e-7 0.726815 -0.6868333 -0.5547732 0.6047127 -0.5714451 0 -0.6763376 -0.7365918 0.3805226 -0.625459 -0.6811781 -0.5942244 0.8042993 0 -0.6898369 -0.6805714 -0.246876 0 1 0 0.4971579 0.6091563 -0.6178695 -0.5462256 0.588079 -0.5964905 -0.7313215 -0.596457 0.3307688 0 -0.7019274 -0.7122485 -1.15743e-5 -0.7016534 -0.7125184 0.7427343 -0.5165742 0.4260247 -0.7985944 -0.5881162 0.1279304 -0.6298546 0.7767131 0 0 1 0 0 0.6763388 -0.7365908 -0.4228355 -0.6586447 -0.6224126 0 -0.7268161 -0.6868322 0.6116625 0.5350651 -0.5827302 -0.5492882 -0.7846351 -0.2874549 -0.820872 0.5134553 0.2500661 1 -1.81607e-6 0 0 1 0 0 1 0 0 -0.7553452 -0.6553273 -0.6084305 0.5083967 -0.609381 -0.5181679 -0.6460326 -0.5604855 0.4745186 0.8802455 0 0.7395261 -0.6613039 0.1256119 0.6936504 -0.7203118 0 0.7025707 0.5472165 -0.454916 -0.004636883 -0.9575883 -0.2881029 -0.002231061 -0.989928 -0.1415539 -0.8816056 -0.1247233 0.4552095 0.003638446 0.9997806 -0.02063167 0.1056652 -0.0284968 -0.9939935 -0.2280296 0.2286047 0.9464368 0.1030219 -0.01994127 -0.9944792 0.1157949 -0.01462596 -0.9931655 0.115785 -0.007167518 -0.9932485 0.2827388 0.09079313 -0.9548903 0.3042518 -0.04764372 -0.9513996 0.4425651 -0.06500214 -0.8943774 0.1017882 -0.006890773 -0.9947823 0.1133372 -0.005451619 -0.9935417 0.1159811 -0.02056998 -0.9930385 0.1308729 -0.07262343 -0.9887356 0.1128426 0.001943767 -0.993611 0.1133342 0.004803061 -0.9935453 0.3905448 0.08204859 -0.9169204 0.3408944 0.06970542 -0.9375139 0.304017 0.05520302 -0.9510659 0.2129935 0.01735889 -0.9768995 0.1870737 0.02880799 -0.9819234 0.130513 0.01604843 -0.9913167 0.1602354 -0.005580246 -0.9870631 0.102124 0.01927429 -0.9945849 0.1032667 0.02099102 -0.9944323 0.6364433 0.1396464 -0.7585769 0.8328783 0.09076833 -0.5459623 0.8508347 -0.05211436 -0.5228427 0.8716236 -0.1039987 -0.4790162 0.9058191 -0.1469528 -0.3973622 0.895511 -0.2713142 -0.3527728 0.8496337 -0.2486315 -0.4650859 0.7954693 -0.129817 -0.5919258 0.773406 -0.1034844 -0.6254071 0.7424522 -0.02941828 -0.6692529 0.6182823 0.1035087 -0.7791104 0.5539867 0.06897485 -0.8296633 0.4357002 0.07729166 -0.8967672 0.4223998 0.06109803 -0.9043481 0.1627585 0.02389919 -0.9863765 0.29633 -0.1012236 -0.9497064 0.1258291 0.03426343 -0.9914602 0.1864761 -0.034249 -0.9818624 0.7150308 -0.05593669 -0.6968516 0.7049593 -0.1642066 -0.6899774 0.5571334 -0.1360172 -0.819208 0.6177266 -0.1551198 -0.7709422 0.3456274 -0.06455665 -0.9361486 0.398945 -0.06038725 -0.9149844 0.4852671 -0.09275841 -0.8694319 0.5362175 -0.0974887 -0.8384312 0.3207269 -0.07372701 -0.944298 0.1364448 -0.05646491 -0.9890373 0.3744164 0.1282675 -0.9183462 0.1454525 0.02510285 -0.9890468 0.1549708 0.04818814 -0.9867431 0.2065992 0.05462348 -0.9768998 0.3289827 0.08015698 -0.9409279 0.320746 0.0715273 -0.9444606 0.2187655 0.05150824 -0.974417 0.1924028 0.0444861 -0.9803072 0.1039316 0.02748721 -0.9942046 0.4005273 0.1024711 -0.910537 0.8489482 0.2543656 -0.4632334 0.9165814 0.1987482 -0.3469551 0.8802395 0.08961194 -0.4659916 0.8445 0.09693002 -0.5267109 0.776445 0.177923 -0.6045467 0.8223605 0.166695 -0.5440001 0.8550055 0.1451403 -0.4978954 0.8903889 0.1534402 -0.4285603 0.9713199 0.2065288 -0.1178293 0.9703354 0.225674 -0.0867213 0.986467 0.1380956 -0.08838909 0.9518085 0.1378718 -0.2739561 0.9393832 0.1417695 -0.3121869 0.9765237 0.184384 -0.1113734 0.9795765 0.1549249 -0.1281727 0.9464521 0.2744711 -0.1699829 0.9445176 0.2946926 -0.145061 0.9597833 0.2510833 -0.1255925 0.9538381 0.2795165 -0.109834 0.9595647 0.2589876 -0.1102771 0.9893727 0.06257402 -0.1312493 0.9860805 0.02084869 -0.164956 0.9809789 -0.01412284 -0.1936007 0.9728059 -0.06204968 -0.2231557 0.9621444 -0.09935396 -0.2537852 0.92511 -0.08853441 -0.3692334 0.9382939 -0.04786908 -0.3425102 0.9558855 0.01386189 -0.2934125 0.9732141 0.06871813 -0.2193904 0.9822999 0.1213594 -0.1426842 0.9975415 0.03059446 -0.0630486 0.9960594 -0.01435184 -0.08752053 0.9974822 -0.0305913 -0.06398034 0.989695 -0.06559044 -0.1272861 0.9856662 -0.04978078 -0.1611962 0.9867321 -0.02765858 -0.1599836 0.9922625 -0.05664098 -0.1104859 0.9930599 -0.09159696 -0.07377076 0.9739071 -0.1571503 -0.163734 0.9418079 -0.2153292 -0.2581304 0.986701 -0.09387773 -0.1326959 0.9349656 -0.2719559 -0.2277703 0.919114 -0.257774 -0.2979631 0.9478968 -0.2247699 -0.2257657 0.9743602 -0.2123733 -0.07429504 0.9665929 -0.2376154 -0.09611082 0.9354918 -0.2886396 -0.2038195 0.953822 -0.2599968 -0.1504179 0.9537743 -0.2703296 -0.1312879 0.8050555 -0.2064694 -0.5561081 0.7992231 -0.1874541 -0.5710548 0.113349 0.03450095 -0.9929561 0.1285923 0.03155225 -0.9911955 0.09067112 -0.04105991 -0.9950341 0.1976183 -0.180356 -0.9635449 0.07724744 -0.09236007 -0.9927248 0.977752 -0.1864439 -0.09612387 0.9117351 0.2448395 -0.3298376 0.7648227 0.0258013 -0.6437239 0.992702 0.09156256 -0.0784806 0.9645747 -0.1706519 -0.2011804 0.9415548 -0.1518849 -0.3006753 0.9304038 -0.1555846 -0.3318771 0.8002892 -0.07269454 -0.5951915 0.8296188 -0.0480495 -0.556259 0.6613512 -0.08549326 -0.7451883 0.2812601 -0.05790567 -0.957883 0.2418774 -0.05785781 -0.9685804 0.23174 -0.04551357 -0.9717125 0.8713053 -0.1044487 -0.4794972 0.8522631 -0.111288 -0.5111385 0.9802212 -0.1198647 -0.1574768 0.9802258 -0.107104 -0.1663916 0.9861076 -0.1344199 -0.09758692 0.9131391 -0.08539915 -0.3986029 0.872973 0.03413647 -0.4865726 0.9170004 0.03205132 -0.3975965 0.7447026 -0.1674031 -0.6460606 0.68562 -0.1546198 -0.7113493 0.1810266 -0.03883528 -0.9827111 0.2151654 -0.06039112 -0.9747086 0.1552248 0.0110802 -0.9878171 0.2937092 0.03465372 -0.9552665 0.7166174 0.05013048 -0.6956627 0.9336893 0.1198702 -0.3374249 0.9570978 0.1289292 -0.2595017 0.9787275 0.08934122 -0.1846905 0.9738914 0.06510549 -0.2174786 0.7459612 0.1074519 -0.657264 0.9696028 0.1685328 -0.1773897 0.9723237 0.1586788 -0.1714864 0.1234215 0.02766507 -0.9919687 0.8948309 -0.02875876 -0.4454779 0.9328823 -0.03758794 -0.3582149 0.9677368 -0.06932395 -0.2422389 0.9097509 -0.02279967 -0.4145283 0.9742011 -0.02728611 -0.2240265 0.9599564 -0.007852911 -0.2800396 0.9811324 0.008758008 -0.193139 0.9705145 0.02608072 -0.2396278 0.9936202 0.05813568 -0.09664028 0.4760705 -0.134023 -0.8691346 0.1220417 -0.01207464 -0.9924516 0.1686009 -0.0617097 -0.9837508 0.6145005 0.1507584 -0.7743778 0.9406214 0.25964 -0.2186741 0.9510468 0.1990165 -0.2364368 0.9288378 0.1873661 -0.319616 0.8328616 0.2259912 -0.5052422 0.7411616 0.1817557 -0.6462541 0.8491705 0.197405 -0.4898377 0.9687607 0.2108092 -0.1306224 0.9690712 0.2043063 -0.13842 0.7836419 0.1687071 -0.5978657 0.695974 0.1520712 -0.7017796 0.8644251 -0.2228612 -0.4506686 0.8984416 -0.2157015 -0.3824601 -0.8876896 0.1269729 -0.4425891 0.07920235 -0.6721017 -0.7362108 0.06486988 -0.7437155 -0.6653414 0.07886403 -0.7122533 -0.6974781 0.5727805 0.5481762 -0.6094468 0.07466441 0.6957708 -0.7143727 -4.71072e-4 -0.9999886 0.004760861 5.25105e-5 -0.9999023 -0.01398503 -0.9726497 0.05928343 -0.2245845 -0.9799627 -0.1267716 0.1536295 0.08183443 -0.656376 -0.7499825 0.07255762 -0.7149156 -0.6954359 0.103479 -0.9443488 -0.312246 0.7156423 0.3237461 0.618906 0.0792452 0.713229 -0.6964371 4.88574e-6 -1 -1.65151e-4 4.859e-5 -0.9999988 -0.001644432 -0.6879249 -0.6872012 0.2334821 0.05305367 -0.7908887 -0.6096559 0.07687848 -0.6783069 -0.7307458 0.07603049 -0.7830085 -0.6173468 -0.224942 0.9032969 -0.3653161 0.9716469 -0.04167824 0.2327342 0.05508822 0.7871233 -0.6143307 0.07720607 0.7322175 -0.6766807 -1.57098e-4 -0.9999994 0.00112909 4.17789e-5 -0.9999969 -0.002512156 -0.9436324 -0.2101079 -0.2557587 -0.9940564 -0.07303398 0.08073371 0.2238007 0.939289 -0.2600951 -1.26162e-6 1 2.91982e-4 0.758998 0.6500512 0.03681731 0.7686129 -0.4814631 -0.4212213 0.8425575 0.4971638 -0.2071836 0.6363304 -0.7702488 -0.04243123 -0.5693249 -0.8221127 0 -0.6066184 0.7949932 0 0 1 0 0 1 0 -3.71814e-5 -0.9999998 -6.87881e-4 0.6740243 0.5981585 -0.4334717 0.5535551 -0.7561966 -0.3489176 0 -1 0 0.7917109 0.3867626 0.4728728 0.2565455 -0.9665322 0 0.8685058 -0.2759242 -0.4117809 -0.002196669 0.9903718 -0.1384164 0.7495207 0.1743959 -0.6385959 0.749351 -0.5964066 -0.2877019 -0.03059798 -0.9987773 -0.03883236 0.9542973 0.2037267 -0.2186604 0.2679665 0.9634283 0 0.995027 -0.07829535 0.06157213 0.2389611 -0.9710292 0 0 -1 0 0.5839334 -0.8118016 0 0.5837818 -0.8119106 3.33998e-4 0.6982496 0.6957412 -0.1684987 0.2174447 -0.08454912 -0.9724039 0.3165573 -0.2194893 -0.9228304 0.3381277 -0.1840887 -0.9229199 0.4503999 -0.5496157 -0.7036069 0.5276005 -0.5340546 -0.6606236 0.4867021 -0.6862788 -0.5405021 0.4567785 -0.8651368 -0.2071037 0.8165455 -0.4885724 -0.3074907 0.7806053 -0.6146008 -0.1136724 0.5248758 -0.8456786 -0.09660857 0.7807127 -0.5922393 -0.1993499 0.7309594 -0.4611211 -0.5030565 0.9310186 -0.3283026 -0.1594426 0.4276871 -0.8851251 -0.1834054 0.4582163 -0.7241071 -0.5154675 0.1635013 -0.1559752 -0.9741351 0.6627745 -0.7243794 -0.1897491 0.5521935 -0.7974578 -0.2431944 0.2902983 -0.3882758 -0.874625 0.404865 -0.4050498 -0.8197677 0.4054856 -0.4503881 -0.7954446 0.6076908 -0.7866976 -0.1087145 -0.5324604 0.8464446 -0.004190981 -0.5924031 0.7983077 -0.1084603 -0.9958945 -0.0169664 -0.08891779 -0.9976769 -0.06100827 -0.03031116 -0.594743 -0.7995145 -0.08400809 0.2508369 -0.9665859 -0.05284464 0.8987548 -0.4339757 -0.06249088 0.9133286 0.3992075 -0.08040136 0.4861288 0.8455266 -0.2208248 0.5536711 0.5825308 -0.5950683 0.3189453 0.3645386 -0.8748632 0.2128437 0.2765721 -0.9371262 0.3046037 0.7659062 -0.5662194 0.7794241 0.5970425 -0.1898383 0.8783328 0.463939 -0.1152922 0.6701887 0.7368559 -0.08882814 0.628237 0.775056 -0.06787216 0.7422292 0.4657399 -0.4818528 0.4061467 0.6600125 -0.6320036 0.5326132 0.7285889 -0.4306757 0.5189911 0.8221828 -0.2338029 0.851944 0.4351286 -0.2912982 0.6594114 0.7414424 -0.1242569 0.6629387 -0.7380905 -0.1254388 0.8179589 -0.5744619 0.03060781 0.9935388 0.01439779 -0.1125763 0.9441324 0.3289521 0.02011221 0.3988231 0.9168692 0.01705974 -0.5413281 0.834777 -0.1005544 0.001922607 -0.9999552 0.00926876 -0.5437827 0.8074322 -0.2288093 -0.999998 1.42411e-4 0.002024292 -1 4.2173e-4 0 -0.7208074 -0.6792764 -0.1379141 0.01263386 -0.9998576 0.01119786 -3.5203e-4 -0.9999989 0.001492798 -0.001031279 -0.9999994 5.54267e-4 0.006061196 -0.9997394 -0.02201467 -0.01744031 -0.9997945 0.01034218 0.3046647 -0.9354971 -0.1789547 -0.01485514 -0.999747 -0.01688909 -0.999999 1.24823e-4 0.001475155 -0.9999822 -5.08279e-4 0.005951344 -0.004711091 -0.9999762 0.005055487 0.01638257 -0.999742 -0.01573973 0.001079201 -0.9999989 0.001033484 7.79992e-4 -0.9999996 6.58748e-4 0.5403454 -0.8402792 -0.04424887 0.2561085 0.4774137 -0.8405264 0.5782454 0.7700979 0.2694099 -0.8538579 0.2840092 -0.4361943 -0.7227399 -0.03130787 -0.6904107 0.6691275 0.7396537 -0.07197773 -0.9285274 -0.3712376 0.004430055 -0.9235684 0.3831168 0.01558464 -0.9905607 -0.01326197 -0.1364318 -0.4091877 -0.902412 -0.1349745 0.7116495 -0.2502924 -0.6564365 4.2682e-4 -0.4458376 -0.8951138 0.308045 -0.3058808 -0.9008582 0.3744199 0.9254825 -0.05737626 -0.001889169 0.5863546 0.8100523 -0.3316253 -0.7630246 -0.5548135 0.807579 0.5620648 -0.1786046 -0.4859275 0.7093599 -0.5105712 -0.7240322 -0.6896531 0.01249384 -0.4651474 -0.877089 -0.119804 0.05485433 0.9790151 0.1962669 0.9392085 0.3359642 0.07082039 -0.980477 0.1964062 0.009461343 0.03061914 0.01476079 0.9994221 -0.6317096 0.1538286 0.7597893 -0.5090222 0.5592732 0.6543012 -0.7005654 0.3240519 0.6357662 -0.02530646 0.4956899 0.8681308 -0.7229469 0.6895795 0.04275608 0.1450604 0.6667875 0.7309938 0.3627523 0.6584964 0.6593886 0.6149975 0.2732141 0.7396839 0.09683442 0.5712592 0.8150374 -0.03879815 0.5350288 0.8439425 0.6542098 0.1729931 0.7362628 0.4643342 -0.7030068 0.5386791 -0.5783141 0.1739925 0.7970443 0.633266 0.5262609 0.5674714 0.003701031 0.003529548 0.999987 -0.03960269 0.0271632 0.9988463 0.04848331 0.01993203 0.9986251 -0.003548502 -0.008452117 0.999958 -0.02402418 0.01506882 0.9995979 -0.00172472 -0.002237439 0.999996 0.02137732 0.01458686 0.9996652 0.01765823 -7.19392e-4 0.9998438 0.8309611 -0.5552336 0.03491771 0.6518381 0.7561103 0.05834692 -0.9576136 -0.2873865 -0.01963067 -0.5549628 -0.8305616 0.04673278 -0.9049912 0.4144824 0.09589338 -0.9954555 -0.03662455 0.08790481 -0.8307031 -0.5550653 0.04283601 -0.1919554 -0.9803726 0.04497647 0.003236293 0.1007061 0.994911 -0.09921389 0.09509575 0.9905118 0.05646365 0.3159756 0.9470857 0.1102044 -0.02192193 0.9936672 0.04668462 -0.1283531 0.9906292 0.02913928 -0.157262 0.987127 0.08633553 -0.1292156 0.987851 -0.08609348 -0.1288501 0.9879198 -0.1262537 -0.08436095 0.9884044 -0.886439 0.4525296 0.09717512 0 0.9972664 0.07389193 0.3862202 0.9192677 0.07603251 0.7531067 0.6539348 0.07210785 0.8035761 0.5930735 0.05029153 0.995427 0.03096425 0.09036797 0.982262 0.135925 0.1291739 0.2402967 -0.9706533 0.009479343 -0.2039311 -0.5473747 0.8116607 -0.08597648 -0.5247544 0.8469009 0.1284179 -0.6912025 0.7111596 0.2602759 -0.6024975 0.7544888 0.3487655 -0.4959991 0.7952029 0.4319412 -0.5801312 0.6905612 0.1333825 -0.5845499 0.800319 0.7156093 0.6585479 0.2328476 -0.9399664 0.29171 0.1771113 -0.1267312 -0.5823882 0.8029716 -0.7431952 -0.4547572 0.4907717 -0.03143745 0.3106797 -0.9499947 0.624359 -0.3167479 0.7140355 0.005839586 -0.002631545 -0.9999795 0.01120299 0.02105307 -0.9997156 -0.004049897 0.004109561 -0.9999834 -0.00428915 0.004203319 -0.9999821 0.004495739 -0.001562476 -0.9999887 0.029697 -0.02023911 -0.9993541 -0.05141973 -0.1025977 -0.9933931 0.07699161 -0.08632922 -0.9932873 0.1330814 -0.1134988 -0.9845849 -0.003625333 0.003317832 -0.999988 -0.007268965 -0.005443215 -0.9999588 0.003798246 -0.001106083 -0.9999923 2.57128e-4 -0.003264904 -0.9999946 0.01093673 0.001439571 -0.9999392 0.6779527 0.7198398 0.1490331 0.9396607 -0.3112532 0.1419836 -0.9992319 0.03785252 -0.01013958 0.9437484 0.3179581 -0.09078305 0.4786387 -0.8778663 -0.01598954 -0.3985016 -0.9166462 -0.03092652 -0.08879089 0.9828777 0.1614546 0.9549266 0.2870151 0.07574653 -0.4184565 -0.903422 0.09339636 -0.9906699 0.136196 -0.004901707 0.9516832 0.2994855 0.06787925 -0.3045141 -0.9523816 0.01550865 0.2279164 -0.3960108 0.8895108 0.2594707 0.05442345 0.9642163 -0.01625674 -0.008362412 0.999833 0 -2.095e-6 1 -0.00298798 5.51973e-4 0.9999954 -0.002583682 -5.50128e-4 0.9999966 0.001900315 -0.001739799 0.9999967 6.97901e-5 -2.44001e-5 1 2.51632e-5 0.005456149 0.9999852 0.004772365 -8.81354e-4 0.9999882 -2.98042e-4 -0.003225624 0.9999948 7.07905e-4 -0.002638995 0.9999964 -0.001238644 -0.003006577 0.9999948 0.5181968 -0.4965419 0.6963608 0.1535703 -0.7413274 0.6533375 0.9700205 0.2392599 -0.04260444 0.8711366 0.4897545 0.03552126 0.2308934 0.6761578 0.699642 0.2917214 0.6419872 0.7090494 -0.8937695 0.4484133 0.01007932 -0.9122627 -0.4092143 0.01790237 -0.7171632 0.6911045 0.08973056 -0.7061124 0.6997912 0.1081553 -0.893818 0.4364256 0.1030634 -0.9719604 -0.212245 0.1012181 -0.8557724 -0.5073927 0.1010257 -0.0308727 -0.9960457 0.0833069 0.3037289 -0.9491868 0.08242154 0.5971719 -0.7978807 0.08229446 0.9447478 0.3083703 0.111173 0.7324748 0.672656 0.1049513 0.4322857 0.8964851 0.09717845 -0.09311246 0.9916889 0.08878809 -0.06172358 0.9928762 0.1019166 0.004327654 0.9966975 0.08108866 -0.9872604 -0.1134045 0.1116081 0.9542348 -0.2854179 0.08928889 0.6596811 0.7425363 0.11602 -0.7468858 0.6442623 -0.1645838 0.5262917 -0.7330148 -0.4309366 0.01619774 -0.2380726 0.9711123 -0.1600413 -0.1201794 0.9797672 -0.2566283 -0.8722746 -0.4162679 -0.8529275 0.009585142 -0.5219414 0.4597154 -0.2933176 0.8382283 0.9602472 0.0174033 -0.2786084 -0.02597165 -0.4015526 0.9154676 -0.3144488 0.9298999 -0.1908091 0.6711277 0.7386243 0.06341743 0.9992663 0.01540333 0.03506702 0.001436889 0.9992743 0.03806465 -0.2543818 -0.9670983 -0.003291606 -0.2588236 0.9659246 9.62657e-6 -0.278267 0.9029877 -0.3273847 -0.349603 0.9240731 -0.154489 -0.1672347 0.7805953 -0.6022489 -0.1540921 0.73972 -0.6550344 -0.249095 0.8511657 -0.4620268 -0.3014911 0.9025622 -0.3073835 -0.2518255 0.8620706 -0.4397935 0.1691483 -0.04541015 -0.984544 0.264257 -0.03128117 -0.963945 0.1899766 -0.05722761 -0.9801194 0.09548753 -0.07729256 -0.9924253 0.1766559 0.983217 -0.04557579 -0.3484228 -0.936952 0.02688217 0.4221127 0.7617861 -0.4914293 -0.9410559 -0.3250086 -0.09371924 -0.1505916 -0.9761164 -0.1565861 -0.1199363 -0.9897018 -0.0781387 -0.934736 -0.3454163 -0.08340454 -0.6506652 0.7576245 -0.05138039 -0.02977603 0.9995567 -1.13899e-4 0.691619 -0.7220366 0.01806831 0.9963611 -0.02915251 -0.0800926 -0.8724995 0.2462272 -0.4220389 -0.5165973 0.5554358 -0.6516274 -0.5253918 -0.6826513 0.5078884 -0.644379 0.7519082 -0.1393191 0.3457832 -0.9371778 0.04617053 -0.0693733 -0.2442865 0.9672184 0.3485628 0.02808314 0.9368647 -0.2209255 -0.2663946 0.9382035 0.9087721 -0.4167674 0.02093619 0.8867059 -0.4622524 0.008698046 0.8867584 -0.4621517 0.008680403 0.8868038 -0.4620643 0.0087049 0.4941447 -0.8654761 0.08229398 0.6120873 -0.7851566 0.09422564 0.9947079 -0.05676436 0.08563888 0.9606409 0.2639691 0.0865423 0.95417 0.285734 0.08897089 0.8208466 0.564892 0.08430826 -0.02362227 0.9962093 0.08372002 -0.8542034 0.5130991 0.08405935 -0.8957573 0.4349849 0.09169 -0.9756738 0.2031686 0.08235973 -0.9892886 -0.1208877 0.08181893 -0.8969238 -0.4343448 0.08289903 -0.7053875 -0.7036213 0.08570653 -0.7300683 -0.6773784 0.0903269 0.9899135 -0.1086381 0.09093451 0.4596481 0.8832702 0.09250688 -0.9942758 0.05204439 0.09331268 -0.9361597 -0.3390946 0.09284287 -0.7190515 -0.6891608 0.08956748 -0.1375342 -0.9893444 0.04777133 -0.1747859 -0.9808131 0.08634686 -0.772144 -0.1134722 0.6252342 -0.9446938 -0.009194552 0.327825 -0.6013433 0.5522157 -0.5774462 0.2207354 0.865395 -0.4498527 0.1993265 0.1195991 -0.9726074 -0.9869364 -0.03108775 -0.1580833 0.3290164 0.4574408 0.8261332 0.7061808 -0.7061796 0.05117911 0.9740928 -0.2259124 0.01033776 -0.2918737 0.9564 0.01042693 0.9646604 0.2584763 0.05118954 0.7070021 0.706999 0.01734161 -0.706173 0.7061851 0.05120956 -0.7070008 -0.7070047 0.01715213 -0.258681 -0.9653746 0.03370487 0.01497864 0.05441617 -0.9984061 -0.1792529 -0.311238 -0.9332735 -0.1771851 0.04747909 -0.9830316 -0.1164792 0.1164836 -0.9863388 -4.08916e-4 -1.09125e-4 -1 -0.1042886 -0.02794581 -0.9941544 -0.2233636 0.9724254 -0.0670647 -0.181892 0.9808679 -0.06938004 -0.1410309 0.9875172 -0.0701434 -0.1008719 0.9925925 -0.06771308 0.01264542 0.9974765 -0.06986254 0.08635842 0.9935755 -0.07314378 0.1116315 0.991166 -0.07161331 0.08094859 0.9943118 -0.06922048 -0.0268743 0.9970895 -0.07134693 -0.06177449 0.9956653 -0.06953305 -0.1374216 0.9878966 -0.07194143 -0.1933299 0.9790129 -0.06447899 -0.1635418 0.98372 -0.07449293 -0.1346701 0.9887723 -0.06475621 -0.2214663 0.9722567 -0.07529675 -0.2151261 0.9741505 -0.06893169 -0.2542134 0.9644494 -0.07220166 -0.2807986 0.9576222 -0.06412434 -0.2799118 0.9569873 -0.0763213 -0.0544781 0.9957702 -0.07398557 -0.0304864 0.9968614 -0.07306134 -0.00632292 0.9977762 -0.0663532 0.08143717 0.9943342 -0.06831914 0.1432088 0.9872745 -0.06913954 0.2206246 0.9715149 -0.08650809 0.1108392 0.9913141 -0.07078975 0.1265184 0.9893031 -0.07261204 0.1627804 0.9839983 -0.07245689 0.1629829 0.9843365 -0.06721931 0.1855533 0.9786943 -0.08790624 0.1969538 0.9777565 -0.07212191 0.2011346 0.9770287 -0.07042509 0.1969212 0.9780489 -0.06813699 0.2256003 0.9713221 -0.07508653 0.2282415 0.9711824 -0.06863349 0.2280113 0.9713942 -0.06636494 0.2295292 0.9707543 -0.07037502 0.04097539 0.9969204 -0.06686526 0.03996461 0.9964831 -0.07365041 0.1866556 0.9801625 -0.06664305 0.1502463 0.9863795 -0.06694537 -0.08198952 0.9944469 -0.0659793 0.04094523 0.5587666 0.8283137 0.2568194 0.8830592 0.3927473 3.42317e-4 0.3883289 0.9215208 0.4649977 0.2383458 0.8526244 -0.01524633 -0.1146868 0.9932847 0.03031462 -0.0993638 0.9945894 0.0261842 -0.09750318 0.9948907 0.07073152 -0.09072756 0.9933607 0.001140058 0.004256963 0.9999904 -0.02003234 -7.02239e-4 0.9997991 -0.008092224 0.01475787 0.9998584 -0.06813746 -0.07314121 0.9949913 0.0970205 -0.02300906 0.9950165 0.1766324 -0.2547378 -0.9507417 0.5086741 -0.06992328 0.8581151 -0.04042047 -0.1329063 0.9903041 0.9989351 0.0301795 0.03489989 0.9989324 0.03040277 0.03478175 0.3112809 -0.9495767 0.03753018 0.3770794 -0.9255443 0.03433805 0.8880625 -0.4589328 0.02694141 0.007266044 0.1795552 0.9837211 0.3092893 0.1042606 0.9452354 0.9989333 -0.03027319 0.03487223 -0.4075253 -0.9107332 0.06699615 -0.909485 -0.4093089 0.07282364 -0.8742781 -0.430477 0.2243377 -0.9388712 -0.3290522 0.1012211 -0.5027162 -0.8437726 0.1879473 -0.6293209 -0.7268152 0.2751271 -0.002631783 0.9801126 -0.1984248 0.578188 0.4553642 -0.6770098 -0.9080662 -0.1634266 -0.3856264 -0.6936529 -0.4093253 0.5927044 -0.454883 -0.755753 0.4710826 -0.9460974 0.06114333 0.3180584 -0.5450739 -0.8319751 0.1034989 -0.2796447 0.9593596 0.03779172 -0.6515659 0.7578396 0.03377944 -0.8227712 0.5672805 0.03522282 -0.857196 0.5136435 0.03722196 -0.9856863 0.1646635 0.03617388 -0.8341822 -0.5502769 0.0365417 -0.5752143 -0.8171775 0.03673267 0.5865842 -0.8091704 0.03409349 0.9497519 -0.3106904 0.03798472 -0.9776077 -0.2071401 0.03709793 -0.6100266 0.7915382 0.03653913 -0.3811422 0.9239273 0.03300231 -0.04514527 -0.9968423 0.06532531 -0.00143814 -0.9993913 0.03485786 -2.90955e-4 -0.9993837 0.03510278 -0.1744132 0.9782583 0.1122083 -0.3877923 0.9135422 0.1227105 -0.9479539 0.2987569 0.1101254 -0.8027558 -0.5115467 0.306436 0.5372974 -0.2663404 -0.800234 -0.7625303 -0.63246 0.1361684 0.005621552 0.8166974 0.5770389 0.2893896 0.8872776 0.359155 -0.1695676 0.9321066 0.3200381 -0.1404354 0.9252551 0.3523935 -0.6594581 0.01399058 0.7516112 0.7291368 -0.5818388 -0.36031 -0.5881647 0.262769 0.7648626 0.8259815 0.5615639 0.04899561 0.008351147 0.9994137 0.03320753 -0.9995414 -0.001949608 0.03022241 -0.9203035 5.51908e-4 0.3912051 -0.7348417 0 0.6782387 0.722326 0 0.6915528 0.7146296 -6.39202e-4 0.6995028 0.9809792 0.001338422 0.1941085 -0.9838408 0.1663494 0.06622254 -0.5499485 0.6313187 0.5468029 -0.02935308 0.890622 -0.4537963 -0.5713326 0.8063812 0.1527361 0.4617316 0.8854614 0.05255639 -0.3139938 0.02291572 0.9491485 0.6563075 -0.7481874 0.09734535 0.4954496 0.868384 0.02095425 0.4998917 0.8659108 0.01752281 0.07135909 0.6257197 0.7767772 0.3254867 0.7776684 0.5378572 0.383353 0.8281881 0.4088336 0.3859145 0.8281061 0.4065839 0.2571343 -0.4945696 0.8302306 -0.001222848 0.4275798 0.9039768 -0.1344564 0.5017243 0.854514 -0.3161383 0.869153 0.3803022 -0.3147551 0.8872219 0.3372929 -0.3395329 0.9328594 0.1203778 -0.3617347 0.9237085 0.126138 -0.375645 0.9240291 0.07114177 -0.3815905 0.9216119 0.07085394 -0.2264069 0.6029543 0.7649744 -0.2219226 0.6286789 0.7453276 -0.3105744 0.8698641 0.3832492 -0.3263512 0.8944122 0.3058133 -0.358912 0.9219063 0.1458458 -0.3477439 0.9288653 0.1276063 -0.2903925 0.8183977 0.4958805 -0.2803164 0.7613694 0.584585 -0.2889587 0.7336483 0.6150309 -0.3265537 0.8930613 0.3095228 -0.0910902 0.7645398 0.6381077 -0.1156194 0.8134281 0.5700588 -0.2051519 0.9287517 0.3087603 -0.2504869 0.9469383 0.2014054 -0.6699386 -0.04775887 0.7408788 -0.03470134 0.01957911 0.999206 -0.1056945 -0.2052597 0.9729837 0.9518982 -0.3034128 0.04278475 0.9961503 0.04340922 0.07615959 0.9548617 0.2939798 0.0426045 0.3462917 -0.9372671 0.04015773 0.3408745 -0.9389627 0.04640769 -0.9429118 -0.3330197 0.003904402 -0.8958252 -0.4426437 0.03954881 -0.7654116 -0.6283262 -0.1391093 -0.4996328 -0.8651431 0.04352796 -0.476368 -0.8397319 0.2606221 -0.1350984 0.1736839 0.9754909 -0.6231632 0.3986753 0.6728489 0.3900641 0.2142857 0.8955064 -0.3605275 -0.9074237 0.2158756 -0.01176673 -0.006407856 0.9999103 0.9952652 0.09501427 -0.02048099 -0.9168599 -0.1487355 0.3704667 0.3509205 0.838756 -0.4163451 0.4702472 0.8519057 -0.2304869 -0.4567829 0.7232927 0.5178776 -0.0107972 0.01706963 0.9997961 0.4999243 -0.865892 0.01751285 -0.513737 0.8567971 0.04441934 -0.4879975 0.411525 0.7697439 -0.1621171 -0.3475109 0.9235553 -0.04623591 -0.662996 0.7471938 0.7123323 0.7005333 0.04284673 0.05273377 0.1492398 0.9873939 -0.3419555 -0.9395542 0.01744914 0.1940065 0.9797002 0.05048853 0.3889877 0.9199383 0.04901301 -0.8952445 0.4438244 0.03946471 0.08249664 0.3271638 -0.9413598 0.158676 0.4625039 -0.8723027 0.1795958 0.4825816 -0.85724 0.2107222 0.5766195 -0.7893708 0.2457299 0.6813518 -0.6894757 0.2965543 0.8340686 -0.4651723 0.3356664 0.9239476 -0.1834361 0.3111862 0.9406057 -0.1357354 0.2448847 0.6682291 -0.7024966 0.3346642 0.9166285 -0.2186143 0.3391878 0.9321984 -0.1263245 0.3378774 0.9260415 -0.1681845 0.3349106 0.9160711 -0.2205646 0.3330972 0.9147188 -0.2287704 0.3372516 0.9270545 -0.1638032 0.3389135 0.9276226 -0.1570163 0.3484414 0.9346929 -0.07027018 0.3265698 0.9022886 -0.2814743 0.3288211 0.891002 -0.313037 0.3331307 0.9019174 -0.2748983 0.3060279 0.5155057 -0.8003755 0.02371996 0.3644463 -0.9309223 0.1058105 0.6635833 -0.7405818 0.03112483 0.7498863 -0.6608342 0.1215117 0.7359787 -0.6660107 0.05854302 0.8132593 -0.5789492 0.2107871 0.8518248 -0.4795451 0.2125933 0.9051995 -0.3679918 0.2347295 0.9305939 -0.2808863 0.2491677 0.9432358 -0.2195949 0.2093191 0.9408574 -0.2664074 -0.2105907 -0.5618177 0.8000078 -0.2397734 -0.6696774 0.7028804 -0.2775709 -0.7450923 0.6064584 -0.2410816 -0.637022 0.7321767 -0.290436 -0.797249 0.5291889 -0.3366635 -0.9219715 0.1913802 -0.3162231 -0.8766151 0.3626968 -0.3305276 -0.8960185 0.2964835 -0.3759081 -0.9241099 0.06865847 -0.3815882 -0.9216153 0.07082265 -0.3383704 -0.9343031 0.1121761 -0.3253495 -0.9346828 0.1432338 -0.3354611 -0.9155879 0.2217311 -0.3329194 -0.9056527 0.2625986 -0.3211278 -0.8880249 0.3290729 -0.2808027 -0.8093023 0.5159262 -0.2060586 -0.6439025 0.7368375 -0.3304687 -0.9211227 0.2057268 -0.05470764 -0.6417836 0.7649321 -0.1208496 -0.7952916 0.5940595 -0.1042749 -0.8026614 0.5872492 -0.05357301 -0.9097139 0.4117652 -0.2209948 -0.9401288 0.2594596 0.9990776 0.01646119 0.03966206 0.9965835 -0.01752328 -0.08071237 -0.4973247 -0.8595662 0.1175341 -0.5831804 -0.8121091 -0.01948332 0.8288722 0.1511486 -0.5386326 0.8180465 -0.138995 -0.5581042 0.8529173 -0.03194659 -0.5210677 0.687745 -0.5426889 -0.482178 -0.4235963 0.4422138 -0.7905777 -0.5962226 -0.7474969 -0.2928601 0.6718567 -0.01438403 -0.7405415 0.6033578 -0.6847921 -0.4086798 0.6198604 0.683596 0.3853177 0.1254004 0.7988997 -0.5882465 0.01229226 0.6271641 -0.7787902 0.6559783 -0.7545446 -0.01883763 0.3016633 -0.9532846 -0.01574486 -0.5221064 -0.8527115 -0.01697206 -0.99966 -0.006027758 -0.02537328 -0.6492557 0.760466 -0.01259034 -0.2829389 0.9590552 -0.01260346 0.8389272 0.5440165 -0.01571983 0.8697611 0.493164 -0.01746636 0.9711878 0.2378228 -0.01531738 0.9975031 -0.0688641 -0.01566201 0.9737389 -0.2266708 -0.02128946 0.9406314 -0.339065 -0.01573216 0.8050421 -0.5928864 -0.01982474 0.9007535 -0.4337698 -0.02206659 0.9749469 -0.2220308 -0.01345264 0.9997518 0 -0.02228158 0.8977618 0.4399653 -0.02131319 0.6646531 0.7469282 -0.01829349 0.9875245 0.1568303 -0.01413029 0.362659 0.9318191 -0.01385241 0.2174918 0.9758027 -0.02250689 -0.6233338 0.7816283 -0.02263021 -0.4162439 0.9091582 -0.01314163 -0.03135842 0.9994299 -0.01251745 -0.9012582 -0.4326307 -0.02375698 -0.8363045 -0.5479915 -0.01732516 0.01078802 -0.9998434 -0.0140292 -0.9988982 0.02500355 0.03971779 -0.861014 0.3592816 0.3599608 -0.9989352 0.03017383 0.03490084 -2.43344e-5 0.9993914 0.0348857 -0.1735397 0.9841936 0.03531098 -0.068156 0.3898696 0.9183444 -0.1486224 0.8469437 0.5104877 -0.1540776 0.86517 0.4772223 -0.1725471 0.9698843 0.1719074 -0.1232076 0.6836504 0.7193345 -0.7891461 0.1202448 0.6023204 -0.8714694 -0.4568412 -0.1784304 2.42526e-4 7.40203e-5 1 -6.62076e-5 -1.77538e-4 1 5.0866e-4 3.42442e-4 -0.9999999 5.12127e-5 -2.36981e-5 1 2.49687e-5 0.002954006 0.9999957 7.60145e-5 6.50892e-5 1 -0.001674294 -6.70747e-4 0.9999984 2.03295e-4 3.97063e-4 1 -0.1624033 -0.9233492 0.3479247 -0.1517612 -0.8553711 0.4952868 -0.07107049 -0.4031237 0.9123817 -0.02769535 -0.1504676 0.988227 -0.1225987 -0.6837575 0.7193367 -0.9254226 0.1090294 0.362913 0.623168 -0.7534655 -0.2096461 0.1735234 0.9842095 -0.0349496 -0.9950686 -0.09106522 0.03931719 -0.8831529 -0.4674348 0.03931742 -0.7607488 -0.6480156 0.03657007 -0.6187217 -0.7847244 0.03730034 -0.3817005 -0.9236856 0.03331041 -0.2897216 -0.9563544 0.03804707 -0.9533715 0.2994179 0.03783959 -0.8838846 0.4664638 0.03405165 -0.7643727 0.6436179 0.03860664 -0.6024766 0.7973889 0.0345391 -0.4573684 0.8885051 0.03705108 0.3102884 0.9499492 0.03629904 0.529713 0.8474913 0.03409796 0.6522229 0.7568994 0.04133421 0.8460572 0.04643064 -0.5310665 0.8875174 -0.1107596 -0.4472643 0.5716816 0.3904249 -0.7216292 0.140782 -0.4016278 -0.9049174 0.1911925 -0.5323148 -0.8246736 0.2191302 -0.5849402 -0.7809142 0.2958392 -0.8103747 -0.5057392 0.3232827 -0.8862785 -0.3316606 0.3367191 -0.9258254 -0.1716616 0.3352001 -0.9156423 -0.2219009 0.2259745 -0.6279368 -0.7447355 0.2722923 -0.7378515 -0.617602 0.3315917 -0.8902381 -0.3122872 0.3389464 -0.926229 -0.1649707 0.340035 -0.9315642 -0.1287031 0.3677043 -0.9242517 -0.1027243 0.3484821 -0.934827 -0.06825637 0.3394358 -0.9376712 -0.07453966 0.3296241 -0.9082535 -0.2577276 0.3288517 -0.9017848 -0.2804296 0.3232552 -0.8894587 -0.3230625 0.2797424 -0.7765908 -0.5644916 -0.8569583 0.166597 -0.4877169 0.41039 -0.9100238 0.05862462 -0.9388002 -0.3420045 -0.04107636 0.8260738 -0.4608796 -0.3243333 0.9949664 -0.0925247 0.03848671 0.2175125 0.9670708 -0.1321454 -0.7700321 0.629087 -0.1063026 -0.9012619 0.4327967 -0.02035015 0.9792572 -0.1745944 0.1028215 0.9257732 0.3604419 -0.1141294 3.3819e-4 3.41561e-4 -0.9999999 -0.03739845 0.1395661 -0.9895063 1.17555e-4 4.33827e-4 -1 0.2587795 0.9657806 0.01734715 0.7061817 0.7061777 0.05119162 0.9657794 0.2587847 0.01734077 0.9646592 -0.258482 0.05118358 -0.964659 0.2584809 0.0511927 -0.2252829 -0.974238 0.01038706 -0.956353 -0.292029 0.01039159 8.9208e-7 8.38748e-7 1 0.009481191 -0.008457124 0.9999194 0.002690434 -0.01317453 0.9999097 -0.007547438 -0.002520561 0.9999684 -0.006441771 -0.005399882 0.9999648 -0.006217777 2.38528e-4 0.9999807 2.07427e-4 3.08103e-4 1 -0.7756263 0.002260327 0.6311886 -0.7868022 3.22955e-4 0.6172052 -0.9600672 -0.004576444 0.2797324 0.9682697 0.004709959 0.2498637 0.1366985 0.9551653 0.2626267 0.4367564 0.8912582 0.1220777 0.7823932 0.6112385 0.119366 0.9595114 -0.2501255 0.1295195 0.9874718 -0.1198186 0.1026802 0.7383891 -0.6648581 0.1128957 0.4394215 -0.8914271 0.1107538 0.4040569 -0.9075055 0.114769 0.1824319 -0.977945 0.1016975 -0.1654064 -0.9816098 0.09530425 -0.6501016 -0.7533785 0.09893906 -0.9928238 0.07021051 0.09680688 -0.1960042 0.9743839 0.1102654 -0.777624 0.6161248 0.1252645 0.3816668 -0.4935954 0.7814691 0.1615762 -0.6498692 0.742673 0.3115594 -0.01083767 0.9501649 0.4730893 -0.809719 0.3471913 -0.5042508 0.08895385 -0.8589636 -0.008347868 0.006596505 0.9999435 -0.009546995 0.004635453 0.9999437 3.5527e-6 -6.52308e-7 1 0.005373597 0.01230412 0.9999099 -0.006550312 0.01052325 0.9999232 -0.004888892 0.001171112 0.9999874 -0.005174279 0.007013738 0.999962 0.04818558 -0.009051263 0.9987974 0.02753782 0.03146457 0.9991255 -0.002784371 0.007039844 0.9999713 -0.474565 0.8687196 0.1418244 -0.8601817 0.4955998 0.1202846 -0.9525978 -0.285283 0.1056931 -0.6049111 -0.79072 0.09404617 0.6939004 -0.706587 0.138698 0.9407006 -0.32252 0.1051828 0.1761415 0.9730573 0.148774 -0.7375271 -0.6640676 0.1227524 0.05902969 -0.9893542 0.1330187 0.06835031 0.9253382 0.3729311 -0.1751494 -0.3721963 0.9114784 0.06645154 0.927657 0.3674735 0.6277913 -0.7783747 0.003321528 -0.9390619 -0.3433452 0.01664155 0.967459 0.2289103 0.10781 0.6358886 0.7608372 -0.1295087 -0.03637194 0.0198062 -0.9991421 -0.02508991 -0.09364271 -0.9952897 -0.0151816 -0.0536608 -0.9984439 0.6822209 0.7310722 0.01039576 0.9646579 0.2584856 0.05118942 0.2587681 -0.9657839 0.01733642 -0.2584677 -0.9646629 0.05118739 -0.7070105 -0.7069905 0.01733809 -0.964659 -0.258482 0.05118751 -0.9657766 0.2587952 0.01733833 -0.7061915 0.706168 0.05118846 -0.2587661 0.9657844 0.01734405 0.974237 -0.2252871 0.01039499 -0.6822116 -0.731081 0.01038891 0.9575526 0.2858048 0.03753429 0.8383727 0.5435867 0.04055726 0.5809589 0.8131765 0.03508251 0.379366 0.9246078 0.03437846 0.8195998 0.5716716 0.03805023 -2.12674e-5 3.53714e-5 1 3.06509e-5 2.88183e-5 1 0.006569445 -0.001134932 0.9999778 0.00266242 -0.008995532 0.999956 0.002184271 -0.009656429 0.999951 -0.002063035 -0.001735746 0.9999964 -0.007031023 0.001627206 0.999974 -3.58358e-6 4.21165e-6 1 -0.001749992 -0.006017744 0.9999805 -0.007400512 -6.34038e-4 0.9999724 2.34675e-6 3.59997e-6 1 -0.4033713 -0.3308554 0.8531275 -0.293381 -0.3668769 0.8827961 -0.4890196 -0.6809415 0.5451409 -0.4425471 -0.4349006 0.784228 0.1287689 0.9463845 0.2962688 0.7322046 0.6764026 0.07972544 0.8754976 0.4551672 0.1622552 0.9952752 -0.006024837 0.09690779 0.6411172 -0.7608644 0.10027 0.2654154 -0.9586803 0.1024051 0 -0.9931965 0.1164504 -0.1630161 -0.9817647 0.09779495 -0.4037638 -0.9068704 0.1206683 -0.6295199 -0.7707645 0.09811681 -0.918574 -0.3803101 0.1076394 -0.9943057 0.04061895 0.09851998 -0.8379181 0.5179198 0.1721987 -0.1049774 0.9905493 0.0882712 -0.103832 -0.8939526 0.4359677 -0.7645855 0.6338143 0.1169983 -0.09174937 0.1897081 -0.9775443 6.28349e-6 2.94147e-6 1 -6.86383e-7 0 1 6.00878e-7 0 1 0.001783192 0.002533733 0.9999952 -0.04870724 0.3577397 0.9325502 -0.279214 0.008693039 0.9601895 0.3095459 0.2622556 0.914004 -8.6004e-5 -1.07193e-4 1 0.003165602 -3.58149e-4 0.9999949 6.75924e-7 0 1 3.92928e-5 2.38674e-5 1 -1.95777e-6 7.82837e-6 1 -2.68078e-4 -1.07389e-4 1 -3.15333e-4 -0.00126928 0.9999992 8.44393e-5 -1.12126e-5 1 1.60844e-6 1.46954e-7 1 5.36086e-7 0 1 5.36097e-7 0 1 2.01083e-5 2.34644e-6 1 -5.76983e-5 -0.003432691 0.9999942 3.84798e-5 2.43868e-5 1 6.8173e-7 0 1 -3.19603e-7 0 1 1.17359e-6 2.75844e-7 1 1.46744e-6 0 1 4.62876e-5 -1.31201e-5 1 -0.001837849 8.25536e-4 0.999998 -0.002224087 8.85506e-4 0.9999971 3.9799e-4 8.37283e-6 1 -0.001117944 1.82406e-4 0.9999994 -8.48695e-6 1.4519e-6 1 -0.002576947 -0.001315772 0.9999958 6.26821e-7 0 1 0.0135501 -0.002373754 0.9999055 0.001258075 -0.001733541 0.9999977 -6.65072e-7 0 1 4.82565e-6 -3.42249e-6 1 -8.69972e-4 -0.005681574 0.9999835 -3.93068e-5 6.01632e-4 0.9999998 -4.68067e-4 -4.03906e-4 0.9999998 -4.84094e-4 -0.001439571 0.9999989 0.006061196 0.006684243 0.9999594 -0.00122416 -7.44922e-4 0.9999991 -0.02374398 0.006671547 0.9996958 -4.35756e-4 1.27058e-4 1 1.01725e-5 4.32181e-5 1 0.6231344 -0.7323463 0.2745406 0.6016006 -0.7158126 -0.3545267 0.2594252 -0.7198461 -0.6438324 0.3512642 -0.7670126 -0.5369406 -0.2224339 0.9745599 -0.02750271 -0.4260995 0.9044632 -0.01963227 -0.9037858 -0.4274944 -0.02049499 -0.8409677 -0.5408099 -0.017264 -0.7062844 -0.7077134 -0.01744323 -0.5374941 -0.8430833 -0.01763284 -0.2224639 -0.9746811 -0.02250891 0.2224656 -0.9746838 -0.02237439 0.628791 -0.7772786 -0.02144861 0.8203259 -0.5716737 -0.01595878 0.5988153 -0.8007585 -0.01436537 0.3739953 -0.9271793 -0.02159404 -0.269433 -0.962926 -0.01339834 -0.3173102 -0.9481708 -0.01692599 0.9881377 -0.1521441 -0.02088487 0.9758805 -0.2176 -0.01754117 0.9246479 0.3805233 -0.01510781 0.9693549 0.2447041 -0.02170222 0.9975532 0.0684114 -0.01441133 0.9007542 0.433766 -0.02211868 0.6129034 0.7899014 -0.02012759 0.3005818 0.9535539 -0.01964157 0.6233853 0.7816902 -0.01874488 -0.07112437 0.9973826 -0.01301062 0.6651502 -0.7464843 -0.01834285 0.292564 0.9559518 -0.02371996 -0.9988391 -0.02361607 0.04198729 -0.9989407 -0.02979832 0.03506416 -0.9989352 -0.03017783 0.03489923 0 -0.9993909 0.03489995 -7.84675e-5 -0.9993914 0.03488236 -0.9495285 -0.3136578 0.003794908 -0.9397974 -0.3416852 0.005669474 0.3407717 -0.2020016 -0.9181884 0.4135209 -0.6747037 -0.6113718 -2.36308e-6 0 -1 4.72205e-5 0.003110051 -0.9999952 -8.26918e-7 0 -1 -2.86156e-5 -1.08981e-5 -1 0.00337857 -0.002170383 -0.999992 -0.001395523 0.004137873 -0.9999905 -2.84717e-4 -2.31619e-4 -1 -3.35755e-4 3.22615e-4 -0.9999999 2.12813e-7 0 -1 0.3594442 -0.9286246 -0.09195888 -0.6227146 0.5510893 -0.5554522 -0.6748189 0.3263783 -0.6618887 -0.2140648 -0.7717011 -0.5988769 -0.9097635 -0.3838991 -0.1579619 0.9695807 0.2361266 0.06447947 0.4805576 0.8373428 -0.2606173 -0.6257728 -0.7701559 0.123566 0.1126903 0.03019529 -0.9931713 0.2278691 -0.1088926 -0.9675836 0.001640081 4.40085e-4 -0.9999986 -0.2584915 -0.9646568 0.05118185 -0.7069951 0.7070057 0.01734393 0.7061816 0.7061781 0.05118781 0.9653778 0.2586689 0.03370726 0.2587841 -0.9657798 0.01733064 -0.9892136 0.1454152 0.01763665 -0.6495251 0.7596274 0.03291612 0.225282 0.9742381 0.0103994 0.9293906 0.3686766 0.01762604 0.2920225 -0.9563551 0.01038628 1.98492e-4 -3.26463e-4 1 -2.95205e-4 -2.65425e-4 1 -0.005881011 0.005545675 0.9999673 -0.007643401 0.001602411 0.9999696 0.007213771 0.00284636 0.99997 0 -1.68459e-6 1 3.27673e-6 -2.10309e-6 1 3.51997e-6 -3.07642e-6 1 0 -6.10951e-6 1 0.2966192 0.7939373 0.5307359 0.2664432 0.8403111 0.4721076 0.207411 -0.9332898 -0.2931738 0.2288079 -0.950227 -0.2114606 0.2182241 -0.8993953 -0.3787696 0.04985481 -0.8240672 -0.564294 0.07941275 -0.7690266 -0.6342648 0.05526739 -0.6670802 -0.7429331 -0.9653963 1.72562e-4 -0.2607873 -0.9661284 -6.69974e-5 -0.2580622 0.5244906 0.006962299 -0.8513879 0.3321781 0.025384 -0.9428751 0.8456305 -0.006932199 -0.5337238 0.6744654 -0.02203941 -0.7379775 -0.6575223 -0.02687555 -0.7529556 -0.8538794 -4.48297e-4 -0.5204707 -0.7076566 0.01991838 -0.7062758 0.9659952 -3.19129e-4 -0.2585598 -0.324585 -0.4291552 -0.8428941 0.9548894 -0.2750478 0.1119601 0.991361 0.08148521 0.1027793 0.7380806 0.6645717 0.1165404 0.4039962 0.9074091 0.1157405 -0.4039812 0.9073646 0.1161416 -0.5038633 0.8574897 0.1040828 -0.961983 0.2407528 0.128945 -0.9050365 -0.4065491 0.1250078 -0.414455 -0.9049872 0.09604859 0.9596045 0.2500974 0.1288826 0 0.9932656 0.1158596 -0.8666341 -0.4724228 0.1605065 -0.4142009 0.3221879 0.8512536 -0.1202528 0.3755487 0.9189682 -0.3703296 0.8650705 0.3383919 -0.9017242 0.3461827 0.2589424 -0.7802661 0.6025239 0.167779 -0.3774565 0.9188084 0.1154024 -0.6514716 0.7518283 0.101681 -0.6565099 0.7454565 0.1152799 -0.6422347 0.7221111 0.2570803 -0.9239822 0.3712868 0.09166812 -0.7741616 0.6126424 0.1591951 -0.8384388 0.5370941 0.09246933 -0.3193346 0.07726377 0.9444871 0.6048056 0.5613445 0.5648916 0.100053 0.7572302 0.6454392 -6.47061e-5 0.4553452 0.8903149 -0.2916051 0.4966698 0.8174874 -0.245966 0.8122677 0.5288874 0.4575065 -0.8882945 0.0402612 0.1142103 0.6260019 0.7714128 0.9361026 -0.2846885 -0.206554 -0.7267574 -0.3508391 -0.5905386 -0.1505731 -0.9831179 -0.1039562 -0.1275844 -0.7774023 -0.6159285 0.8955523 -0.3485985 -0.2765233 0.6051264 0.1428115 0.7832157 0.2742419 -0.1442518 0.9507801 1.18054e-5 0.9986316 -0.05229705 -0.04862523 0.9987651 0.01019996 0.9659261 0 -0.2588182 0.9070729 0 -0.4209737 -0.9070298 0.002008914 -0.4210618 -0.001851081 -0.9986537 -0.05184113 -9.853e-7 0.9986296 0.05233669 -0.2980523 1.34977e-4 -0.9545496 -0.01393431 -0.9898535 0.1414071 -0.9659019 0.001354336 0.2589049 0.9033091 -0.01955533 0.4285444 -0.4115606 0.01041513 0.911323 -0.9221675 -0.01051437 0.3866479 -1.07622e-6 -0.9986295 0.05233699 1.07624e-6 -0.9986296 0.05233687 0.9659266 0 0.2588163 0.961696 -0.004948675 0.2740738 -0.2289612 -0.06515669 0.9712526 -0.9645292 -8.88546e-6 0.2639765 -0.965982 1.76284e-5 -0.2586094 -0.9659274 -9.05703e-5 -0.2588135 0.006014227 0.999961 -0.006474256 -0.005816698 0.9999808 0.002147912 0.00261718 0.9999859 -0.004632413 0.01372653 0.9998624 0.009318292 -0.2770544 5.49597e-4 -0.9608542 -0.2830275 -1.71739e-4 -0.9591118 -0.3275259 0.001305937 -0.9448414 -0.3127961 -0.001440405 -0.9498192 -0.332275 2.73171e-4 -0.9431825 0.3076916 0.002844631 0.9514819 -0.1570897 0.02161705 -0.9873477 -0.2962266 -0.007253468 -0.9550902 -0.2929986 -0.002613484 -0.9561093 -0.2997662 -0.003675043 -0.9540056 0.02690714 -0.04593169 -0.9985822 -0.0659492 0.9976049 0.02086561 -0.9447312 0 0.327846 -0.9999423 5.83394e-4 0.01073414 -0.2115082 -0.09208738 -0.9730284 -0.1140775 -0.1509378 -0.981939 -0.2592526 -0.02587497 -0.9654629 -0.1524274 -0.05043649 -0.9870269 -0.2942873 -0.009774386 -0.955667 -0.2539356 0.04025173 -0.9663832 -0.09561264 0.1889783 -0.9773154 -0.08261567 0.1197243 -0.9893639 -0.2669408 0.03933036 -0.9629101 -0.2033924 0.1261059 -0.9709423 0.9668675 0.001400887 -0.2552752 0.03043824 0.0141552 -0.9994365 0.8838782 -0.001158714 -0.4677157 0.7467693 -0.02368456 -0.6646615 3.58841e-5 0.9986309 -0.05231153 0.001202106 0.998543 -0.05394947 -0.001934707 -0.9987944 -0.0490536 0.9079526 0.04521423 0.4166269 -0.9447312 0 0.3278462 0.2857713 -0.01169753 0.9582265 0.3542401 0.005379974 0.9351391 0.09225231 0.9912519 0.09438878 0.07627618 0.9895222 0.1225882 0.3317817 1.6257e-4 0.9433562 0.3397895 -3.18568e-4 0.9405015 0.314962 -0.001340031 0.9491034 0.03663522 -0.2218615 0.9743898 0.2222083 -0.06172627 0.9730434 0.09049421 -0.1472734 0.9849474 0.244471 -0.02860933 0.9692345 0.0702843 -0.0525152 0.9961438 0.07670199 -0.0741952 0.9942897 0.3915473 -0.001014828 0.9201574 0.4302574 0 0.9027063 0.997165 0.01280093 0.07414972 0.4309115 -6.2486e-5 0.9023942 0.8886796 -0.01209545 0.4583691 0.6942787 5.21698e-5 0.7197063 0.2583068 0.0464828 0.9649441 0.2642742 0.02836894 0.9640303 0.2291409 0.05878114 0.9716168 0.07302808 0.2628874 0.9620588 0.1186905 0.01782053 0.9927714 0.07657736 0.01138257 0.9969987 -0.3923609 0.4094054 -0.8236748 0.5972461 -0.3804239 0.7060983 0.5972415 -0.3804504 0.7060879 -0.3797609 0.8987104 -0.2193201 -0.3393699 0.658319 -0.6718959 -0.603439 0.7902696 -0.1064684 0.03615975 0.1595159 -0.9865329 0.07681119 0.08722543 -0.9932229 0.02269804 0.2237527 -0.9743816 0.0836032 0.1099697 -0.9904127 0.07789862 0.1176616 -0.9899938 0.01911443 0.2730037 -0.9618232 0.09776157 0.1187694 -0.9880974 0.04459345 0.2775703 -0.9596699 0.03381264 0.2904625 -0.9562889 -0.0672034 0.7829678 -0.6184215 -0.5372407 0.8300739 -0.1494989 -0.05903166 0.6729657 -0.7373145 -0.1051351 0.6582486 -0.745423 -0.2838169 0.749746 -0.59777 -0.3735653 0.838519 -0.3966546 -0.2683733 0.8207423 -0.504339 -0.2085719 -0.7247266 -0.6567109 -0.1778039 -0.7592114 -0.6260862 -0.4252336 -0.8383386 -0.3411231 -0.1937134 -0.8525515 -0.4854186 -0.2666692 -0.7445752 -0.6119603 0.08402681 -0.1089391 -0.9904907 0.02853173 -0.2957137 -0.9548504 0.04342871 -0.2797307 -0.9590958 0.03691744 -0.2088782 -0.9772446 0.06482446 -0.004680216 -0.9978858 0.1529961 -0.03090429 -0.9877436 0.07428723 -0.06323659 -0.9952299 0.08202618 -0.05642879 -0.9950314 0.03018468 -0.178403 -0.9834944 0.104368 -0.06234365 -0.9925828 0.9854731 -0.09809499 -0.1386367 0.6939066 0.5488387 -0.466122 0.3714849 -0.1527214 0.9157921 -0.4829397 -0.8365225 -0.2588427 -0.4829305 -0.8365306 -0.2588336 -0.4829624 -0.8365168 -0.2588189 0.4829646 0.8365148 0.2588209 0.4829639 0.836516 0.2588185 0.482962 0.8365172 0.2588184 -0.01268094 0.1512637 0.9884122 -0.01245892 0.1526578 0.9882006 -0.04972261 0.1285886 0.9904508 -0.02787208 0.1932713 0.9807494 -0.02276086 0.2311947 0.9726412 -0.03597068 0.2205762 0.9747062 -0.1092873 0.117715 0.9870154 -0.05224603 -0.04337233 0.9976919 -0.06099152 -0.08388841 0.9946069 -0.06180119 0.001586437 0.9980873 -0.1481389 -0.02719324 0.9885927 -0.1070352 -0.1142265 0.9876719 -0.03791576 -0.2986471 0.9536102 -0.03978341 -0.2035176 0.9782627 -0.07061785 -0.1340574 0.9884543 -0.04126131 -0.1402095 0.9892618 -0.03118675 -0.2140216 0.9763309 0.6794393 -0.7318969 0.05185925 0.6807638 -0.7306141 0.05257123 0.2956614 -0.8021308 0.5188165 0.3721472 -0.8793826 0.2969729 0.02238976 -0.6490548 0.7604123 0.4522535 -0.8462902 0.2815306 0.3467534 -0.8302543 0.4363943 -0.0218091 0.0377745 0.9990484 0.4829632 -0.8365161 0.2588191 0.482962 -0.8365167 0.2588195 0.4829626 -0.8365165 0.2588194 -0.482964 0.8365157 -0.2588192 -0.4829635 0.8365159 -0.2588193 -0.4829632 0.8365162 -0.2588189 -0.4829636 0.8365159 -0.2588196 -0.6811125 0.7303067 -0.05232536 1.34896e-4 -4.24994e-5 1 1.91302e-4 -2.61484e-4 1 4.33332e-4 -2.0475e-4 0.9999999 0.006593346 -0.01787114 0.9998186 -0.3798839 -0.9058202 -0.1875579 0.001149535 3.62545e-4 0.9999994 -0.9304348 -0.2896161 -0.2245303 0.4692032 -0.8828649 -0.01994818 0.7209489 -0.6840561 0.1109052 0.6321567 0.7660015 0.1167036 -0.8313791 0.5477488 0.09370255 0.05906903 -0.9982534 -0.001097857 -0.4714743 0.881776 -0.01353609 0.8205239 0.5592687 -0.1181493 -0.9866901 0.1625801 -0.003236055 -0.9594623 0.2782431 -0.04486715 0.3493866 -0.936327 0.03494 0.004801273 0.008316278 0.9999539 -0.6280788 0.3270199 0.7060985 -0.7301201 0.5240233 0.4385479 -0.1326104 -0.3412322 0.9305778 -0.001381754 0.008222281 0.9999653 -0.9338155 0.3577545 4.88763e-4 -5.99836e-6 2.53275e-5 1 0 0 1 -1.23881e-7 0 1 -9.81033e-5 4.81221e-4 0.9999999 9.17316e-5 4.32734e-4 1 7.87453e-7 -4.31811e-6 1 -1.95332e-7 -2.99584e-6 1 -2.5509e-7 -2.95278e-6 1 -4.38709e-7 1.93108e-6 1 -4.77728e-7 -2.2926e-6 1 0 5.03119e-7 1 0.9818183 0.1898224 4.90342e-4 0.7838633 0.4157128 0.4612389 -0.6253241 -0.772676 0.1092782 -0.9808641 -0.166478 0.1009491 0.8301323 -0.553433 0.06776738 0.888472 -0.442958 0.1200238 0.8220803 0.5641708 0.07678186 0.7394679 0.6658165 0.09937638 0.3531665 0.9318017 0.08377981 0 0.9955354 0.09438914 -0.7354743 0.6715106 0.09028339 -0.7400143 0.6663221 0.09161704 -0.9469157 0.3076691 0.09322249 0.233744 -0.9653822 0.1157627 -0.4050954 0.9098393 0.08994519 -0.07823449 -0.3313678 0.9402525 0 0 1 0.0311982 -0.07728004 0.9965212 -0.4701525 -0.8810571 0.05191421 0.394194 0.2193416 0.8924688 -1.49322e-5 -6.31984e-5 1 1.23382e-5 -3.76492e-4 1 0 0 1 0 0 1 0 0 1 0 0 1 2.092e-4 6.15427e-4 0.9999998 -1.09204e-5 -1.43926e-4 1 4.24231e-6 -4.39195e-6 1 1.95744e-4 -0.001407206 0.999999 -0.6968091 0.02190715 0.7169221 -0.1316515 0.9752433 -0.1776745 0.5425112 0.8383793 -0.05293291 0.688798 0.01963156 0.7246875 0.6753246 -0.2129876 0.706097 -0.6551077 0.269883 0.7056891 -0.001125752 4.30904e-4 0.9999994 -0.9398164 0.3416799 1.98075e-4 0.1742237 -0.9846498 0.01052713 0.4652681 0.8303359 0.306705 -0.06877839 0.997632 8.08053e-5 -0.06791019 0.9976914 -3.41376e-4 0.05903923 -0.9982557 2.65644e-5 0.9482798 -0.2307717 0.2179676 -0.1708712 -0.9549015 -0.2428292 0.3532557 -0.9275422 0.121967 -0.03050947 -0.04308533 0.9986054 0.1569108 0.008059978 -0.9875799 0.7088862 0.02656966 -0.7048223 -0.4523025 0.8439055 0.288524 0.3428454 0.6621184 -0.6663755 0.609986 -0.07656991 -0.7887042 0.4447819 -0.6262222 -0.640324 0.1958474 -0.5589087 -0.8057698 0.2712899 -0.9039085 -0.330683 -0.007423996 -0.003074467 0.9999678 0.04193913 -0.1146963 0.9925149 0.6887977 -0.0196368 0.7246877 0.01553601 -0.01553267 -0.9997587 0.2576243 -0.07357215 -0.9634402 0.26216 -0.07025063 -0.962464 0.001554191 4.17063e-4 -0.9999988 0.001275479 0.001275599 -0.9999984 0.1231498 -0.1242827 -0.984575 8.26639e-4 -8.25989e-4 -0.9999994 1.28524e-5 1.07666e-5 -1 -0.005319118 -0.01984399 -0.9997889 -0.2258589 0.9730024 0.04747831 -0.1970322 0.0120179 -0.9803234 0.9548491 0.2773059 0.1066058 0.2114032 -0.576239 -0.7894665 0.9862172 0.03867536 0.1608722 0.2052468 -0.258255 -0.9440224 -0.8500968 0.02046942 0.5262286 -0.5626793 0.7716388 0.2965899 -0.7442799 0.5050335 0.4370225 -0.8096542 0.3555589 0.4669454 -0.837681 0.1817734 0.5150232 -0.8509849 -0.0379939 0.523814 -0.8368125 -0.1758285 0.5184875 -0.8086394 -0.3401027 0.480034 -0.6463409 -0.6831213 0.3399837 -0.2984869 -0.9473733 0.1157128 -0.8477556 -0.003432393 0.5303758 -0.8479869 -7.55407e-5 0.5300171 -0.8478718 1.44393e-4 0.5302014 -0.8479613 -0.00125277 0.5300568 0.3523382 0.1005788 -0.9304525 0.3660048 -0.04261898 -0.9296366 -0.8539241 -0.2648707 0.4479477 -0.7191619 -0.4179936 0.5550563 -0.6917721 -0.0353744 0.7212491 -0.1364752 0.02336215 0.990368 -0.0667141 0.002056181 0.9977701 -0.06225222 -0.001572906 0.9980592 -0.3860237 -0.008760511 0.9224473 -0.5133042 0.1256593 0.8489574 -0.4568712 -0.01427936 0.8894184 -0.4770222 -0.03802704 0.8780682 0.8475074 -0.003399372 -0.5307728 0.843931 -0.04768198 -0.5343286 -0.9254744 0.2774 -0.2579658 -0.4926622 0.8245256 0.2782829 0.8436111 0.05068647 -0.5345571 0.8472943 0.007416307 -0.531072 -0.182322 0.7541199 -0.6309214 -0.8388802 -0.3219087 0.4389247 0.8449672 0.03940236 -0.5333648 0.3294321 0.9343278 -0.1360376 0.2983406 0.9468339 -0.1204104 0.5529688 0.7831323 -0.2844814 0.5921493 0.7402126 -0.3185035 0.8067986 0.3626659 -0.466422 0.0348159 0.1876127 -0.9816259 0.1248039 0.7093611 -0.6937081 0.1474645 0.8100405 -0.5675286 0.1736346 0.9596208 -0.2213121 0.03568583 -0.1874594 -0.981624 0.09614819 -0.5374683 -0.8377849 0.09801328 -0.5513136 -0.8285209 0.04785323 -0.2728143 -0.9608759 0.1739082 -0.9841341 -0.03515881 0.3461523 -0.9269317 -0.1448317 0.9423245 -0.3330798 0.03290152 0.9294049 0.3686406 0.01763081 0.2254076 0.974209 0.01040923 -0.7310237 0.6822728 0.01039946 0.7061792 0.7061805 0.05118829 0.2587867 0.9657791 0.01733028 -0.2584882 0.9646568 0.05119693 -0.7070029 0.7069982 0.01733171 -0.9657831 -0.2587717 0.0173341 -0.7061884 -0.7061703 0.05120027 -0.6798339 0.05415755 0.7313637 0.05938935 -0.7033711 0.7083376 0.0599119 -0.1829782 0.9812898 0.1107259 -0.9516401 0.2865678 -0.9900998 -0.1040711 0.09418916 -0.7395026 0.6658565 0.09884881 -0.3535941 0.9313495 0.08694517 0.4921747 0.8672537 0.07506817 0.859934 -0.492428 0.1342697 0.240819 -0.9628595 0.1220974 -0.3132486 0.6361742 0.7050942 -0.2892381 0.1898935 0.9382334 0.2782143 -0.9605191 0 0.9778524 0.09671837 0.1856078 0.2339497 0.9688522 -0.08119779 -0.2850649 -0.7874184 0.546544 -0.199079 -0.4128836 0.8887602 -0.2564324 -0.1058163 0.9607526 -0.02228176 -0.09322816 0.9953954 -0.08991992 -0.03616869 0.9952921 -0.0869919 0.07832747 0.993125 0.1043133 -0.05768573 0.9928702 0.09833991 0.03318244 0.9945995 0.08657848 0.07795548 0.9931904 -0.03854262 0.09763813 0.9944754 0.03072929 -0.1293978 0.9911166 0.001126587 0.01974463 -0.9998044 9.12773e-4 -0.001089394 -0.9999991 -2.82892e-4 1.98382e-4 -1 2.50742e-4 0.001144111 -0.9999994 -0.001581668 0.002107083 -0.9999966 8.42621e-6 0.003176569 -0.9999951 1.88736e-4 -0.001241862 -0.9999993 0.001449584 0.00162959 -0.9999976 9.93641e-4 -0.002955496 -0.9999952 0.3248894 -0.2041426 -0.923457 0.3258593 -0.2165613 -0.9202809 0.3796644 0.1502734 -0.9128378 -0.7070041 -0.706997 0.01733821 -0.2586762 0.9653757 0.03371143 0.1827061 -0.9826169 0.03290522 -0.682214 -0.7310788 0.01039302 -0.3686655 0.9293949 0.01763027 -0.7599707 -0.6498519 0.01171028 -0.703064 0.707763 0.06908524 0.93656 0.3457192 0.0577383 0.9358279 -0.3493611 0.04661566 0.3461276 -0.9376161 0.0327394 -0.2586737 -0.9653764 0.03371131 -0.9742764 0.2253289 -0.003545641 -0.2920444 0.9563983 -0.003548443 0.7069993 -0.7069973 0.01751989 -0.09868216 -0.05697154 0.9934869 -0.1059259 0.03441596 0.9937784 0.1341053 0.07316005 0.9882629 0.1438133 0.05996531 0.9877864 0.08277142 0.07083344 0.9940481 0.0415948 0.1072306 0.9933637 -0.04495197 0.1042793 0.9935317 -0.1141614 -0.01199889 0.9933899 0.1074274 -0.9941747 -0.008726477 -0.9975211 -0.0698682 -0.008387804 -0.9981118 -0.05898672 -0.01713138 -0.9986634 0.05167722 9.51754e-4 0.9983631 0.05447947 -0.01740986 -1.33965e-4 -0.001335918 -0.9999991 0.002029955 0.001043736 -0.9999975 0.8191167 0.5735607 -0.008725404 0.5735418 -0.8191295 -0.008771598 0.573554 -0.8191212 -0.008734762 -0.5735534 0.8191218 -0.00872296 -0.819101 -0.5735832 -0.00871694 3.63807e-6 0 -1 -3.63806e-6 0 -1 0.8629907 -0.5051153 -0.01028239 0.8660017 -0.4999651 -0.008724808 -0.4999811 -0.8659924 -0.008728802 0.4999817 0.8659919 -0.008741378 0.4999815 0.8659921 -0.008744895 -0.8659998 0.4999682 -0.008729338 0.4999799 0.8659932 -0.008727312 -0.4999819 -0.865992 -0.008728265 -0.4999803 -0.8659929 -0.008727431 0.8659927 -0.4999808 -0.008725047 0.8191247 0.5735492 -0.008725106 -0.5735543 0.8191211 -0.008726835 -0.8191244 -0.5735496 -0.008726596 -0.316659 -0.9484993 -0.008726477 -0.9484987 0.3166608 -0.008726358 -0.9484988 0.3166607 -0.008726 0.3290339 0.9442768 -0.008838713 0.3166426 0.9484543 -0.01311832 0.9887936 -0.1491033 -0.007452785 0.7628043 -0.6457769 -0.03319549 0.2421046 -0.9696988 0.03270524 0.1217705 -0.9920032 -0.03319466 -0.9959797 0.08944129 0.004977703 -0.7740443 0.6305229 -0.05741554 -0.4675421 0.8814284 0.06699627 -0.9889103 0.1483553 -0.006870567 0.1001032 0.9946279 -0.02635836 -0.07989841 0.03118216 -0.9963153 -3.85352e-4 1.92195e-5 -1 3.11853e-6 1.21483e-5 -1 -0.3644458 -0.001026332 0.9312241 -0.3123815 -0.001073718 0.9499561 -0.3216833 7.52617e-4 0.946847 -0.3905049 4.92417e-4 0.9206007 -0.4091989 -0.001166701 0.9124445 -0.5087381 3.04357e-4 0.8609213 -0.5376608 -0.001512706 0.8431598 -0.5601001 5.58202e-4 0.8284248 -0.6136947 -2.40612e-4 0.7895435 -0.6649276 -8.75962e-4 0.7469073 -0.7101359 6.60721e-4 0.7040644 -0.7326682 -8.93665e-4 0.6805855 -0.7932207 -8.73424e-4 0.6089337 -0.8247056 -9.71794e-4 0.5655615 -0.7929665 8.81345e-4 0.6092647 -0.6300745 0.003539919 0.7765266 -0.5376653 0.001512587 0.8431571 -0.4048342 -2.56287e-4 0.9143902 -0.3644042 9.77888e-4 0.9312404 -0.3341556 -0.001180231 0.9425172 -0.06928175 -0.004060089 0.9975889 -0.09006798 -0.001270294 0.9959349 -0.1098492 0 0.9939484 -0.1382907 -3.11445e-4 0.9903917 -0.1449991 4.47549e-4 0.9894317 -0.1482372 0 0.9889519 -0.1449992 -4.46548e-4 0.9894317 -0.126188 4.8887e-4 0.9920063 -0.201619 -0.001182794 0.9794633 -0.1784657 9.55415e-4 0.9839457 -0.189624 -7.63002e-4 0.9818565 -0.2096672 -6.33718e-4 0.9777726 -0.2299858 8.66476e-4 0.9731936 -0.2315249 4.50046e-4 0.9728289 -0.2548525 -3.45543e-4 0.96698 -0.2653754 0.001600861 0.9641439 -0.2799922 -1.43767e-4 0.9600023 -0.2654675 -0.001823544 0.9641181 -0.240106 -7.2471e-4 0.9707464 -0.2545736 0.001127421 0.9670528 -0.2590644 1.12357e-4 0.9658601 -0.3146959 0.002771854 0.9491886 -0.4104791 6.28057e-4 0.9118699 -0.8448171 -7.82028e-4 0.5350549 -0.9397236 5.62677e-4 0.3419347 -0.9593896 2.07728e-5 0.2820845 -0.9648652 -0.001628458 0.2627406 -0.9424844 3.67048e-5 0.3342503 -0.8883678 -7.66625e-4 0.4591319 -0.9112079 -7.31552e-4 0.4119461 -0.8883175 7.62096e-4 0.4592291 -0.9205615 3.8702e-4 0.3905977 -0.9807453 7.60449e-4 0.1952902 -0.9827179 -1.35222e-4 0.1851094 -0.7677634 -8.55973e-4 0.640733 -0.7328819 8.64392e-4 0.6803554 -0.4656031 -0.001253247 0.8849928 -0.2300335 -0.001025617 0.9731823 -0.2182716 3.77494e-4 0.9758881 -0.1727401 -4.59799e-4 0.9849674 -0.1604804 3.99577e-4 0.987039 -0.1784389 -0.001015365 0.9839504 -0.1688814 1.94025e-4 0.9856364 -0.1604748 -4.10901e-4 0.9870399 -0.1579877 0 0.9874411 -0.2575102 -2.73894e-4 0.9662756 -0.1891245 8.1716e-4 0.9819529 -0.1984386 -6.42695e-4 0.9801132 -0.2101126 8.74056e-4 0.9776768 -0.1165491 0 0.9931849 -0.2314592 3.87756e-4 0.9728446 0 -0.011913 -0.9999291 -5.82348e-4 -0.04915976 -0.9987908 0.003325581 -0.02200436 -0.9997524 -3.30811e-4 -0.06412357 -0.9979419 9.11119e-4 -0.05780494 -0.9983276 -1.69632e-4 -0.03700113 -0.9993153 6.42145e-5 -0.05210953 -0.9986414 2.62898e-4 -0.07458949 -0.9972143 -9.36478e-5 -0.09368991 -0.9956015 -2.46867e-4 -0.1004355 -0.9949436 2.90796e-4 -0.1021743 -0.9947665 0.0028885 -0.1318632 -0.9912638 8.74597e-4 -0.1411365 -0.9899898 0.001788616 -0.134423 -0.9909225 -0.001450419 -0.200627 -0.9796667 -0.001141786 -0.229117 -0.9733982 5.4797e-4 -0.2105007 -0.9775936 -0.1045137 0.1435599 -0.9841075 0.001741886 -0.1734064 -0.9848489 -6.31764e-4 -0.1984733 -0.9801062 3.49031e-4 -0.2018538 -0.9794156 0.00106585 -0.2898941 -0.9570581 0.004521608 -0.3897122 -0.9209257 0.003240644 -0.4604362 -0.887687 -0.00364691 -0.5332376 -0.8459576 0.003577291 -0.397623 -0.9175419 0.004618406 -0.4749332 -0.8800098 0.05895829 -0.6332204 -0.7717226 0.05768662 -0.6260343 -0.7776589 0.007893681 -0.6958457 -0.7181479 0.02089184 -0.7542917 -0.656207 -0.00821042 -0.8481623 -0.5296728 9.80789e-4 -0.6971859 -0.7168897 0.001020669 -0.6969846 -0.7170854 0.00238943 -0.5502481 -0.8349978 -7.29062e-4 -0.5404404 -0.841382 -9.44376e-4 -0.4981405 -0.8670959 -7.70765e-5 -0.4647814 -0.8854255 -4.40143e-5 -0.4003317 -0.9163703 -1.74991e-4 -0.40053 -0.9162837 6.27968e-5 -0.4370292 -0.8994473 8.41479e-5 -0.4940418 -0.8694382 7.1705e-4 -0.5465636 -0.8374173 -9.74637e-4 -0.506461 -0.8622624 -2.13424e-4 -0.5023371 -0.8646718 1.64838e-4 -0.5263322 -0.850279 0.001373469 -0.5435572 -0.8393712 -0.001027226 -0.6067543 -0.7948888 -1.97346e-4 -0.6001314 -0.7999014 -7.49904e-4 -0.6500893 -0.7598576 4.36561e-4 -0.7219893 -0.6919041 0.004016101 -0.8673961 -0.4976022 -0.02961272 -0.9388074 -0.3431674 -0.001575469 -0.6327282 -0.7743724 -0.00138998 -0.6998154 -0.7143225 -0.007076144 -0.8396514 -0.5430796 3.77923e-4 -0.4688852 -0.8832592 -1.08697e-4 -0.465251 -0.8851788 -8.95765e-4 -0.437849 -0.8990481 3.25173e-5 -0.3711381 -0.9285777 5.54662e-4 -0.3636176 -0.9315482 -0.001222133 -0.3305189 -0.9437986 -7.5887e-4 -0.3277475 -0.9447652 -1.88668e-4 -0.3305382 -0.9437927 0.003718316 -0.3179075 -0.9481145 4.12779e-4 -0.3009973 -0.9536249 1.21221e-4 -0.3201284 -0.9473742 -2.2398e-4 -0.3024861 -0.9531538 -0.001822352 -0.1847091 -0.9827916 0.01492106 -0.4647543 -0.8853139 0.01281207 -0.5755622 -0.8176577 -0.003884196 -0.5777412 -0.8162108 0.009741187 -0.6666799 -0.7452805 0.002844274 -0.3820682 -0.9241298 -0.005715429 -0.4194195 -0.9077747 0.006235599 -0.3120784 -0.9500359 -0.007548034 -0.3632744 -0.9316517 -0.005369842 -0.4542487 -0.8908588 3.35041e-4 -0.6333339 -0.7738787 0.00152564 -0.6590937 -0.7520594 -0.005106091 -0.6115521 -0.7911877 -0.003919124 -0.4888768 -0.8723441 -0.004342675 -0.4883501 -0.872637 -0.005758643 -0.3999323 -0.9165266 -0.003475189 -0.3316028 -0.9434127 0.005227029 -0.3456462 -0.9383504 -0.01370513 -0.284124 -0.9586896 -2.26282e-4 -0.6090034 -0.7931676 -0.05951446 -0.3411664 -0.938117 -5.8782e-5 -0.1354266 -0.9907874 -0.05753916 -0.2305478 -0.9713584 0.06424671 -0.01435279 -0.9978309 -5.39731e-4 -0.2080132 -0.9781259 4.63128e-4 -0.1880964 -0.9821506 0.002303242 -0.178853 -0.9838731 4.67603e-5 -0.1152775 -0.9933334 1.72072e-4 -0.1177213 -0.9930467 -9.28419e-4 -0.1259972 -0.9920302 7.08738e-4 -0.1815978 -0.9833726 -9.37413e-4 -0.1796704 -0.9837265 -0.006871163 -0.1874771 -0.982245 -0.2357577 0.9704409 -0.05160367 5.46308e-4 -0.02190005 -0.9997601 -3.49468e-4 -0.554468 -0.8322051 1.26642e-4 -0.3411129 -0.9400224 -1.3614e-4 -0.359966 -0.9329654 -1.92014e-5 -0.2613028 -0.9652569 -3.71829e-4 -0.2904052 -0.9569038 7.65588e-5 -0.4139446 -0.9103022 0.009126067 0.4454416 0.8952646 0.001142799 0.4061722 0.913796 0.0128045 0.3830224 0.9236504 0.01158326 0.549544 0.8353846 0.01325857 0.637197 0.770587 -0.01297289 0.625151 0.780396 0.01481473 0.6738612 0.7387095 -0.01260393 0.7292902 0.6840884 -0.002398669 0.7039984 0.7101975 -0.02126407 0.5513095 0.8340298 -0.01499766 0.4422305 0.8967761 -5.38289e-4 0.5143728 0.8575665 5.60051e-4 0.4765651 0.879139 -3.94163e-4 0.4606414 0.8875863 6.79894e-4 0.5070595 0.8619109 8.18962e-4 0.5687473 0.822512 9.4119e-4 0.6351992 0.7723478 0.001171648 0.6398556 0.7684944 3.46385e-5 0.6036142 0.7972766 -2.50286e-4 0.6025742 0.7980628 4.4368e-4 0.5316004 0.8469952 -0.001823842 0.3896579 0.920958 8.73011e-4 0.3308455 0.9436846 -6.36564e-4 0.3613734 0.9324211 8.57747e-5 0.3766017 0.9263753 -3.72974e-4 0.3133558 0.9496358 -0.001128196 0.2394741 0.9709021 5.99953e-4 0.2132921 0.9769884 1.65782e-4 0.2036328 0.9790474 0.006709635 0.2466042 0.9690932 0.005315363 0.2989044 0.9542683 7.22675e-6 0.3230791 0.946372 0.007522106 0.5373198 0.8433451 -0.03641963 0.4363762 0.8990271 -0.02187824 0.5452197 0.8380078 0.007273972 0.3091584 0.9509828 8.76038e-4 -0.6322174 -0.7747906 -0.06586319 0.5649439 0.8224965 0.00147289 0.4473515 0.894357 -0.008525669 0.4493862 0.893297 0.006502807 0.360512 0.932732 6.13602e-4 0.3627451 0.9318883 -3.1125e-4 0.2942203 0.9557377 -0.004679501 0.2990667 0.9542208 0.002899706 0.3305802 0.9437735 0.002074062 0.3317539 0.9433638 -7.91638e-4 0.6310356 0.7757536 0.03925824 0.5344964 0.8442586 5.08835e-4 0.7097423 0.7044613 1.24071e-4 0.6773137 0.7356944 0.02416831 0.5894453 0.8074467 -0.00548166 0.5115562 0.8592324 0.005249321 0.4343796 0.9007146 2.26785e-4 0.6450022 0.7641807 -0.01476931 0.556735 0.8305589 -2.13854e-4 0.01192903 0.9999289 5.33714e-5 0.05614584 0.9984226 3.75922e-5 0.09581905 0.9953988 -1.89075e-4 0.1756139 0.9844591 1.94883e-4 0.1457834 0.9893165 -9.49109e-5 0.1236273 0.9923288 5.06096e-4 0.1857638 0.9825944 -5.38825e-4 0.2138537 0.9768657 5.17745e-4 0.2292581 0.9733656 7.08985e-4 0.2618376 0.9651118 -0.001107096 0.3072804 0.9516184 0.001072406 0.584087 0.8116903 0.001407206 0.7055597 0.7086491 0.001930177 0.777834 0.6284669 2.82163e-4 0.7716754 0.6360165 0.00642693 0.8442588 0.5358972 -0.02036535 0.5113081 0.8591561 -2.06136e-4 0.1007334 0.9949135 -0.007692694 0.02896094 -0.9995511 -0.001898884 0 -0.9999982 5.96641e-4 0 -0.9999999 5.85321e-4 0 -0.9999998 -0.001898884 -0.001871943 -0.9999965 -0.008066952 0.02896332 -0.999548 -0.4205441 0.2113921 -0.8823017 -0.003627717 -0.9999518 -0.009128034 1.86961e-5 -0.9999616 -0.008773565 -2.21953e-6 0.9999619 -0.008727073 -4.07461e-4 0 -1 0.2715408 0.1360251 -0.952766 -3.94526e-4 0 -1 -7.71344e-4 -3.10478e-5 -0.9999998 0.9999609 -6.67855e-4 -0.008828997 0.9999619 0 -0.008726418 3.925e-6 -0.999962 -0.008725702 -0.001987576 0.9999572 -0.009043037 8.76412e-4 0.9999613 -0.008765339 -0.9999592 0.001064956 -0.008972644 -0.999962 -2.82657e-4 -0.008724629 1.49661e-5 0.9999619 -0.008733689 -0.9999605 0 -0.008889973 -0.9999598 -0.001110255 -0.008899509 -1.32952e-5 0.9999613 -0.008808195 1.22933e-5 -0.9999616 -0.00876981 0.9999617 -1.19415e-4 -0.008753538 0.9999619 6.68763e-5 -0.008727192 0.999956 -0.002796411 -0.008968889 0.9999617 1.21237e-5 -0.008758962 6.386e-7 -0.999962 -0.008726954 2.9066e-6 -0.999962 -0.008726298 0.999962 0 -0.008726537 -0.4291734 -0.02144771 -0.9029675 -0.9339181 -0.3511077 -0.06723517 0.3695378 0.03362333 -0.9286072 -0.999962 -8.24294e-7 -0.008727014 -0.9999619 5.71917e-5 -0.008733987 -0.3538094 -0.2597066 -0.8985386 -0.3663759 -0.005034208 -0.9304534 8.25295e-4 -0.9996814 -0.02522927 0.9996287 -0.01173484 -0.02459323 0.9972928 -0.07329356 0.005933523 0.9996075 1.69592e-6 -0.02801758 0.9986256 -0.05080473 -0.01287978 0.9635668 0.2670795 0.01440984 0.2064087 0.9746615 0.08619892 0.1812843 0.9794085 0.08885526 0.1980572 0.9764848 0.08515119 0.2092766 0.9738195 0.08876395 0.2270836 0.9701201 0.08544075 0.181527 0.979636 0.08579856 0.1679599 0.981786 0.08880263 0.1513993 0.9844614 0.08896124 0.1549596 0.9841907 0.08576875 0.108565 0.9901332 0.08860057 0.09020829 0.9919615 0.08874142 0.1087602 0.9903738 0.08562093 0.09693592 0.9915879 0.08577221 0.07715553 0.9930724 0.08862429 0.05755025 0.9943924 0.08872288 0.0442062 0.9953542 0.08553361 -0.0321635 0.9955251 0.08885681 -0.03160607 0.9958998 0.08476227 -0.03699338 0.9955278 0.08692604 -0.07395821 0.9934244 0.08739721 -0.1119337 0.990004 0.08580875 -0.151177 0.9848297 0.08518344 -0.190536 0.9779835 0.08511394 -0.2296698 0.9694427 0.08621287 -0.08389788 0.9926773 0.08690816 -0.1260536 0.9879684 0.08960419 -0.1581134 0.983441 0.08856642 -0.1203615 0.988878 0.08737111 -0.1973867 0.9762912 0.08884829 -0.1687536 0.9819413 0.0855202 -0.2012234 0.9756181 0.08762717 -0.29944 0.9498223 0.09040665 -0.2916985 0.9526774 0.08554476 0.01005786 0.8057989 0.5921039 0.09097921 0.7571546 -0.6468691 0.09136074 0.7676205 -0.6343596 -0.1215819 0.9452095 -0.3029801 -4.60754e-4 0.6872559 0.7264153 -0.1682202 0.9145228 0.3678997 0.9355037 0.353209 -0.008726716 0.9355247 0.3531539 -0.008719742 0.9355124 0.3531861 -0.008726596 -0.002393543 -0.0075019 -0.999969 0.003701269 -0.006412327 -0.9999726 -0.9353797 -0.3535367 -0.008753895 -0.9355067 -0.3531987 -0.008832395 0.3532233 -0.9354968 -0.008899867 0.3531844 -0.9355131 -0.008725941 0.6128942 -0.7873211 -0.06698024 0.3565553 -0.9342333 -0.008746385 0.9355767 0.3530152 -0.008745133 0.9611766 0.2754365 -0.01655995 0.9418275 0.3357377 -0.01553332 -0.9353154 -0.3537057 -0.008799314 -0.9354591 -0.3533267 -0.008746325 -0.9402331 -0.3403004 -0.01254254 -0.935501 -0.3532162 -0.008726477 0.356571 -0.9342276 -0.008714318 0.4690982 -0.8831126 -0.00768429 0.3542472 -0.9350476 -0.01396429 0.9355126 0.3531858 -0.008723914 0.9355223 0.3531598 -0.008726596 -0.007985413 -5.04547e-4 -0.999968 -0.007484436 6.13344e-4 -0.9999719 -0.001038372 0.003047347 -0.9999948 0.004763603 0.004392325 -0.9999791 0.8879925 0.4597946 -0.007650792 0.05441319 0.02056491 -0.9983068 0.5270545 0.1989889 -0.8262065 -0.05451041 -0.0205633 -0.9983015 -0.5270516 -0.1989829 -0.8262097 -0.9055878 -0.4240554 -0.009371161 -0.3544331 0.9345575 -0.0312969 0.9355604 0.3529368 -0.01274639 -0.3531884 0.9355116 -0.008726239 -0.3505294 0.936506 -0.009265244 0.04889285 0.01863801 -0.9986302 0.04890179 0.01863944 -0.9986297 0.0489068 0.01863902 -0.9986295 -0.9355074 -0.3531994 -0.008726596 -0.9355349 -0.3531265 -0.008728623 -0.9355115 -0.3531881 -0.00874108 -0.9355636 -0.353044 -0.008984923 -0.9355221 -0.3531603 -0.008727073 -0.2117673 -0.7454109 -0.6320737 0.3052519 -0.05388975 -0.9507457 0.09913939 -0.2388513 -0.9659821 -0.9376725 -0.3473767 -0.009994983 -0.9354932 -0.3532295 -0.009026169 0.7373981 -0.09056192 -0.6693599 0.9355097 0.3531935 -0.008726418 0.9355201 0.3531659 -0.008726358 0.9355107 0.3531884 -0.008819162 -0.3531827 0.9355137 -0.008726179 -0.9354589 -0.3531823 -0.0133782 -0.9355078 -0.3531983 -0.008726716 0.2315579 -0.9727141 -0.01443678 0.03185617 -0.09421032 -0.9950426 0.3531808 -0.935514 -0.008765101 -0.9355099 -0.3531926 -0.008727252 -0.9355024 -0.3532129 -0.008725404 -0.3191163 0.9436991 0.0871604 -0.3238853 0.9372212 0.1292856 -0.4040399 0.1879929 0.8952153 -0.3911989 0.2120909 0.8955339 -0.3569519 0.517615 0.777599 -0.3639044 0.7713737 0.5220693 -0.344687 0.9215013 0.1789593 -0.4040216 0.187984 0.8952255 -0.4424577 0.7561742 0.4821118 -0.5245533 0.4691075 0.7104802 -0.5594813 0.1704438 0.8111287 -0.5475326 0.2197381 0.8074176 -0.9037688 0.1346242 0.4062983 -0.6683984 0.4964736 0.553857 -0.9470417 0.2628558 0.184442 -0.3845492 0.9149256 0.1226099 -0.8110494 0.5398052 0.225409 -0.5126813 0.8507867 0.1154119 -0.8122689 0.2049213 0.5461013 -0.6411149 0.1159366 0.7586373 -0.2505928 0.150381 0.9563414 -0.3951391 0.5004534 0.7703322 -0.6685903 0.1770374 0.7222499 -0.3637127 0.4954566 0.7888191 -0.42151 0.6750386 0.6055182 -0.4513278 0.6941583 0.5607562 -0.4423781 0.8377513 0.3201162 -0.7082078 0.4933096 0.5050618 -0.3268856 0.9383245 0.112664 -0.2866092 0.8569601 0.4283394 -0.2043517 0.08056747 0.9755765 -0.01766479 0.360908 0.9324342 -0.1766408 0.4309962 0.8848957 -0.4112305 0.9075139 0.08548688 -0.02362155 0.163105 0.986326 -0.02928167 0.1729266 0.9844994 0.003264546 0.2270888 0.9738686 -0.06130594 0.1986961 0.9781419 -0.1465507 0.04796928 0.9880395 -0.02600413 0.2894126 0.9568512 -0.01520448 0.3464534 0.937944 -0.02273637 0.1168885 0.9928848 -0.08053398 0.02203118 0.9965084 -0.05455124 0.07702273 0.995536 -0.06880545 0.04576784 0.9965798 -0.004038572 0.2717949 0.9623467 -0.01201564 0.2977904 0.9545557 -0.06390506 0.08372896 0.9944374 -0.1690381 0.6700696 0.7227953 -0.3910673 0.8904038 0.2329111 -0.3634575 0.9035272 0.2270182 0.4072523 -0.7896308 -0.458943 0.4221596 -0.2866311 -0.860014 0.3882055 -0.8972744 -0.2102262 0.4468944 -0.5509115 -0.7048276 0.3265668 -0.210146 -0.9215166 0.3257883 -0.1346448 -0.935806 0.4575302 -0.6112074 -0.6458263 0.01996904 -0.2124372 -0.9769707 0.09836524 -0.03100752 -0.9946673 0.06210809 -0.03902429 -0.9973062 0.1023816 -0.03554725 -0.9941099 0.07998794 -0.04268628 -0.9958814 0.07963401 -0.01674991 -0.9966835 0.01353782 -0.3028711 -0.9529355 0.04817491 -0.07549065 -0.9959822 0.04701852 -0.6748363 -0.7364681 0.5285633 -0.8454031 0.07690453 0.3329295 -0.8038084 -0.4930012 0.2157399 -0.002902626 -0.9764466 0.212146 -0.009597182 -0.9771909 0.1317169 0.001083135 -0.9912869 0.1075195 -2.02372e-4 -0.994203 0.00856477 -0.01374149 -0.9998689 0.1300124 -2.99796e-4 -0.9915123 0.1159255 2.64538e-5 -0.993258 0.3673332 0.05594539 -0.9284054 0.11466 -0.001099765 -0.9934042 0.1189633 0 -0.9928987 0.1235578 0 -0.9923374 0.579204 2.54265e-4 -0.8151827 -0.1970043 -9.83016e-7 -0.9804027 0.1328705 1.6576e-6 -0.9911335 0.1682906 -1.24923e-4 -0.9857375 0.2804924 0.025303 -0.9595227 0.1814938 5.04812e-4 -0.983392 0.04338425 0.01347249 -0.9989677 0.183563 -0.01134622 -0.9829426 0.2014248 -1.00159e-4 -0.979504 0.2266749 -3.35561e-5 -0.9739705 -0.2252119 0.003115713 0.9743049 0.1240416 -0.002750813 -0.9922733 0.1308034 0.002055346 -0.9914062 0.134648 -5.22939e-4 -0.9908934 0.00660479 -0.08585822 -0.9962856 0.132472 6.39834e-4 -0.9911866 0.1305827 -0.001007437 -0.9914369 0.1197428 -0.002378821 -0.9928022 0.1156878 -3.33849e-6 -0.9932857 0.1270779 -4.11802e-4 -0.9918927 0.1310215 2.98055e-4 -0.9913796 0.118139 -6.2783e-5 -0.9929971 0.1315478 -5.89612e-4 -0.9913097 0.1516618 2.88106e-4 -0.9884324 0.1313298 0.001626133 -0.9913374 0.3497242 -0.002691686 -0.9368488 0.3491875 0.005605518 -0.9370362 -0.3009675 -0.005568683 0.9536182 0.2994208 8.81722e-4 -0.9541209 0.3222793 6.72029e-4 -0.9466444 0.4267525 -3.87841e-4 -0.9043684 0.4071152 -0.006644785 -0.9133527 0.4213744 0.001306533 -0.9068858 0.4612345 -3.45904e-4 -0.8872783 0.5572986 -6.52127e-4 -0.830312 0.5604939 -8.05467e-4 -0.8281582 0.5835518 -0.001231849 -0.812075 0.3497104 -0.005970358 -0.9368389 0.338485 0 -0.9409718 0.3219169 0.01315289 -0.9466766 0.2752134 6.80008e-5 -0.9613832 0.2431433 0 -0.9699904 0.2226601 0 -0.9748962 0.243138 -0.001770853 -0.9699901 0.2678315 0.005681157 -0.9634491 0.2226517 0 -0.974898 0.2431372 0.002252638 -0.9699894 0.2753904 1.74697e-4 -0.9613324 0.300582 -0.01366227 -0.9536581 0.2908417 2.53174e-4 -0.9567713 0.2938957 4.82688e-5 -0.9558376 0.2842223 -1.97005e-5 -0.9587584 0.2751703 1.6078e-4 -0.9613956 0.2226608 1.61912e-6 -0.974896 -0.1970337 2.91361e-6 -0.9803968 0.1783958 0.001102447 -0.9839583 0.1961024 -9.72007e-5 -0.9805834 0.1737304 -1.10825e-5 -0.9847933 0.1648031 9.00571e-5 -0.9863265 0.1570011 6.26314e-5 -0.9875985 0.1505809 -2.20856e-4 -0.9885978 0.3069068 0.01558548 -0.9516119 0.2324715 0.02999663 -0.9721406 0.166418 1.4894e-4 -0.9860554 0.1620552 3.17326e-4 -0.9867817 0.1568062 -5.205e-4 -0.9876292 0.17195 -1.86504e-4 -0.9851058 0.1328645 -0.08768105 -0.9872483 0.1735574 -2.21734e-4 -0.9848238 0.3617451 8.67739e-4 -0.9322767 0.4802556 -8.97828e-4 -0.8771281 0.4602956 7.96897e-4 -0.8877654 0.5147247 7.38815e-4 -0.8573552 0.5139577 -9.24743e-4 -0.8578152 0.2505729 -4.40616e-5 -0.9680978 0.1934422 -4.32557e-4 -0.9811116 0.185132 6.26316e-4 -0.9827135 0.1424012 -2.90074e-4 -0.9898091 0.1413263 -9.93003e-5 -0.9899631 0.0988444 -1.99572e-4 -0.9951029 0.08880871 -6.94647e-5 -0.9960488 0.1060529 6.86017e-5 -0.9943605 0.1600441 0.001306533 -0.987109 0.3723168 0.003502368 -0.9280991 0.3863294 0 -0.922361 0.4691737 -0.01537597 -0.8829721 0.5673626 -3.01262e-4 -0.823468 0.651705 6.62908e-4 -0.7584723 0.6696485 -0.001320958 -0.742677 0.7001496 0.001426637 -0.7139948 0.7342657 -0.001147389 -0.6788613 0.765883 -0.001427114 -0.6429784 0.7360759 9.57472e-4 -0.6768984 0.6088612 4.80829e-4 -0.7932766 0.6724818 9.58867e-4 -0.740113 0.6094644 -0.001094818 -0.7928127 0.8014479 -0.001973032 -0.5980613 0.8383507 0.001139402 -0.5451302 0.8686902 -0.001932442 -0.495352 0.8998274 0.001848638 -0.4362422 0.968253 8.83807e-6 -0.2499723 0.9865353 4.28884e-5 -0.1635491 0.8999744 -0.001863181 -0.4359388 0.8378146 -0.001191258 -0.5459538 0.9492164 -3.26765e-6 -0.3146243 0.2565304 -0.001478195 -0.966535 0.2494448 -1.40714e-4 -0.968389 0.1632179 -6.85506e-4 -0.9865899 0.2234768 1.31873e-4 -0.9747093 -0.5827743 0.3413365 0.7374711 0.6454364 0.08525258 0.7590416 0.9601556 -0.1922798 -0.202805 -0.07345545 -0.4694406 -0.8799034 0.6209222 0.1495175 0.7694805 0.2726467 0.2267553 -0.9350112 0.3138914 -0.6906099 0.6515598 0.5584979 0.2542523 0.7895797 0.580161 0.4356196 0.6882215 0.5893385 0.4853768 0.6458247 0.2768033 -0.05592453 0.959298 0.4091492 -0.9112679 -0.04677319 0.01163059 -0.3487041 0.9371608 -0.001314222 -0.4357457 0.900069 -0.005984842 -0.5121135 0.858897 0.01076853 -0.5073442 0.8616763 0.01883298 -0.5923782 0.80544 -0.001237094 0.6520879 -0.7581424 0.02832132 -0.5712499 0.8202875 -3.0789e-4 -0.6825219 0.7308651 -0.02374666 -0.8113662 0.5840557 -0.007689297 -0.8037367 0.5949355 0.001402139 -0.8408505 0.5412657 0.0264675 -0.6285641 0.7773073 -0.0133804 -0.6348134 0.7725497 0.003501772 -0.5571836 0.8303819 -0.01165753 -0.4280491 0.9036803 -0.02361273 -0.555243 0.831353 -0.005665302 -0.3484199 0.9373215 -0.04406964 -0.5872607 0.8081973 0.02231639 -0.4653795 0.8848299 -0.007112026 -0.4754562 0.8797107 -0.002162158 -0.3980094 0.9173789 0.001340687 -0.2909676 0.956732 -0.002104103 -0.2923867 0.956298 0.001650214 -0.2502365 0.9681834 -0.009020388 -0.21313 0.9769823 -0.00283426 -0.2111929 0.9774403 0.02537548 -0.2426871 0.9697727 -0.001445114 -0.5974949 0.8018714 0.003524065 -0.3606743 0.9326851 -0.004108667 -0.3059701 0.9520323 -0.06328451 -0.5695081 0.8195459 -4.18412e-4 -0.6410626 0.7674886 6.02155e-4 -0.14629 0.9892416 1.30478e-4 -0.1010608 0.9948803 8.74234e-4 -0.08763378 0.9961525 1.1247e-4 -0.04193449 0.9991204 2.51674e-4 -0.2031816 0.9791411 -3.08526e-4 -0.2385764 0.9711237 2.02127e-4 -0.2841511 0.9587795 -8.8865e-4 -0.3071534 0.9516596 -5.39548e-4 -0.3858202 0.9225739 -1.72523e-4 -0.4604613 0.8876798 1.93895e-4 -0.6064804 0.7950986 1.94008e-4 -0.606478 0.7951003 2.06149e-4 -0.606501 0.7950827 1.97294e-4 -0.5715505 0.820567 -5.00936e-4 -0.3666415 0.9303622 8.81259e-4 -0.6433916 0.7655369 0.4372088 -0.8419492 -0.3161808 0.008605241 -0.5965016 0.8025658 -0.01263779 -0.5817176 0.8132928 0.006440341 -0.5276403 0.8494436 -0.01556134 -0.4992856 0.8662977 -1.85391e-4 -0.01452982 0.9998944 0.008197128 -0.6779806 0.7350342 4.28765e-4 -0.7842839 0.6204019 0.00375694 -0.6701399 0.7422254 0.7422508 0.5860589 0.3249595 0.6156762 0.4248406 0.6636666 0.6320746 0.4974117 0.5941913 0.5233275 0.3048232 0.7957456 0.6787986 0.6889061 0.2542459 0.2198016 -0.4307329 0.8753036 -0.3958669 -0.7034389 0.5903077 -0.4268291 -0.7970493 0.4272344 0.6159744 0.7877094 0.009459793 0.6121566 0.790736 -0.001085758 0.6828455 0.7069393 0.1842796 0.6123369 0.7905969 4.56707e-6 -0.6442472 -0.7631641 0.05026084 -0.6560547 -0.7547064 -0.003251671 -0.6542252 -0.7562999 2.0213e-4 -0.3669515 -0.6963886 0.6167574 -0.6898651 0.1214011 0.7136862 0.6465908 0.4050247 0.6464328 0.6069027 0.2312515 0.7603893 0.7767472 0.5336548 0.3344795 0.7208046 0.6390364 0.2684648 0.3888393 -0.9022601 -0.1863618 0.9587799 0.2806771 -0.04429131 -0.260179 -0.4572327 0.8504382 -0.5108515 -0.7293766 0.455017 -0.4108775 -0.6621608 0.6266759 0.651727 0.1778412 0.7373089 0.6054086 0.2764291 0.7463695 0.9660121 0.1906519 -0.1745644 -0.5041754 -0.5693277 0.6493637 -0.5453352 -0.5955418 0.5898641 0.6092104 0.1227862 0.7834452 0.6697932 0.3433793 0.6583827 -0.8133738 -0.5405743 0.2149484 0.2106189 -0.587864 0.7810606 -0.6315273 -0.6149212 0.4722766 -0.5858039 -0.6038913 0.5405083 -0.6194801 -0.5590825 0.5510637 -0.532738 -0.6643798 0.5242038 -0.2277966 -0.5461051 0.8061502 0.6667786 0.6557704 0.3540784 0.8462808 0.3620809 0.3907766 0.6529764 0.2371047 0.7193074 -0.4770648 0.8718867 -0.110558 0.502367 -0.01246362 0.8645648 -0.8155697 -0.4994715 -0.2921888 -0.591375 0.5802441 0.5599934 -0.5298066 0.5148417 0.6739755 -0.5397732 0.664536 0.5167561 -0.4393484 0.6752998 0.5924046 0.6983616 -0.371547 0.6117549 0.6144613 -0.215389 0.7589764 0.74961 -0.3233726 0.5775077 0.5980247 -0.3266751 0.7318811 0.7318201 -0.4065266 0.5469694 -0.1010413 -0.4968675 -0.8619243 -0.2306388 -0.9685065 -0.09381359 -0.4762088 0.7445824 0.4677845 -0.2974813 0.3318299 0.895206 -0.435948 0.6917399 0.5757129 -0.4433765 0.6926027 0.568963 -0.4844805 0.7347109 0.4748457 0.6914114 -0.4086753 0.5957641 0.509446 -0.1652253 0.8444913 -0.691833 0.7178838 0.07752436 -0.7049076 0.7092992 -2.0468e-4 0.5578835 -0.6744686 -0.4835889 0.6905543 -0.5874131 0.4219961 0.6664181 -0.7455782 -3.71167e-4 0.6721906 -0.7374184 0.06613612 0.6671289 -0.7449375 0.002693951 -0.8752247 -0.3663858 0.3158217 -0.4518646 0.7549197 0.4753049 -0.08105325 0.3855717 0.9191109 0.5919275 -0.2399013 0.7694603 0.6127705 -0.2709711 0.7423523 -0.6558372 0.7549003 -0.001779854 -0.6542385 0.7562882 1.3533e-4 -0.6567635 0.7540701 -0.006330788 -0.850833 -0.5253277 -0.01068633 -0.9368293 0.1090647 0.3323491 0.6310165 -0.7688259 0.103562 0.622702 -0.782273 0.01706713 0.6121675 -0.7907275 -0.001017749 -0.3910756 0.7876384 0.4761152 -0.3957293 0.8070721 0.4382157 0.4526743 -0.739097 -0.4988201 0.5628931 -0.07782804 0.8228574 0.4932827 -0.08104848 0.8660851 -0.5983305 0.8012446 0.002790033 -0.5930798 0.8047771 0.02429705 -0.7899453 -0.6059722 -0.09372448 -0.9515236 -0.2990872 0.07176196 0.6604936 -0.7301201 0.1751368 0.6409087 -0.7333629 0.2267491 0.5620307 -0.8260822 0.04134798 0.5624241 -0.8266249 0.01925301 0.5593527 0.8289174 0.004525065 0.5660316 0.8238174 0.03054863 0.5542224 0.8323686 1.68468e-5 -0.5978492 -0.8014137 0.01768088 -0.5950537 -0.8034716 0.01856309 -0.5953 -0.8033344 0.01648545 -0.4160236 0.9090205 -0.02461767 -0.935422 0.152722 0.3188446 -0.9943411 0.01594012 0.1050327 0.311731 0.9242722 0.2203289 0.6303132 -0.7746642 0.05099594 0.716806 0.6872785 -0.1176335 0.7652522 0.6437073 -0.005480051 0.7663918 0.6423549 0.004903852 -0.796234 -0.604952 0.006669402 -0.7889421 -0.6139003 0.0264011 -0.7904088 -0.6120422 0.02566128 -0.7989172 -0.6013789 -0.008656501 -0.7862735 0.6105476 0.09489864 -0.9096226 0.2952151 0.2922928 -0.7337787 0.6573578 0.1716088 -0.8348695 -0.550448 -1.87176e-4 -0.8348233 -0.5505181 5.10789e-6 -0.8347876 -0.5505724 1.16662e-4 -0.8348063 -0.5505431 9.25124e-4 0.7909218 0.61014 -0.04660362 0.6666571 0.7453647 4.75776e-6 -0.7030193 -0.7111694 -0.001401782 0.722964 0.6493976 0.2358088 -0.8226879 0.5669959 -0.04123455 -0.5302981 -0.6600328 0.5321097 -0.7572398 0.6479135 0.08243811 -0.7645574 -0.6433482 -0.03943532 -0.7517554 -0.6593969 -0.007723629 -0.7518583 -0.6593248 -5.51081e-5 -0.7519777 -0.6591852 -0.00212419 0.7289039 0.6842114 0.02353566 0.7180072 0.6960352 9.21199e-4 0.71417 0.6993545 -0.02940213 0.7337796 0.675948 0.06827837 0.6535588 -0.7085047 -0.2662368 0.7160058 -0.6980454 -0.008281588 0.7179366 -0.6961085 -1.16194e-4 -0.7492897 0.6621658 0.01007485 -0.7410625 0.6709914 0.02443128 0.002985119 -0.999638 -0.02673935 0.5499185 0.8306449 -0.08728522 0.8111189 -0.5848391 0.007045686 0.8091598 -0.5875888 -2.66459e-4 0.8112788 -0.5844792 0.01452565 -0.8342193 0.5508655 0.02500933 -0.8228911 0.5665651 0.04306244 -0.8347769 0.5505883 1.46113e-4 -0.8356856 0.5490428 -0.01348441 -0.8652168 -0.5005429 -0.02927243 0.7659902 -0.6428523 1.02321e-4 0.7654449 -0.6435016 -3.99986e-6 0.7655568 -0.6433644 -0.00228846 -0.7847473 0.6191127 0.02951574 -0.7933508 0.608759 0.002681553 -0.7951142 0.6064594 6.91603e-4 0.7702325 -0.5507161 0.3216423 -0.6443173 0.5907788 0.4856292 0.6424275 0.5552816 0.5281565 0.7798876 -0.4924615 -0.3863382 -0.9057545 -0.317528 0.2806865 -0.6095237 0.08621758 0.7880656 -0.6845185 0.2904465 0.6686369 -0.5425264 0.1915259 0.8179137 -0.7136983 0.08532476 0.6952371 -0.5016644 -0.03790867 0.8642314 0.3524064 0.1722784 -0.9198532 0.1984042 -0.6835904 -0.7023817 0.7181923 -0.4967409 -0.4872865 0.8284121 0.05125552 -0.5577692 0.6945509 0.3736157 -0.6148256 0.5239827 -0.03559029 -0.850985 0.3361929 -0.006820023 -0.9417685 0.2867798 -0.1010404 -0.9526533 0.3790925 -0.2501579 -0.890904 0.4111077 0.09791433 -0.9063131 0.7620664 0.2954817 -0.5761471 0.0284065 -0.06454116 -0.9975107 -0.06932002 -0.6654592 -0.7432085 -0.08203512 -0.01149308 -0.9965633 0.09161287 0.004963219 -0.9957824 -0.001950144 0.01422691 -0.9998969 -0.2218979 -0.08480453 -0.9713751 -0.0429266 0.065225 -0.9969469 -0.01106286 -0.01863461 -0.9997652 0.09086656 -0.07099097 -0.9933295 0.2486994 -0.04889172 -0.9673461 0.1287701 -0.09310698 -0.987294 -0.001260638 0.02245134 -0.9997472 -0.3892933 -0.9209808 0.01566487 -0.6460447 0.7609426 0.05993968 -0.03376948 0.9962643 0.07947951 0.7951201 -0.6051344 0.039958 -0.8121566 -0.5820248 -0.04060602 -0.256211 0.9597505 -0.1150442 0.5917549 0.8044824 0.05132645 0.8931748 0.4447462 -0.06663072 -0.5457417 -0.7991844 -0.2519332 -0.9220504 0.3169696 0.2221562 -0.6024134 0.7658864 -0.224758 -0.1570232 -0.07745093 0.9845533 0.02048754 -0.002095162 0.9997879 -0.023063 -0.06339871 0.9977218 -0.02198195 -0.02443426 0.9994598 -0.02583885 -0.04673498 0.9985732 -0.005005776 -0.003585278 0.9999811 0.008992373 8.3214e-4 0.9999592 -0.02145731 -0.07974946 0.996584 -0.8501626 -0.3052294 -0.4290205 -0.4625977 -0.8865625 0.003242194 -0.8249617 0.5651751 -0.003949463 -0.7885617 0.6145501 -0.02233171 0.5553968 0.8193816 -0.1419445 0.8006789 -0.5981494 -0.03362584 0.002381563 -0.9848344 -0.1734807 0.8673223 0.4974764 -0.01641744 -0.1459703 -0.05935877 -0.9875066 0.3871932 -0.9170386 -0.09550756 -5.78003e-4 -0.91028 -0.4139928 -0.417586 -0.9085598 -0.0118829 -0.9477379 -0.3025428 -0.1012952 -0.7827298 0.6209686 -0.04162031 0.9799552 0.1990131 -0.009031116 0.9352971 -0.2772892 -0.2198412 0.8502784 -0.5230653 0.05856221 0.09113359 0.02716803 -0.9954681 -0.02721679 0.08890467 -0.9956682 -0.07147204 0.08530104 -0.9937885 -0.0813812 -0.06213164 -0.9947447 -0.02485013 -0.01092672 -0.9996315 0.01154571 -0.06261205 -0.9979712 -0.8530919 0.3433455 -0.3928719 -0.009190082 0.9159721 -0.4011369 -0.5858613 0.8069136 -0.07521355 0.2619038 0.03265696 -0.9645413 0.2960089 -0.03307843 -0.9546123 -0.09000486 0.07354968 -0.9932219 0.004946708 0.1082885 -0.9941073 -0.08797657 -0.08885705 -0.9921516 0.489528 -0.8719596 -0.006991624 -0.483782 -0.8751766 0.004569053 -0.8010287 -0.5973066 -0.03972446 -0.7729328 0.6336414 -0.03276795 0.05782574 0.9529424 -0.2975854 -0.5138876 -0.8577881 -0.01091969 0.9360491 0.3456393 -0.06592142 0.03154903 -0.1229408 -0.9919124 0.266481 -0.07413125 -0.9609851 -0.07083284 0.07203739 -0.9948836 0.320508 0.01201635 -0.9471697 -0.03800606 0.07162785 -0.9967072 0.004837453 -0.180788 -0.9835102 0.1437366 -0.7084143 -0.6910058 -0.9747402 0.001506865 -0.2233369 -0.7653078 0.6234935 -0.1598752 0.01805955 0.9990267 -0.04024636 -0.8559843 -0.1113946 -0.5048587 -0.4337598 -0.09107547 -0.8964139 -0.4277251 -0.1178393 -0.8961949 -0.5119686 -0.1432971 -0.8469676 -0.9952372 -0.01630711 -0.09610909 -0.9930988 -0.02959173 -0.1134868 -0.9288607 -0.07035464 -0.3636866 -0.8441299 -0.05183398 -0.5336275 -0.6768233 -0.03786021 -0.7351713 -0.2889723 -0.02158051 -0.9570943 -0.1365268 -0.001183509 -0.9906357 -0.2152837 -0.004654824 -0.9765406 -0.2410939 -0.01255398 -0.9704207 -0.3698415 -0.01729577 -0.928934 -0.2726349 2.69166e-4 -0.9621176 -0.2670603 -0.01478129 -0.9635665 -0.1431726 -0.00469166 -0.9896867 -0.1783076 -0.02749949 -0.9835905 -0.2050984 -0.1713162 -0.9636313 -0.2528778 0.02523165 -0.9671692 -0.07242977 -0.01914393 -0.9971898 -0.2038757 -0.03732377 -0.9782851 -0.2649353 -0.05309373 -0.9628035 -0.7469993 -0.1022883 -0.6569089 -0.893783 -0.1002503 -0.437152 -0.4199653 -0.08218955 -0.9038109 -0.6064724 -0.1549055 -0.779869 -0.9316663 -0.2031904 -0.301184 -0.9643231 -0.1056537 -0.2427307 -0.9701643 -0.24013 -0.03344851 -0.9853879 -0.1662935 -0.03683912 -0.9683896 -0.1139106 -0.2219144 -0.9771083 -0.1750666 -0.120877 -0.967603 -0.2394044 -0.08018618 -0.9677212 -0.2519794 -0.004689395 -0.9898732 -0.1418607 -0.005151391 -0.9925673 -0.1169391 -0.03369629 -0.9903362 -0.05662626 -0.126601 -0.9990573 -0.02581518 -0.03490126 -0.177621 -0.0998755 -0.9790177 -0.2339807 0.05640995 -0.9706034 -0.2011939 -0.04550135 -0.9784941 -0.9963277 -0.08529806 -0.007445275 -0.9837793 -0.1788274 -0.01411461 -0.5351915 -0.03968739 -0.843798 -0.3430125 -0.02370858 -0.9390317 -0.4320457 -0.01598978 -0.90171 -0.8563882 -0.03341817 -0.5152501 -0.9967463 -0.06841498 -0.04261958 -0.7756211 -0.07388418 -0.6268596 -0.4070168 -0.05854028 -0.911543 -0.4714808 -0.05880731 -0.8799135 -0.5225537 -0.05344396 -0.8509299 -0.9651231 -0.07619792 -0.2504621 -0.9766874 -0.1998829 -0.07828545 -0.9542104 -0.2208182 -0.201797 -0.8904197 -0.1778051 -0.4189727 -0.8899413 -0.1746642 -0.4213039 -0.7434498 -0.1738893 -0.6457902 -0.3163906 -0.05131834 -0.9472399 -0.3229938 -0.08096987 -0.9429311 -0.3369461 -0.08622086 -0.9375678 -0.9698761 -0.1794925 -0.1646903 -0.9825474 -0.1553462 -0.1023154 -0.6233806 -0.1100425 -0.7741365 -0.2637271 -0.05700004 -0.9629119 -0.9927045 -0.1092572 -0.05099594 -0.9869856 -0.1507472 -0.05598831 -0.8942434 -0.09663116 -0.4370254 -0.2118511 -0.03528553 -0.9766648 0.9553762 0.2953404 0.005526363 0.29413 -0.9557434 0.006480336 -0.9040792 -0.4154189 -0.1003387 -0.1917316 0.01465648 -0.981338 -0.05050027 -0.9983563 -0.02710258 -0.8167127 0.5443998 -0.1913357 -0.1187806 0.9911223 -0.05973213 -0.4179618 0.8793641 -0.2280938 -0.3744125 0.01451092 -0.9271488 -0.6488384 0.07809323 -0.7569085 -0.7856941 0.1937934 -0.5874767 -0.9563744 0.2492473 -0.1523942 -0.9677091 0.2519804 -0.00672245 -0.1341499 -0.004733502 -0.9909498 -0.4442074 0.01084035 -0.8958584 -0.5068657 -1.04066e-4 -0.8620251 -0.9252083 0.03470319 -0.3778693 -0.3091619 0.008399307 -0.9509724 -0.6467169 0.03223389 -0.7620488 -0.9010148 0.004273653 -0.4337675 -0.4890422 0.009172677 -0.8722119 -0.5671975 0.004464268 -0.8235697 -0.787529 0.009464621 -0.6162049 -0.8492966 -0.01358318 -0.5277411 -0.9933201 0.03095632 -0.1111612 -0.989512 0.1418058 -0.02751713 -0.6557649 0.04270488 -0.7537565 -0.6033174 0.1473866 -0.7837636 -0.5171424 0.1212766 -0.8472638 -0.2209931 0.0531916 -0.9738237 -0.2131588 0.04373562 -0.9760382 -0.2127542 0.03357642 -0.9765288 -0.1955681 0.02622598 -0.9803395 -0.1889575 0.06740391 -0.9796692 -0.2156718 0.003374874 -0.9764601 -0.254383 0.04956632 -0.9658325 -0.4187558 0.07716125 -0.9048147 -0.3523672 0.05431175 -0.9342845 -0.2307743 0.01950997 -0.9728118 -0.2465528 0.03232866 -0.9685901 -0.9798268 0.1978857 -0.02794355 -0.9958065 0.0852518 -0.03318828 -0.9759588 0.1422811 -0.165108 -0.9938367 0.06477677 -0.08995985 -0.9236792 0.09001541 -0.3724434 -0.7416676 0.03965133 -0.6695946 -0.6979933 0.0809077 -0.7115191 -0.4676557 0.06587833 -0.8814524 -0.3794588 0.04739242 -0.9239941 -0.308242 0.006209373 -0.9512878 -0.3007672 0.02527719 -0.9533627 -0.2971985 0.01739698 -0.9546573 -0.1598675 -0.005884766 -0.9871209 -0.9868572 0.006740748 -0.1614546 -0.9992796 0.02510386 -0.02846395 -0.9776949 0.1655845 -0.1292075 -0.990862 0.1079475 -0.08087062 -0.9879521 0.1463422 -0.05034655 -0.544445 0.08574622 -0.8344025 -0.7566417 0.1166448 -0.6433409 -0.603124 0.1154773 -0.7892444 -0.4495646 0.04051434 -0.8923286 -0.9285103 0.1006902 -0.3573937 -0.9571899 0.112995 -0.266495 -0.9742381 0.183804 -0.1306761 -0.9562239 0.2048056 -0.2090229 -0.2940107 0.05949521 -0.9539487 -0.2729752 0.05852943 -0.960239 -0.4189779 0.07592165 -0.9048168 -0.453073 0.1072413 -0.8849995 -0.3727325 0.0130909 -0.9278466 -0.2194586 0.03515261 -0.9749883 0.5960863 -0.781395 -0.1846703 0.2861348 0.9580583 0.01584911 0.5865945 0.805479 -0.08432435 0.03820234 -0.9992334 -0.008567214 -0.4644815 -0.1761658 -0.8678839 -0.9888748 0.08444887 -0.1224546 -0.9189582 0.07319796 -0.3875024 -0.8843676 -0.1033798 -0.4551995 0.07252877 -0.9933454 -0.08946847 -0.07156002 0.2365974 -0.9689691 0.4972147 0.3431016 0.7969058 0.2045289 -0.9405996 -0.2709988 -0.6605672 -0.5844694 -0.4712182 -0.03918749 -0.9991101 0.01560014 5.42676e-4 0.02231842 -0.9997509 0 0.01460134 -0.9998935 -2.01259e-4 0.04167753 -0.9991312 0.001003146 0.1628904 -0.9866437 3.63185e-4 0.1243361 -0.9922401 -1.68651e-4 0.1238976 -0.992295 1.45286e-5 0.09021377 -0.9959225 -0.001358628 0.1006284 -0.9949232 0.002175748 0.1462351 -0.9892475 0.005359351 0.1251006 -0.9921296 0.004091024 0.1299148 -0.9915168 0.001502811 0.2218744 -0.9750741 -0.004089415 0.2088483 -0.9779396 -8.7323e-4 0.2838749 -0.958861 4.0432e-4 0.3412067 -0.9399882 -2.82384e-4 0.4131976 -0.9106413 -7.20481e-5 0.5230028 -0.8523311 -7.57887e-4 0.6078583 -0.7940452 2.85444e-4 0.5954479 -0.8033939 -0.0012331 0.3308241 -0.9436917 2.39717e-4 0.3427804 -0.9394155 -0.001514256 0.4415664 -0.8972274 -9.56395e-4 0.4625407 -0.8865975 9.56024e-4 0.4641582 -0.8857519 -3.18832e-4 0.5667537 -0.8238872 -2.00639e-4 0.6336849 -0.7735913 -1.35381e-4 0.6310051 -0.7757787 -0.004690468 0.6481925 -0.7614621 0.03295773 0.615154 -0.7877178 -0.001497507 0.6762914 -0.7366328 2.59066e-4 0.7068754 -0.7073381 -0.007368445 0.7704259 -0.6374872 5.30427e-4 0.5803799 -0.8143458 0.01822513 0.5061267 -0.8622666 0.00330305 0.47831 -0.878185 -0.00882411 0.3937374 -0.9191807 8.76999e-4 0.4143282 -0.9101271 0.004961788 0.3551895 -0.9347812 0.002587139 0.2586725 -0.9659617 0.02646529 0.2256494 -0.9738491 -0.007549703 0.363274 -0.9316518 0.01946198 0.4804644 -0.8767983 -7.62608e-5 0.2041722 -0.978935 -5.51937e-4 0.2024089 -0.979301 8.27408e-4 0.1760252 -0.9843853 0.001678049 0.1285054 -0.9917074 -0.002628982 0.1882014 -0.982127 -2.84686e-4 0.2440887 -0.969753 -1.48407e-4 0.2779249 -0.9606028 -3.04805e-4 0.3084145 -0.9512521 4.45997e-4 0.3007854 -0.9536918 -6.6263e-4 0.3419097 -0.9397326 9.16245e-4 0.05811798 -0.9983094 2.12478e-4 0.05403465 -0.998539 -2.80266e-4 0.02961438 -0.9995614 -0.001046478 0.7330579 -0.6801654 0.01733869 0.6723716 -0.7400107 -0.00851196 0.5783144 -0.8157697 -0.005890965 0.6834 -0.7300204 -0.01439797 0.4852223 -0.8742723 -4.55372e-4 0.6469628 -0.7625215 0.02297145 0.6450619 -0.763785 -0.001057028 0.5353748 -0.844614 0.001802623 0.3399465 -0.9404431 0.001171171 0.3203577 -0.947296 -0.004059731 0.530955 -0.8473904 -0.004873394 0.4456899 -0.8951742 0.003966391 0.3789849 -0.9253944 -0.0340026 0.5089538 -0.860122 -0.02133524 0.4903331 -0.8712739 0.04633104 0.5595664 -0.8274896 0.02964735 0.4475216 -0.8937816 -0.0595206 0.341165 -0.9381172 -0.01994669 0.2514756 -0.9676581 0.001029849 0.4800167 -0.8772588 2.42269e-4 0.3815029 -0.9243677 6.71571e-4 0.3789715 -0.9254081 2.02409e-4 0.2611663 -0.9652939 0.009931623 0.6435618 -0.7653298 0.01618093 0.5125421 -0.8585096 -0.005758583 0.3999329 -0.9165264 -0.001184046 0.1600953 -0.9871008 0.004382371 0.1715907 -0.9851587 0.004339456 0.174053 -0.9847268 0.01931226 0.1825171 -0.983013 -4.26763e-4 0.07413023 -0.9972485 -0.001461386 0.1996722 -0.9798617 -0.003815829 0.09468066 -0.9955005 -4.27055e-4 0.04335379 -0.9990597 -0.002507984 0.07985782 -0.9968031 3.80032e-4 0.2323182 -0.9726399 0.002549529 0.2465791 -0.9691193 2.61544e-4 0.1723471 -0.9850363 0.002268016 0.14496 -0.9894349 -0.9642897 0.2600103 -0.05040001 -0.2471013 0.96883 -0.01758998 0.7720699 0.6354371 0.01130414 0.1381481 0.9872147 -0.07951259 0.7144031 -0.6992356 0.02641832 -0.6239953 -0.7813941 0.007301807 0.2283047 0.9462718 -0.229012 -0.7147067 -0.1860657 -0.6742209 0.9098259 0.3465883 -0.2282398 -0.4340386 0.8860105 -0.1630824 0.8038797 -0.4055997 -0.4350475 -0.9101238 0.401983 0.100422 0.9989593 0.04392677 -0.01228457 -0.1814343 -0.02012646 -0.9831971 -0.5479891 0.7642623 -0.3400163 0.9216099 0.1359121 -0.3635424 0.3920321 0.3102353 0.8660629 -0.8926727 0.2571839 -0.3701244 0.9989593 -0.0331009 -0.03138005 -0.597841 -0.7973765 -0.08232247 -0.796932 -0.6030214 -0.03556478 -0.01205402 -0.9998917 -0.008453249 -0.9208118 -0.2477208 -0.3012309 -0.4971421 0.8650372 -0.06753116 0.7123329 0.7018418 -4.53334e-4 0.8233282 0.5655743 -0.04750156 -0.71658 -0.6972124 -0.02020019 -0.8124276 -0.5787916 -0.07043862 0.0274114 0.9662196 -0.2562585 0.8806073 -0.2480789 -0.4037175 0.156 -0.986409 -0.05158925 0.6599641 0.3432905 -0.6682808 -0.9901983 -0.1356107 0.0334233 -0.2935816 0.02068036 -0.9557103 -0.3129053 0.07931876 -0.9464665 -0.1561223 0.2149698 -0.9640612 7.01601e-4 0.5080045 -0.8613542 1.46612e-4 0.5048241 -0.8632223 9.57394e-4 0.3829135 -0.9237837 -3.80886e-4 0.3308243 -0.9436923 0.001369357 0.2287549 -0.9734831 -0.002459645 0.1854925 -0.9826427 0.009019672 0.043352 -0.9990192 -0.00232625 0.7691308 -0.6390872 -0.007018744 0.8400503 -0.5424632 -0.01239657 -0.08762711 0.9960763 -0.004823029 -0.2220935 0.9750134 0.0019086 -0.183839 0.9829545 -3.16945e-4 -0.2841508 0.9587795 5.00584e-4 -0.33077 0.9437114 2.85681e-4 -0.3318888 0.9433186 -2.24142e-4 -0.3805586 0.9247568 1.37611e-4 -0.5067692 0.8620817 -0.001160681 -0.5146126 0.8574221 -0.001903295 -0.5895611 0.8077217 -0.003010034 -0.6701424 0.7422265 -8.10453e-4 -0.8157292 0.5784335 0.07852596 -0.9474919 0.3099883 0.001003921 -0.5682604 0.8228482 0.001791179 -0.635532 0.7720725 0.002289116 -0.7751924 0.631721 0.006568431 -0.8468199 0.5318392 0.1548776 -0.02809691 0.9875341 0.1363478 0.01583403 0.9905345 0.9994222 -0.03064972 0.0146948 0.8952068 -0.1160984 0.4302629 0.8307199 -0.2301545 0.5068861 0.9800482 -0.1952697 0.03708267 0.9887189 -0.1486833 0.01811438 0.992866 -0.1158234 0.02832162 0.995736 -0.09184116 0.008667349 0.9976426 -0.01367282 0.06724941 0.4546204 -0.1241458 0.881991 0.5609664 -0.02603131 0.8274293 0.4249436 -0.04673844 0.9040125 0.3458257 -0.1164147 0.931049 0.1856777 -0.003117084 0.9826058 0.2721403 -0.0735253 0.9594445 0.2891656 -0.07918798 0.9539982 0.2425947 -0.0435369 0.9691503 0.154768 -0.008356213 0.9879156 0.1814647 -0.02460592 0.9830896 0.793162 -0.1835891 0.58068 0.8350296 -0.159777 0.526495 0.827414 -0.131717 0.5459274 0.7199289 -0.2155313 0.6597338 0.9183045 -0.2764949 0.283315 0.9526676 -0.2935426 0.07910311 0.9604462 -0.2784249 0.004792213 0.9687815 -0.2461681 0.02938848 0.9768182 -0.2129108 0.022255 0.9305288 -0.269288 0.2481943 0.9687912 -0.233995 0.08179247 0.9780459 -0.2059153 0.03202152 0.9529392 -0.2928712 0.0783168 0.3649472 -0.004904925 0.9310154 0.4032436 -0.01736581 0.914928 0.4361876 -0.004316866 0.8998454 0.8549516 -0.1106542 0.5067675 0.7634835 -0.03671401 0.644783 0.8523895 -0.02901899 0.5221016 0.8247555 -0.04018825 0.5640597 0.2260065 -0.01306307 0.9740383 0.4005588 -0.03369891 0.9156512 0.6344524 -0.04730325 0.7715133 0.9490669 -0.07796782 0.3052755 0.9518729 -0.08221137 0.2952614 0.9927093 -0.0594868 0.1048307 0.9257736 -0.1464016 0.3485828 0.5066068 -0.03952395 0.8612708 0.3661353 -0.061634 0.9285184 0.3014358 -0.03027385 0.9530057 0.2983425 -0.03132557 0.9539448 0.5221323 -0.08583724 0.848534 0.5035145 -0.1034698 0.8577687 0.6352147 -0.09259945 0.7667645 0.8222934 -0.06268978 0.5656003 0.9792037 -0.09892135 0.1771298 0.991865 -0.1126107 0.05935275 0.9865362 -0.15052 0.06395477 0.5858643 -0.1016075 0.8040143 0.4994904 -0.06783837 0.8636593 0.4252868 -0.05041599 0.9036534 0.6377006 -0.142166 0.7570514 0.9474369 -0.1480041 0.2836517 0.9737713 -0.1453577 0.1750453 0.981971 -0.1751068 0.07120794 0.2635239 -0.05477643 0.9630964 0.442497 -0.08606797 0.8926303 0.9774422 -0.1829893 0.1054601 0.9736063 -0.1672625 0.155287 0.5906679 -0.12717 0.7968308 0.7727098 -0.181914 0.6081339 0.9083167 -0.2085594 0.3625793 0.8808802 -0.2000747 0.4289755 0.9525489 -0.2211326 0.2091677 0.3124706 -0.07662159 0.9468323 0.3807642 -0.09956616 0.9192962 0.4470985 -0.1251311 0.8856891 0.6408681 -0.1653334 0.7496352 0.5537459 -0.1619544 0.8167842 0.01222306 0.9995116 0.02876204 -7.99907e-5 0.9999598 -0.008974432 -3.94049e-4 0.9999631 -0.0085783 0.07021641 0.9975227 -0.004276156 0.9186778 0.3949655 0.005781292 0.9557449 0.2939777 -0.01135969 0.8563407 0.5163959 -0.004008948 0.3752719 0.9268804 -0.007991135 0.2125424 0.9771414 -0.004520416 -0.005329549 0.9999565 -0.007667839 -0.4089274 0.9125465 -0.006120145 -0.7070736 0.7070922 -0.008226096 -0.9999514 0.005357384 -0.008280932 -0.9918747 0.12712 -0.005025207 -0.3050137 -0.9523001 -0.009550452 -0.4386677 -0.8983456 -0.02336335 -0.5942949 -0.8042392 -0.003626763 -0.999962 -5.7744e-5 -0.008720159 -0.9999624 3.8328e-5 -0.00867927 -0.9997291 -0.01076346 -0.02063602 -0.9995095 -0.01807713 0.02557241 -0.9922143 0 0.124543 -0.3391492 0.9317973 -0.1293504 -0.3345208 0.9297318 -0.1539306 -0.34234 0.9390901 -0.030218 -0.3399318 0.9390634 -0.05105137 -0.3432061 0.9369259 -0.06617742 -0.3111493 0.866705 -0.3898829 -0.2827136 0.7894399 -0.5448467 -0.2592769 0.722175 -0.6412791 -0.3311197 0.9005516 -0.2817211 -0.3277152 0.9188786 -0.2196931 -0.3092763 0.8372487 -0.4509577 -0.3391854 0.9165986 -0.2116612 -0.3239052 0.8835642 -0.3382304 -0.2181349 0.974342 -0.05545234 -0.1449471 0.8202484 -0.5533381 -0.1448062 0.800082 -0.5821512 0.6811091 0.7303061 -0.05237764 0.6812641 0.7301554 -0.05246394 0.6814747 0.7299692 -0.05231904 0.3023034 0.9491119 -0.08831411 -0.6811185 -0.7302989 0.05235707 0.2235707 -0.9501451 0.2173491 0.2431115 -0.9678456 0.06458795 0.277004 -0.9570213 0.08590126 0.2220965 -0.8201643 0.5272605 0.2103475 -0.7981108 0.5645999 0.08034139 -0.7134644 0.6960703 0.175643 -0.9479734 0.265511 0.1907569 -0.9054645 0.3791385 0.1525931 -0.8392505 0.5218946 0.3347364 -0.9288574 0.1586685 0.3410942 -0.9367932 0.07793211 0.3420414 -0.939601 0.01256132 0.3433871 -0.9389806 0.02001917 0.342098 -0.939334 0.02491366 0.3421043 -0.9363798 0.07847052 0.3417519 -0.9274497 0.1517984 0.3304254 -0.8987404 0.2882447 0.2827681 -0.7802813 0.557856 0.302469 -0.8403465 0.4498114 0.3366464 -0.9249956 0.1762171 0.3250945 -0.8931202 0.3108859 0.2638317 -0.7194709 0.6424598 0.2265528 -0.6332132 0.7400777 0.322204 -0.9044097 0.2796925 0.3411654 -0.9398075 0.01918548 0.3429742 -0.3522239 0.8708083 0.2754863 -0.7335842 0.6212581 0.802635 -0.5163089 0.2986675 0.4498369 -0.8048684 0.3870836 0.9055842 -0.4236851 0.02021068 0.5563893 -0.8053846 0.2044183 0.3831387 -0.9208239 0.07271903 0.5978846 -0.8005768 0.04013723 0.4525855 -0.8908751 0.03883564 0.6612823 -0.7499922 0.01474541 0.5622949 -0.4011451 0.7231232 0.6569387 -0.7347495 0.1690409 0.2587932 -0.9657931 0.01642268 0.7067257 -0.7067479 0.03234565 0.2587267 0.96555 0.02781736 -0.7068248 0.7068404 0.02784562 -0.7067462 -0.7067254 0.03239053 -0.2036613 0.9755963 0.08206152 -0.3317944 -0.9343754 0.1298278 -0.8440213 0.2994191 -0.4449452 -0.9316059 0.3101355 -0.189543 -0.9412612 0.3369639 0.02197051 -0.7485894 0.6280454 -0.2125393 -0.5490657 0.829815 -0.09967017 -0.6243438 0.6922398 -0.3619378 -0.6634025 0.5687204 -0.4862657 -0.9274155 0.3725992 -0.03271621 -0.6917929 0.722012 -0.01101571 -0.3328498 0.9324868 -0.1402831 -0.3637899 0.931022 -0.02924001 -0.3557864 0.9267783 -0.1204082 -0.3371994 0.9412754 -0.01723736 0.9999495 -0.001307547 -0.009974479 0.9999573 0.003132224 -0.008696913 0.8535651 -0.5209172 -0.008487462 0.8172358 -0.5762002 -0.01091951 0.7051069 -0.7090628 -0.007378041 0.5761838 -0.817247 -0.01093751 0.2733718 -0.9618588 -0.00978583 0.9579009 -0.2869255 -0.00998187 -2.16115e-6 -0.9999616 -0.008775293 8.6224e-6 -0.9999615 -0.00878489 0.07177239 -0.9974182 -0.002419233 0 -0.99331 0.1154788 -0.2786018 0.3254541 -0.9035821 -0.120822 0.306806 -0.9440721 -0.3475691 0.6431426 -0.682322 -0.486836 0.708732 -0.5105779 -0.3112403 0.6633498 -0.680512 -0.2693424 0.6223764 -0.7349166 -0.3438374 0.3371671 -0.8764099 -0.4190153 0.2862489 -0.8616774 -0.75058 0.1773599 -0.6365322 -0.7508457 0.1252708 -0.6484891 -0.1769207 -0.9192722 0.3516216 0.07329893 -0.2956368 0.9524842 0.002309083 -0.4387303 0.8986158 0.2615468 -0.2637829 0.9284461 0.1677459 -0.313624 0.934613 -0.5073877 -0.8463941 0.1617866 -0.7222082 -0.2214873 -0.6552548 0.5126928 -0.1956558 0.8359814 -0.5105479 0.1714971 -0.8425732 -0.4256653 0.2574056 -0.8674972 -0.4726796 0.3402474 -0.8128995 -0.3888841 0.2831063 -0.8767098 -0.6315799 0.5406596 -0.5556924 -0.634791 0.5399141 -0.5527505 -0.6202252 0.2218365 -0.7524024 0.5229775 -0.1112907 0.8450497 -0.3673459 0.4465814 -0.8158567 -0.2587327 -0.9655866 -0.02645748 -0.5988874 -0.8000011 -0.03649979 0.4251095 -0.9050083 -0.01555216 0.8238206 -0.5668503 -7.26944e-4 0.9562932 -0.2918694 -0.01777273 0.9124023 0.4090887 -0.01298278 0.8807591 0.4735185 -0.006618738 0.5276172 0.8494707 -0.004443526 0.2587409 0.9656075 -0.02560269 0.8708146 0.4902568 -0.03647422 -0.9974344 0.06745851 -0.02396279 -0.9991345 0.03646963 -0.020011 -0.9655891 0.2587459 -0.02623891 -0.8486762 0.5274555 -0.03923863 -0.4867513 0.8733569 -0.01791745 -0.2587429 0.9656299 -0.02471852 0.01861298 0.9998266 -5.86132e-4 0.3959764 -0.9175811 -0.03532159 0.4046924 -0.9143592 -0.01309537 -0.566205 0.186769 -0.8028258 -0.5914927 0.1817294 -0.7855641 -0.09346681 -0.04686212 -0.9945189 0.07432526 0.2962287 0.9522207 0.1822281 0.04983538 0.9819926 0.08448356 0.005386173 0.9964103 0.1341006 -0.005747079 0.9909511 0.08939921 0.08919358 0.9919942 0.1607937 0.04495704 0.9859637 0.1851194 3.12874e-5 0.9827161 0.3534485 0.051952 0.9340103 0.5145159 0.07808315 0.8539184 0.6911265 0.1475799 0.7075057 0.7635516 0.1732999 0.6220581 0.8313635 0.1809451 0.5254462 0.8575621 0.1956762 0.4757081 0.9768502 0.2129163 0.02074676 0.9623273 0.2718476 0.005029976 0.9538253 0.2965444 0.04773777 0.3098546 0.01900458 0.9505941 0.4976472 0.02012038 0.8671463 0.5803322 0.013902 0.8142613 0.6249877 0.01754188 0.7804375 0.7161118 0.02811747 0.697419 0.8695734 0.02414351 0.4932132 0.9957551 0.09184569 0.00602585 0.99093 0.1276548 0.04197657 0.9779008 0.1702312 0.1213733 0.9630495 0.1837812 0.1968763 0.5159299 0.04706799 0.8553368 0.4383084 0.04503756 0.8976956 0.5301627 -0.00322318 0.8478899 0.5448592 -0.005252003 0.8385111 0.8870308 0.08042466 0.4546518 0.9425165 0.04278647 0.3314094 0.9922515 -0.001058518 0.1242421 0.9940325 0.05003964 0.09693056 0.9968014 0.07046103 0.03771412 0.9992257 0.006972193 0.03872191 0.9606028 0.2542052 0.112348 0.9658848 0.2320871 0.1149014 0.9423962 0.2345213 0.2385146 0.9052254 0.2296409 0.357536 0.6792253 0.2119038 0.7026734 0.6517221 0.1924474 0.7336364 0.6463875 0.1651414 0.7449239 0.5928173 0.1889063 0.7828679 0.3077612 0.0517686 0.9500543 0.2577946 0.04749524 0.9650318 0.2036172 0.03498703 0.9784253 0.5229223 0.1325148 0.8420168 0.4290615 0.1042476 0.8972396 0.460339 0.1401758 0.8766065 0.2986813 0.0811277 0.9508985 0.2283484 0.05014485 0.9722872 0.1635579 0.01765185 0.9863759 0.2101163 0.01739293 0.9775217 0.982622 0.1716197 0.07071673 0.9873726 0.1139179 0.1100826 0.9835663 0.1219136 0.1331712 0.9669615 0.1037315 0.2328636 0.9436361 0.09801828 0.3161382 0.828959 0.1015253 0.5500178 0.8380693 0.116555 0.5329681 0.8400464 0.1173392 0.5296732 0.6855602 0.1373036 0.714951 0.4267862 0.05403029 0.9027372 0.2300097 0.01339125 0.9730962 0.3051813 0.02155363 0.9520504 0.6600348 0.03296279 0.7505115 0.652006 0.04335248 0.7569735 0.9903355 0.05287885 0.1282165 0.9963555 0.07244068 0.04503417 0.4133517 0.08077645 0.9069817 0.2541363 0.04131269 0.9662858 0.2111343 0.02862232 0.9770379 0.2577654 0.0474804 0.9650402 0.8667793 0.2211808 0.4469593 0.5191326 0.1318406 0.844464 0.9530259 0.2681222 0.1408973 0.9183393 0.2451803 0.3107084 0.5669745 0.1546736 0.8090835 0.3648999 0.01682043 0.9308948 0.09173017 -0.9950091 -0.03927356 -1.37811e-4 -0.999958 -0.009164214 0.01222723 -0.9995115 0.02876424 -0.3949847 0.9186772 0.004419624 -0.3052576 0.9522223 -0.009516239 -0.4367874 0.899262 -0.02334123 -0.5938822 0.8045439 -0.003629505 -0.7145956 0.6994894 -0.0082286 -0.9659472 0.2587089 -0.00397408 -0.8235942 0.5671675 -0.003709912 -0.9999561 -0.005360782 -0.007687568 -0.9966007 -0.0822494 -0.004704058 -0.8049809 -0.5932812 -0.004802942 -0.7070721 -0.7070936 -0.00822854 -0.4089549 -0.9125342 -0.006120264 0.699514 -0.7145829 -0.007166802 -0.9994448 0.02139574 0.02554494 -0.9999589 -2.07429e-4 -0.009061098 -0.9999644 -2.92815e-4 -0.008447349 -0.9999626 -1.05748e-4 -0.008646667 -0.999962 9.23654e-5 -0.008727669 -0.9975494 0.06965041 -0.006649911 -0.3419161 -0.93949 -0.02125889 -0.3419876 -0.9396235 -0.01234453 -0.3418649 -0.9389566 -0.03858762 -0.3373471 -0.9278063 -0.1592879 -0.3299757 -0.896299 -0.2962502 -0.3141776 -0.8621038 -0.3975796 -0.3428995 -0.9338135 -0.102041 -0.2895033 -0.7752075 -0.5614635 -0.3308555 -0.9044073 -0.2694104 -0.3145919 -0.8603152 -0.4011107 -0.3374135 -0.9273127 -0.1619983 -0.3371716 -0.9380412 -0.0799635 -0.2612532 -0.9305847 -0.2564347 -0.06917631 -0.775568 -0.6274625 -0.1269698 -0.7244154 -0.6775699 -0.2521347 -0.9659128 -0.05865788 -0.2351456 -0.8865131 -0.3984985 -0.2789509 -0.9065934 -0.3166621 -0.07126593 -0.7355792 -0.6736798 -0.2371752 -0.8760909 -0.419777 0.6725242 -0.7381039 -0.05398076 0.67872 -0.7323236 -0.05514889 0.1547236 0.8335242 0.5303753 0.07381802 0.7778688 0.6240762 0.0612747 0.740807 0.6689174 0.06441986 0.6831343 0.727446 0.02528202 0.5199288 0.8538355 0.2575667 0.7506816 0.6083885 0.1579071 0.8568074 0.4908632 0.246149 0.9673621 0.06017905 0.3342757 0.9300411 0.1525893 0.3256176 0.8999776 0.2898512 0.344472 0.9385825 0.02004796 0.3420312 0.9395876 0.01378124 0.3266889 0.9005821 0.2867514 0.4209203 0.9068315 0.02197289 0.6483322 0.7570129 0.08122199 0.4083429 0.3751532 0.8321756 0.3879648 0.8421815 0.3744512 0.4986136 0.8626631 0.08483558 0.7397723 0.5199649 0.4270521 0.8131241 0.4575107 0.3598797 0.9376299 0.327886 0.1155036 0.9440407 0.3244212 0.05948162 0.7844155 0.6201046 -0.01275426 0.2795519 0.7265362 0.6276909 0.4839959 0.7590477 0.4354248 0.6042358 0.7049644 0.3713817 0.7240097 0.4681138 0.5066354 0.466821 0.5033895 0.727102 0.480119 0.7272248 0.4905404 0.5565568 0.5399608 0.6314167 0.464769 0.4255828 0.7764464 -0.9655389 0.2587255 0.02820867 0.2587097 -0.9655545 0.02782177 0.9637683 0.2582612 0.06672239 0.2582341 0.9637815 0.0666365 -0.976397 -0.1995404 0.0826599 -0.3139946 -0.9458075 0.08279979 0.6649998 -0.7423111 0.08215612 0.3132882 0.9460918 0.08222436 -0.9338555 -0.2645267 -0.2407063 -0.9568908 -0.2885205 0.03340554 -0.5073587 -0.8216428 -0.2597891 -0.9293889 -0.366087 -0.04708003 -0.7430996 -0.6445322 -0.1799478 -0.6612016 -0.7487246 -0.04715943 0.9973342 0.07275533 -0.005589425 0.9999611 -2.46351e-5 -0.008821725 0.9999612 -4.57214e-5 -0.008808612 0.999962 -3.72829e-4 -0.008717894 0.9608641 0.2768779 -0.008882462 0.2709824 0.9625369 -0.009555578 0.9115738 0.4110839 0.00657916 0.7051069 0.7090626 -0.007377862 0.4251446 0.9050986 0.006990969 0.5062878 0.8623275 -0.00800687 -0.3532567 -0.1272538 -0.9268314 -0.5134232 -0.6900689 -0.5100997 -0.3813955 -0.7008135 -0.6028249 -0.3703684 -0.5575104 -0.7429734 -0.835424 0.2399608 -0.4944549 1.57205e-4 0.459489 0.8881835 0.1039804 0.3659443 0.9248097 -0.6486144 0.7582147 0.06640863 0.7982784 -0.127038 0.5887385 -0.4711585 -0.01223188 -0.8819638 -0.6962705 -0.6235988 -0.355432 -0.3919616 -0.5288271 -0.7528001 -0.5492607 -0.6384065 -0.5392124 -0.6989623 -0.2947575 -0.6515902 -0.6920384 -0.3734642 -0.6177439 -0.6264069 -0.4357374 -0.6463338 0.258732 0.9656106 -0.02557474 -0.5140233 0.8576452 -0.01499915 -0.9982113 -0.05380672 -0.02606087 -0.5091161 -0.8605755 -0.01452159 -0.2587307 -0.9656332 -0.02472239 -0.8595764 -0.5094603 -0.03973418 -0.9656203 0.2587179 -0.02534967 -0.2587373 0.9656538 -0.02383077 0.9656432 -0.2587377 -0.0242471 0.873205 -0.4873064 -0.006744146 0.258728 -0.9656113 -0.02558851 0.03528511 -0.9986674 -0.03766125 0.01515901 -0.999885 -5.83457e-4 -0.8166989 0.5757852 -0.03839546 -0.5492208 0.8348011 -0.03825771 -0.5639961 -0.1864926 -0.8044433 -0.5657767 -0.1875159 -0.8029537 -0.6179438 -0.201783 -0.7598876 -0.1059001 -0.9905074 -0.08763688 -0.1231058 -0.9884288 -0.08862024 -0.1287307 -0.9877244 -0.0884822 -0.1798565 -0.9798216 -0.08718627 -0.1987858 -0.9761632 -0.08711928 -0.1837099 -0.9789509 -0.08891534 -0.1531542 -0.9844085 -0.08650898 -0.149874 -0.9850666 -0.08474534 -0.2315641 -0.9686217 -0.09027802 -0.2330433 -0.9687801 -0.08459335 -0.04706925 -0.9950042 -0.08804094 -0.02485895 -0.9959927 -0.08591026 -0.009891748 -0.9958019 -0.09099847 0.008657813 -0.9963017 -0.08548778 0.01755636 -0.9961913 -0.08540874 -0.02188742 -0.9958997 -0.08777654 0.05864226 -0.9945693 -0.08598405 0.04118096 -0.9952517 -0.08819472 0.1013094 -0.9912268 -0.08488839 0.08105868 -0.9928025 -0.08816361 0.129217 -0.987581 -0.08936828 0.2295123 -0.969492 -0.08607822 0.1969282 -0.9764351 -0.08828336 0.1155381 -0.9892965 -0.08912575 0.2671008 -0.9598422 -0.08579146 0.2428824 -0.9660363 -0.08821511 0.2479493 -0.9645258 -0.09061676 0.3045337 -0.9485087 -0.08712333 0.2759745 -0.9573751 -0.08527141 -0.04529076 -0.9950426 -0.08853793 -0.07832348 -0.9927085 -0.0916261 -0.06796151 -0.9939436 -0.08635556 -8.9689e-4 0.007547974 -0.9999711 1.25857e-4 1.97059e-4 -1 1.91549e-5 4.14147e-4 -1 -2.99408e-4 -8.39072e-4 -0.9999997 -1.42693e-4 -0.002221465 -0.9999976 2.95762e-4 -0.003367781 -0.9999943 0.001007378 -0.002737104 -0.9999958 -4.0204e-5 -6.35401e-4 -0.9999999 0.00121057 0.00604552 -0.999981 0.002139985 0.004038035 -0.9999896 9.29968e-5 -0.001737356 -0.9999986 5.67799e-5 -9.94342e-5 -1 -7.88585e-5 2.66704e-5 -1 -1.60396e-4 -8.57686e-4 -0.9999997 3.86363e-5 4.09271e-4 -1 1.34063e-4 2.6327e-4 -1 0.001544654 9.84651e-4 -0.9999983 0.001545071 9.84159e-4 -0.9999984 -9.82182e-4 -0.001368284 -0.9999986 -9.24317e-4 6.94009e-4 -0.9999994 -6.79168e-6 3.1631e-4 -1 0.001946926 7.807e-4 -0.9999978 4.33712e-4 -1.97455e-4 -0.9999999 3.46567e-4 -3.79846e-4 -0.9999999 3.99486e-4 -0.001144289 -0.9999994 0.007953643 0.0355333 -0.9993369 0.07617795 -0.1617147 -0.9838929 4.39615e-4 0.001259982 -0.9999991 2.69847e-4 0.001552522 -0.9999988 0.001312971 0.001438379 -0.9999981 9.79155e-5 -2.45107e-4 -1 -0.001218676 3.72591e-4 -0.9999993 -4.88033e-4 0.001595556 -0.9999987 -2.68557e-7 0 -1 7.8316e-6 5.7672e-4 -0.9999998 3.55805e-7 0 -1 -2.17905e-7 0 -1 2.77122e-4 -2.16125e-4 -1 -2.36739e-4 -0.001278698 -0.9999992 2.31263e-5 -9.90205e-5 -1 -2.64315e-6 -1.16139e-4 -1 -2.61242e-5 -5.17597e-5 -1 1.37579e-4 -0.001627683 -0.9999988 -8.33093e-5 -5.38294e-5 -1 2.0635e-4 3.56995e-4 -1 1.92969e-4 -0.001879155 -0.9999982 -7.09621e-4 -0.001223206 -0.999999 -9.4973e-5 1.92537e-5 -1 4.01495e-4 -4.08323e-4 -0.9999998 3.92238e-4 -5.76175e-4 -0.9999998 2.88343e-4 -0.01532334 -0.9998826 -3.02106e-5 0.001038908 -0.9999995 2.5939e-4 1.8248e-4 -1 2.51011e-4 1.68676e-5 -1 2.62016e-4 0 -1 9.93651e-5 -1.01861e-4 -1 -5.44364e-5 -1.29886e-4 -1 2.91216e-4 -7.70263e-4 -0.9999997 -1.88467e-4 1.84308e-4 -1 -2.29554e-5 2.98186e-4 -1 -1.85522e-4 -0.01038265 -0.9999462 5.48053e-4 3.36017e-4 -0.9999998 1.49117e-7 0 -1 5.79817e-7 0 -1 -1.42346e-7 0 -1 0.00166589 0 -0.9999987 -0.005218505 0.005700767 -0.9999701 0 0 -1 -4.93732e-5 -1.00495e-5 -1 -4.19196e-4 -1.69665e-4 -1 -9.8829e-4 4.12682e-4 -0.9999995 -9.10741e-4 9.10558e-4 -0.9999992 0 -1.72725e-6 -1 -1.70707e-4 2.03122e-5 -1 0.005127787 0 -0.999987 8.6714e-5 2.62433e-4 -1 1.65453e-4 -1.37968e-4 -1 2.93226e-4 -4.1571e-4 -0.9999999 4.18142e-4 -1.88327e-4 -1 0.001005053 0.006441354 -0.9999788 7.89095e-4 -0.001573026 -0.9999985 0.1088097 -0.06446111 -0.9919704 -0.01560163 0 -0.9998783 6.89703e-4 -0.001556694 -0.9999986 0.01872652 -0.7457569 0.665955 -0.002705633 -0.3567157 -0.9342092 -0.137114 -0.9241772 0.3565059 0.005387306 -0.7509418 -0.6603466 -0.2731844 -0.9582296 0.08465516 -0.1327446 -0.9877898 0.08155006 -0.2170623 -0.9727358 0.08166515 -0.2074625 -0.973643 0.09475553 -0.04606282 -0.9938352 0.1008461 -0.07489454 -0.9944328 0.07412332 -0.03674823 -0.9951367 0.09139227 -0.001380741 -0.9962731 0.08624374 0.01229423 -0.995585 0.09305649 0.05785495 -0.9936078 0.09693461 0.08611178 -0.9928788 0.08231914 -0.02920067 -0.9960693 0.08362615 -0.04917174 -0.9976011 0.04872649 -0.04642641 -0.9944147 0.09478396 -0.01851409 -0.9970157 0.07494682 0.09652328 -0.9910333 0.09239214 0.1378445 -0.9869341 0.08342599 0.1772175 -0.9798646 0.09197485 0.2182282 -0.9724373 0.0821107 0.159855 -0.9838109 0.08101022 0.09605908 -0.9911384 0.0917468 0.1628166 -0.982581 0.08958405 0.2008886 -0.9762344 0.08130395 0.2304272 -0.9688981 0.09022122 -0.1644181 -0.9821419 0.09145623 -0.2312712 -0.9688493 0.08856993 0.1011931 -0.9916082 0.08045649 0.1384174 -0.9866957 0.08527863 0.06787455 -0.9944028 0.08096992 0.03488647 -0.9953345 0.08995771 -0.003483653 -0.9960486 0.08874213 -0.1144388 -0.9900926 0.08136516 -0.1758985 -0.9803605 0.08918005 0.2617793 0.960928 -0.08993959 0.1284586 0.9885586 -0.07905882 0.08458542 0.9923114 -0.09035199 0.1535466 0.9845904 -0.08369797 0.1132385 0.9893168 -0.09181171 0.1008118 0.991616 -0.08083862 0.0951001 0.9912799 -0.09121567 0.03798598 0.9951499 -0.0907405 0.01679551 0.9964323 -0.08270871 -0.007722795 0.9964754 -0.08352935 -0.02914983 0.9961339 -0.08287018 -0.05361998 0.9950774 -0.08334159 -0.05322575 0.9944991 -0.09021401 -0.1164146 0.9903479 -0.07522535 -0.1534129 0.984416 -0.08596271 -0.1345992 0.9867944 -0.09011042 -0.1307972 0.9871403 -0.09190297 -0.1482153 0.9855843 -0.08158397 -0.1668145 0.9824039 -0.0839976 -0.1638153 0.9821237 -0.09272414 -0.2054542 0.9741939 -0.09346008 -0.236491 0.9684756 -0.07827466 0.1525936 0.9839959 -0.09201771 0.2029861 0.974717 -0.09339976 0.2056643 0.973475 -0.100243 0.06451898 0.9937165 -0.09145927 -0.07267063 0.9931822 -0.09114944 -0.190142 0.9773054 -0.09338158 -0.1473845 0.9848945 -0.09088814 -0.5442 0.837322 -0.05233108 0.4622666 0.8751356 -0.1429945 0.4346349 0.8772534 -0.2037622 0.2842903 0.7676392 -0.5743772 0.2863672 0.858233 -0.4259458 0.2217227 0.7636886 -0.6063159 0.229303 0.3889116 -0.8922825 0.2346872 0.2511987 -0.9390534 0.2006876 0.770973 -0.6044214 0.08473634 0.03824836 -0.995669 0.08347368 0.04050177 -0.9956867 0.08422362 0.0378617 -0.9957274 0.1243951 0.1212317 -0.9847989 0.09214472 0.05712389 -0.9941058 0.08725827 0.05226677 -0.9948137 0.09128636 0.04322206 -0.9948863 0.02165389 0.2017399 -0.9791998 0.09909003 0.08706188 -0.9912625 0.1051847 0.1233079 -0.9867783 0.2244397 -0.2878965 -0.9309902 0.1778174 -0.4378899 -0.8812682 -0.5431918 -0.8379356 -0.0529772 -0.2576989 0.9617874 0.09250092 -0.9656751 0.2317866 0.1172462 -0.9581714 0.2566761 0.1265898 -0.9650649 -0.2585218 0.04261881 -0.7058494 -0.7058221 0.05993181 0.2585828 -0.9650489 0.04261106 0.9617722 -0.2577507 0.09251433 0.9644715 0.2584798 0.05461686 0.7040922 0.7040569 0.09251028 0.2584232 0.9644864 0.05462193 -0.337207 -0.9283059 0.1566517 0.7447133 0.6583874 0.1092162 0.7565901 -0.6395245 -0.1363079 0.9718588 0.009891331 -0.2353568 0.9852179 -0.02653533 -0.1692389 0.9386655 -0.07617253 -0.3363106 0.002799034 0.9708261 0.2397688 -0.2554299 0.9635174 -0.07993644 -0.03895533 0.9990968 0.01697558 -0.2729824 0.9619555 0.01106524 -0.8194187 0.5730622 0.01235961 -0.9663089 0.2571547 0.01089864 -0.9562098 0.2923008 0.01493203 -0.999917 0 0.01288384 -0.9995097 -0.02714341 0.0156123 0.9866682 -0.06604337 -0.1487424 0.9648945 0.08216345 -0.2494549 0.8200796 0.383346 -0.4248709 0.8169082 0.5386865 -0.2061016 0.3194011 0.943604 -0.0871461 -0.9993254 0.03295749 0.01620316 -0.999917 0 0.01289147 -0.9882557 -0.1176986 -0.0974574 -0.5730128 -0.8194536 0.01234036 -0.5830094 -0.8123505 0.01367592 -0.2624595 -0.9609506 -0.08768844 4.11134e-4 -0.9721217 0.2344768 -0.4197815 -0.896928 0.1389377 -0.7058473 -0.7058274 0.05989474 0.6582976 -0.7447959 0.109194 -0.7060661 0.7060326 0.05466824 0.9645022 -0.2583692 0.05459779 0.7040919 -0.7040657 0.09244567 0.4980995 -0.8627279 -0.08716362 0.4980986 -0.8627293 -0.08715611 0.3819465 -0.9202246 -0.08546155 0.4485669 -0.8894329 -0.08773201 0.4498059 -0.8888298 -0.08750069 0.453133 -0.8871092 -0.08779358 0.3191123 -0.943699 -0.08717614 0.3191142 -0.9436992 -0.08716672 0.3191148 -0.9436989 -0.08716887 0.3191126 -0.9436998 -0.08716589 0.3191328 -0.9436949 -0.08714467 0.9990975 -0.03929346 0.0161308 0.9999311 0.003756105 -0.01112025 0.2853771 0.9583718 0.009146213 0.9991139 0.04052239 0.01138365 0.7070569 -0.707045 0.01256942 0.3638554 -0.9313784 0.01198804 -0.4380994 -0.8988623 0.01075398 -0.7623566 -0.6470785 0.01009303 -0.9598951 -0.2802338 0.008388996 -0.9440386 -0.3294634 0.01565545 0.674129 0.7384646 0.0148397 0.9101746 0.4139763 0.01435053 0.9996463 0.02277576 0.01373386 0.9280928 -0.3721169 0.01314139 -0.4139679 -0.9101783 0.01435369 -0.0481624 -0.9987303 0.01477599 -0.0593478 -0.9981641 0.01209706 0.3294556 -0.9440417 0.01563656 0.674126 -0.7384645 0.01497584 0.9280927 0.3721173 0.0131455 0.3638552 0.9313781 0.01200962 0.7070421 0.7070595 0.01258552 0.8988606 -0.4381031 0.01073968 0.3721145 0.9280936 0.01316022 -0.7617563 0.6477848 0.01011914 -0.04053127 0.9990846 0.01368105 -0.7385038 0.6740908 0.01462417 -0.9621269 0.2725055 0.007264852 0.3192308 0.9436462 -0.08731311 0.3191174 0.9436998 -0.08714926 0.3191145 0.9437002 -0.08715498 0.3191138 0.9437004 -0.08715569 0.3191145 0.9437001 -0.08715581 0.319114 0.9437004 -0.08715498 0.3191117 0.9437012 -0.08715367 0.6857197 0.7241088 -0.0738579 0.6894465 0.7200237 -0.07892721 -0.00189054 0.9998341 -0.0181182 -3.74228e-4 0.9998603 -0.01671791 -3.96446e-4 0.9998593 -0.0167728 -6.59469e-5 0.9998337 -0.01823842 -4.56313e-4 0.9998443 -0.01764214 -0.2736078 0.9465675 -0.1707301 0.4568294 0.8852441 -0.08746236 0.5438203 -0.8375651 0.05238652 -0.4112281 -0.9075156 0.08548188 -0.3191141 -0.9437003 0.08715581 -0.3191141 -0.9437004 0.08715444 -0.319114 -0.9437003 0.08715534 -0.3191145 -0.9437001 0.08715564 -0.3191111 -0.9437015 0.08715355 -0.3192068 -0.9436798 0.08703863 -0.3003925 -0.9322622 0.2016226 -0.3191142 -0.9437002 0.08715569 -0.001847028 -0.9998109 0.01935893 -3.4329e-4 -0.9998551 0.01702421 -0.001730024 -0.9998366 0.01800245 -0.996607 -0.0586692 0.05772829 -0.5356755 -0.8372844 0.1095747 -0.5060561 -0.8568692 0.09839916 -0.9774955 -0.1854634 0.100528 -0.86628 -0.4985603 0.03157037 -0.636783 -0.06135016 0.7685984 -0.6595612 -0.1353836 0.7393581 -0.4663913 -0.8711553 0.1535176 -0.6765487 -0.6434949 0.3580452 -0.6761578 -0.5900761 0.4411585 -0.9178193 -0.2223723 0.3288744 -0.9364504 -0.2408021 0.2550981 -0.4929316 -0.1641469 0.854444 -0.6048135 -0.6219396 0.4973851 0.2062297 0.9760116 0.06979113 0.5444477 0.8371551 0.0524246 0.5441775 0.8373361 0.05233949 -0.4009963 0.88092 0.2513604 -0.3618133 0.8987893 0.2475257 -0.1472594 0.6549199 0.7412116 -0.1570853 0.7260507 0.6694585 -0.1947148 0.8554301 0.4799225 -0.04694682 -0.07156598 0.9963304 -0.1012872 -0.02700465 0.9944908 -0.07269042 -0.04133206 0.9964978 -0.086196 -0.00262624 0.9962748 -0.145851 -0.07245278 0.98665 -0.1285307 -0.1251404 0.9837783 -0.1150637 -0.09321349 0.9889751 -0.1102532 -0.1011022 0.9887481 -0.05965787 -0.08068621 0.9949526 -0.05013072 -0.05196464 0.9973899 -0.3097562 -0.9266886 0.2128365 -0.21452 -0.7357383 0.6423942 -0.3130814 -0.915898 0.2512193 -0.03606182 -0.5115846 0.8584759 -0.1702974 -0.6998296 0.6937127 -0.03628802 -0.5103337 0.8592106 -0.1744353 -0.6833354 0.7089605 -0.2526647 -0.7256831 0.6399568 -0.08093279 -0.8066793 0.5854218 -0.4455753 -0.8603187 0.2476179 -0.2937301 -0.8624566 0.4121786 -0.2612618 -0.8055607 0.5318028 -0.3711059 -0.8422411 0.3910378 0.3703343 0.9041928 -0.2128097 0.3095858 0.2408049 -0.9198749 0.4355456 0.1591512 -0.8859859 0.4535099 0.557511 -0.695349 0.3773784 0.7437132 -0.5517937 -0.5679482 0.8121011 -0.1338915 -0.8164479 0.5709865 -0.08595007 -0.9772521 -0.2062582 -0.04935461 -0.8016718 -0.5605685 -0.2075706 -0.4914022 -0.8695428 -0.04918646 0.7432805 0.6608422 -0.104027 -0.8012858 -0.0552991 0.5957208 -0.752223 -0.6583555 0.02699351 0.3633481 -0.9300613 -0.05444467 0.7063608 -0.7063636 -0.04588037 0.7528821 -0.6575123 -0.02909052 0.9980563 0.04048717 -0.04737728 0.992439 0.1164843 -0.03868234 0.8969801 0.4371954 -0.06547421 0.9346694 0.347173 -0.07657694 0.2188632 0.9746091 -0.04728907 -0.75065 0.66048 0.01705461 -0.6854719 -0.3952504 0.611478 0.5574774 0.7165446 -0.4192646 0.5514159 0.2516632 -0.7953655 -0.6635565 0.1454139 0.7338581 0.3818982 0.9099952 -0.1614393 0.646153 -0.7604546 -0.06477075 0.6263747 -0.7763044 -0.07075595 0.9638987 -0.2535981 -0.08116334 0.8978122 -0.4375867 -0.04951083 0.9982357 -0.04049283 -0.04342818 0.6624916 0.7461884 -0.06563502 0.7061728 0.706193 -0.05110114 0.3635204 0.9305016 -0.04494112 0.3751837 0.9143817 -0.1521298 -0.3758168 -0.7503208 -0.5438569 0.08248442 0.811024 -0.5791688 0.6607645 0.158846 -0.7335928 0.8081623 0.2473856 -0.5344851 0.9897195 0.1085149 -0.09316658 0.7139111 0.1195604 -0.6899538 -0.838181 0.04574632 -0.5434703 -0.4384434 0.7077218 -0.5539831 0.5979228 -0.05874806 -0.799398 0.2390516 0.74073 -0.6278324 0.2481445 0.7528681 -0.6096016 0.4769692 0.7847214 -0.3958697 -0.7350499 0.6316742 -0.2463521 -0.843142 -0.1591573 0.5135958 0.5775973 0.7083323 0.4057669 -0.4162054 -0.7347953 0.5355828 -0.4478151 -0.2094702 0.8692433 -0.3467373 -0.2144109 0.9131273 -0.2709179 -0.1746108 0.9466333 -0.2623049 -0.1165842 0.9579166 -0.4636961 -0.6924257 0.5527501 -0.3447816 -0.9013665 0.2620384 -0.3361489 -0.9289233 0.1552593 -0.3585264 -0.7351295 0.5753638 -0.366538 -0.3589782 0.8583616 -0.3257737 -0.4332611 0.8403312 -0.321551 -0.3798074 0.8673819 -0.2795106 -0.05278497 0.9586907 -0.344967 -0.1261171 0.9301034 -0.44404 -0.5808664 0.6822191 -0.3872935 -0.8217906 0.4179282 -0.3814367 -0.6892964 0.6159355 0.2076723 -0.9753282 0.07488191 0.02760332 0.07435578 0.9968497 0.9429833 0.05585902 0.3281192 0.03988879 0.9980583 -0.04783755 0.9653034 0.258702 -0.0355342 -0.9655016 0.2586732 -0.02991694 0.04004722 -0.9980625 -0.04761832 0.6913412 -0.7212742 -0.04255664 0.9652957 -0.2587053 -0.03572225 -0.7067046 0.7066676 -0.03448891 -0.2586885 -0.9654302 -0.03201359 -0.7066942 -0.7066779 -0.03449088 -0.9989468 0.003212392 -0.04577159 -0.9654809 0.2587365 -0.03003805 -0.7067033 0.706682 -0.03422212 -0.2586857 0.9654305 -0.03202843 0.2586686 0.9653828 -0.03356552 0.6913582 0.7212578 -0.04255783 0.9653207 0.2586123 -0.03571838 0.9984331 0.004513442 -0.05577808 0.9653296 -0.2586046 -0.03552979 0.7065272 -0.7064945 -0.04104703 0.6986549 -0.7142148 -0.04217439 0.2586717 -0.9653822 -0.03355848 0.6662495 -6.29731e-4 -0.7457287 0.686414 -0.0123229 -0.7271066 0.7023307 -8.31444e-4 -0.7118503 0.6444129 0.0110172 -0.7645984 0.6273049 -2.05354e-4 -0.7787739 0.6662497 6.4381e-4 -0.7457285 0.7023301 8.43741e-4 -0.7118509 0.9772981 0.1219053 -0.1732845 0.9710103 0.2316649 -0.05891132 0.9120371 0.4073055 -0.04786115 -0.9025055 -0.4196971 -0.09663522 -0.9737658 -0.2189219 0.06207573 0.1959708 0.04565966 -0.9795461 0.1492154 0.001317083 -0.9888039 -0.8263812 0.5589934 -0.06797415 -0.5883601 -0.8057017 -0.06839114 -0.3058974 -0.9341199 -0.1839752 0.9322525 -0.3580849 -0.05177462 0.5828728 0.8105672 -0.05692356 0.5989055 0.7970518 -0.07759374 0.1469835 -0.008000433 -0.9891067 -0.3697009 -0.928893 -0.02188915 -0.6691498 -0.7264129 -0.1567254 0.5691943 -0.7989116 -0.1943147 -0.3040504 0.9347638 -0.1837666 -0.4959193 -0.8667525 -0.0529564 0.9120485 -0.4072802 -0.04785758 0.9773063 -0.1218839 -0.173254 -0.9082438 0.3680242 -0.1991267 -0.973725 0.2191743 0.06182426 0.1492063 -0.001318037 -0.9888052 0.1959784 -0.04565703 -0.9795448 0.9478462 0.3187276 5.34758e-4 -0.523719 0.8252425 -0.211408 -0.7432158 0.6182739 0.2556713 -0.951587 -0.02525228 -0.3063405 0.5109387 0.8076109 -0.2944596 0.0679506 0.9484472 0.3095653 0.1666046 -0.9788947 0.1183557 0.01712906 -0.01069086 -0.9997962 0.02349871 0.01302784 -0.999639 -0.9334419 -0.3413247 0.1103807 -0.2130967 0.9300222 -0.2994136 -0.932586 -0.3405284 -0.1196826 0.8416317 -0.5363774 0.06289166 0.1612316 0.9616321 0.2219642 0.4752452 -0.86504 -0.160773 0.6821413 -0.5155739 -0.5185238 -0.2509771 -0.8390643 -0.4826817 -0.7427804 0.3104144 -0.5932288 -0.3961579 -0.9037393 0.1622164 0.9806396 0.04205513 0.1912522 0.5634732 -0.2485272 -0.7878657 0.02059125 -0.0620827 -0.9978586 0.003116071 -0.003822863 -0.9999879 -0.02097439 -0.05997467 -0.9979796 0.6391405 0.729767 0.2427749 -0.02658551 0.01208925 0.9995735 -0.01855719 -0.01175594 0.9997587 -0.04387098 -0.005646824 0.9990213 -0.01794731 0.05643808 -0.9982448 0.001776576 6.38462e-4 -0.9999983 0.002764344 -0.001028954 -0.9999957 0.004702627 0.007980227 -0.9999572 0.02487438 -0.03642773 -0.9990267 0.04651457 -0.001351177 -0.9989168 0.03191512 -0.03205913 -0.9989764 0 -0.1513067 -0.988487 8.80036e-5 -1.15768e-4 -1 0.7328226 -0.6803236 -0.01144397 -0.2648246 0.9635475 0.03800338 -0.7835139 0.5800288 -0.2228738 -0.9898818 -0.09172838 -0.1082593 0 -0.9907634 -0.135602 0.1666033 -0.9788951 0.1183545 0.2542955 0.462517 -0.8493596 -0.5304327 -0.5609825 -0.6355627 0.3035182 0.2267693 0.9254471 0.4658439 0.3946635 -0.7919788 0.9998273 0.01392781 0.0123049 -0.2462154 0.6174643 -0.7470715 -0.1399753 -0.4053192 -0.9033955 0.2886606 0.3558136 -0.8888599 0.9485782 -0.3162145 0.01441437 -0.2679859 -0.9490203 -0.1659644 -0.3174416 -0.9436001 -0.09407305 0.00557965 0.0142377 -0.9998832 0.02648466 -0.02947229 -0.9992147 9.63514e-4 -0.001099109 -0.999999 -0.4062201 -0.8492316 -0.3373293 0.9609345 -0.203214 0.1879069 0.01252365 -0.002280414 0.999919 0.0159887 0.02854537 0.9994647 -0.01715713 -0.0110687 0.9997916 -0.02710002 -0.009026706 0.9995921 0.05640345 -0.01066994 0.998351 -0.0106486 0.02246421 0.999691 0.01274591 0.07114434 -0.9973846 2.20452e-4 -4.18045e-4 -1 0.001009166 0.003939509 -0.9999918 -0.007172405 7.0512e-5 -0.9999743 -0.001002848 -9.45158e-5 -0.9999995 -0.8043054 0.5635645 -0.1883822 -0.505892 -0.7269142 -0.464402 0.6501293 -0.7568062 0.06764829 -0.9908103 -0.02627485 -0.1326827 3.6416e-7 -0.9907629 -0.1356061 -0.9859601 0.1266399 0.1088352 0.8372461 -0.5452696 0.0412327 0.8744115 0.4290007 0.2266342 -0.4782304 -0.6390745 0.602395 0.2270212 -0.115132 0.9670605 -0.4410544 0.642159 0.6269792 -0.2265115 -0.3057317 -0.9247815 -0.7931333 -0.4269912 -0.4343018 0.7571004 0.002223134 -0.6532949 -0.07421845 0.6765399 -0.7326565 -0.4751579 -0.8276216 -0.2987771 0.2106286 -0.9499651 0.2306554 -0.4551093 -0.8896045 -0.03846287 -0.2256168 -0.966382 -0.1233007 -0.8730263 0.4136221 -0.2583448 0.7924456 0.5482254 -0.2673555 0.2972053 0.6147418 -0.7305899 1.10923e-4 -3.44295e-4 -1 0.02854216 0.08327257 -0.996118 -4.20015e-4 -0.00406897 -0.9999917 0.01258617 -0.1787154 -0.9838204 0.00725305 2.82752e-4 -0.9999737 7.6193e-5 1.71565e-4 -1 -0.003498077 -0.002422034 -0.9999909 -0.2400864 -0.0758574 0.9677831 0.00784713 -0.002852082 0.9999651 -0.02753561 0.01270741 0.99954 -0.01008433 0.01917457 0.9997653 -0.02473801 0.06808662 -0.9973727 0.002933084 0.004829585 -0.999984 0.003563523 0.006731331 -0.999971 -5.03064e-4 -0.005736231 -0.9999835 0.02051275 4.24959e-4 -0.9997896 -0.01024049 0.08268743 -0.996523 -0.8085496 0.587476 0.03346031 0.8747355 -0.1875002 -0.4468575 -0.5585874 0.814059 -0.1590221 -0.7432106 0.6182746 0.2556846 -0.9515855 -0.02524918 -0.3063457 -0.6747382 -0.7377136 -0.02251619 0.9757823 -0.09040707 -0.1991874 0.8024008 0.5951039 -0.0447722 2.46111e-4 -1.4181e-4 -1 0.9397621 -0.3412111 -0.02055221 -0.1475211 0.9606837 0.2352116 -0.1497929 0.9594337 0.2388495 -0.1074178 0.7959603 -0.5957422 0.2739151 0.9375643 -0.2143452 -0.5299814 0.8480094 0 -0.2049526 0.9642398 -0.1680364 0.9171037 -0.3824785 -0.1123878 -0.7299636 -0.6673473 -0.1476513 0.7769268 0.6292095 -0.02191048 -0.1049341 -0.976464 -0.1884328 0.9871002 0.0693562 0.1443015 4.43315e-4 -4.64753e-5 -1 -0.9677121 0.1017113 -0.2306257 -0.7980959 0.4607946 -0.3882156 -0.07067531 0.9974994 0 0.5404812 0.8048099 -0.2452776 0.3267378 -0.1534838 -0.9325691 3.37945e-5 -4.78261e-4 -0.9999999 2.34478e-4 -3.25425e-4 -1 4.20353e-4 -1.19745e-4 -1 -0.0381326 -0.2684388 -0.9625417 -0.0026232 -0.2596783 -0.9656917 1.9214e-4 -0.003111124 -0.9999952 -0.2993735 -0.9482659 0.1056758 0.986589 -0.115565 0.115269 0.1739479 0.3928982 0.9029802 -0.2792698 0.1111617 0.9537566 0.01310998 0.02807009 0.99952 0.03533178 -0.03239923 0.9988504 -0.03007638 -0.01741522 0.999396 -0.005652487 -0.06127518 0.998105 -0.01272928 0.05988937 -0.9981239 -0.1148025 -0.1227257 -0.9857783 -0.00775659 -0.01167321 -0.9999018 -0.02434641 0.002253413 -0.9997012 -0.1059907 0.01328212 -0.9942784 0.1110654 -0.001717865 -0.9938116 4.33243e-7 -0.1901184 -0.9817612 -0.03406113 -0.07684278 -0.9964613 0.1282624 0.04694998 -0.9906284 3.99159e-4 -9.03181e-5 -1 -0.004060387 -0.01220184 -0.9999174 -0.01624011 0.05846101 -0.9981576 5.89838e-4 -0.9998496 0.01733702 0.9809314 -0.00339359 -0.1943253 0.9809308 -0.003389716 -0.194328 -0.9809317 0.003388822 0.1943231 -0.9809312 0.003383338 0.1943262 -0.9809308 0.003397345 0.1943277 -0.1839191 -0.9120498 0.3665229 0.2538692 -0.2376692 -0.9375841 0.2011563 -0.9205628 0.334814 -0.192835 -0.01799517 -0.9810663 -0.1943533 -0.01608639 -0.9807997 0.9809315 -0.003388106 -0.1943244 0.9809595 -0.003511786 -0.1941809 0.9810011 -0.003128945 -0.1939772 0.119157 -0.02645862 0.9925228 0.2256639 -0.006412446 0.9741842 -0.9810217 0.002254724 0.1938847 -0.9806578 0.005167424 0.1956622 -0.9810726 0.00532031 0.1935673 -0.9812485 0.003504693 0.1927152 6.37201e-6 -0.9998481 0.01743739 2.64424e-6 -0.999848 0.01744019 3.06768e-6 -0.9998479 0.01744675 -4.20516e-6 -0.9998478 0.01744997 -5.44347e-6 -0.9998478 0.01745188 8.67471e-7 -0.9998478 0.01745003 2.77048e-6 -0.9998478 0.01744955 2.75353e-6 -0.9998478 0.01744633 -1.10542e-6 -0.9998478 0.01745033 4.47451e-6 -0.9998478 0.01745349 3.89287e-6 -0.9998477 0.01745414 7.33249e-6 -0.9998477 0.0174514 -1.61574e-6 -0.9998478 0.01745015 9.69451e-7 -0.9998478 0.01744776 0.8552792 -0.009015321 -0.5180891 0.9810041 -0.003340423 -0.1939586 0.8763678 0.00840485 0.4815692 0.6587798 0.01313012 0.7522214 0.3617621 0.01626825 0.9321285 -0.321726 0.01652389 0.9466887 -0.8555325 0.009099543 0.5176693 -0.9882396 -0.00266987 -0.1528902 -0.6587821 -0.01313161 -0.7522193 -0.021066 -0.01744461 -0.9996259 0.8763682 0.008405685 0.4815683 0.3617398 0.01627057 0.9321372 -0.8553025 0.009043037 0.5180503 -0.8763629 -0.008405566 -0.4815784 -0.3617372 -0.01627123 -0.9321382 0.005028367 0.999406 -0.03409373 0.006709098 0.9992879 -0.03713315 -0.001335799 0.9998192 -0.01897329 -0.005115032 0.9997818 -0.02025383 -0.9992582 -0.03558039 0.01474416 -0.3123579 -0.8504471 0.4232877 -0.3831148 -0.3612888 0.8501138 -0.1530075 -0.1076983 0.982339 -0.4217864 -0.4793841 -0.769602 0.03449833 0.03922033 0.9986349 -0.6029013 -0.01936972 -0.7975807 -0.8577583 0.01895844 0.5137035 -0.8228126 0.01478469 0.5681206 0.9884297 -0.006221771 0.1515529 -0.9691066 -0.01231026 0.2463351 0.500702 0.1128134 -0.858237 -0.05657464 -0.01010411 -0.9983473 0.5229194 -0.3204919 0.7898358 -0.004730105 -0.2142089 -0.9767764 -0.008829832 -0.2397909 -0.9707844 0.111495 -0.9442058 -0.3099104 0.7594797 -0.01912099 0.6502501 0.6767365 -0.6774457 0.2882623 0.6090306 -0.1411622 0.7804838 0.2414011 0.4852788 -0.840375 0.7541203 0.5190649 -0.4023363 0.8450101 0.3791238 0.3771249 -0.5970863 0.4489061 0.6648092 -0.5749858 0.4143084 -0.7055069 -0.7490062 0.01867055 -0.6623 0.4133307 0.03731209 0.9098162 0.9579779 0.0113551 -0.2866172 0.7013167 0.07189559 -0.7092151 -0.483002 0.01950246 -0.8754021 -0.9390884 0.03441518 -0.3419486 -0.03553199 0.9966327 -0.07389652 0.1176984 0.9930309 0.006064236 -0.03789645 0.9979828 -0.05093663 0.007503747 0.9996324 0.0260545 0.05804091 0.9982972 -0.005834877 -0.005941569 0.9979284 -0.06406038 -0.6128358 -0.7183402 -0.3292715 0.2200775 0.01214945 0.9754068 0.9421446 -0.02567857 0.334222 -0.1358251 0.2098923 -0.9682442 -0.6725556 0.1792567 0.7180083 0.9347729 0.2340092 0.2672817 -0.8616888 0.4763275 -0.1749417 0.4249792 0.3062439 0.851826 0.01908195 0.4786086 0.877821 -0.9031331 0.4276487 -0.03830772 -0.8296625 -0.1209361 -0.5450088 0.9472684 0.2658339 -0.1789273 0.3350196 -0.6931979 -0.6381524 -0.6526165 -0.1347065 0.7456178 0.2156111 0.2598553 -0.9412689 -0.5774872 -0.5405638 -0.6118002 -0.8362557 -0.5009588 -0.2229724 -0.5023714 0.7748278 0.3837512 8.9879e-7 0.9998477 -0.01745265 0 0.9998477 -0.01745194 -6.03965e-6 0.9998478 -0.01744991 0.9092239 -0.3597179 -0.2095587 -0.2540277 0.4007928 0.8802472 -0.9995236 -0.02680516 -0.01530134 -0.4839725 -0.1122676 -0.8678519 0.4467294 -0.06353241 -0.8924106 0.8968243 0.02139729 -0.4418693 0.9974231 -0.02664101 0.0666151 0.4378913 0.102086 0.8932132 0.1460152 0.9686838 0.2008268 0.001405417 0.9980734 -0.062029 0.1391872 0.9874593 0.07450592 -0.1773986 0.9801309 0.08873146 -0.2145947 0.976183 0.03187549 0.103851 0.9945805 0.004954338 0.09970837 0.9880219 0.1177755 0.2614061 0.9056814 -0.3337788 -0.1649854 0.8870264 -0.4312353 -0.6764107 0.6378712 0.368224 -0.1908244 -0.9659062 0.1749611 -0.06531435 0.6514537 -0.7558718 0.9764729 0.09766739 -0.1922544 0.2170642 0.208971 0.9535273 0.08182877 -0.8179503 0.5694397 -0.1087887 -0.8741886 -0.4732436 0.4603608 -0.3986743 -0.7931752 -0.9488911 0.1993302 -0.2446902 -0.9528193 0.2055076 -0.223388 -0.1764523 -0.8403691 -0.5124884 0.4646272 -0.06899422 -0.8828145 0.7120004 -0.4228286 -0.5605992 -0.4451478 -0.4389819 -0.7804732 -0.3549104 -0.6782504 -0.6434401 0.1681129 0.984865 -0.04217928 -0.1480441 0.9875044 0.05401927 -0.9715617 0.132193 0.1964511 -0.8415027 -0.5148199 0.1638105 -0.1170325 -0.9931269 -0.001555681 -0.7676759 0.6168867 0.1735641 -0.9723843 0.03996461 0.2299383 0.234179 -0.9719383 -0.02228099 0.7824809 -0.6115991 -0.1169207 0.9619562 -0.1506164 -0.2279367 0.1419308 -0.8894581 0.4344193 -0.3412027 0.4527062 0.8237948 -0.9375572 0.094208 0.3348308 0.9751627 -0.2033151 0.08786821 0.7861866 -0.6143825 -0.06667059 -0.642907 -0.6905529 0.3313719 -0.9772516 0.1069103 0.1831652 -0.4607498 0.5850292 0.6674208 -0.3444443 0.9341748 0.0931425 0.4823451 0.8748525 0.04445719 -0.6962031 -0.6674173 0.2643018 0.9199314 0.2465078 -0.3048939 -0.1943365 0.001045584 -0.9809343 -0.1224591 -0.3189166 -0.9398383 -0.3539854 -0.9351921 -0.01049906 -0.9341112 0.2567822 -0.2479901 0.7899941 -0.5905025 -0.1649729 0.8117718 -0.5583439 -0.1711102 0.6945949 -0.7041786 -0.1472085 0.1879135 -0.9814401 -0.03826117 -0.1961758 -0.9800872 0.03072649 -0.8189098 -0.5527244 0.1545392 -0.9627701 -0.191771 0.1905195 -0.9627221 0.1984331 0.1838216 -0.5433961 0.8333273 0.1014219 0.1948357 0.9801164 -0.03756338 0.5464462 0.8295635 -0.1149824 0.9611162 0.1917511 -0.1987141 0.9571084 -0.2112157 -0.1983222 -0.3520482 -0.9334532 0.06875562 -0.5492492 -0.8295534 0.1008298 -0.8189067 -0.5527287 0.1545414 -0.8149803 0.5583925 0.1549353 -0.5433847 0.8333346 0.1014227 0.7938073 0.5850198 -0.1661977 0.9584581 0.2046176 -0.1987209 0.9528407 0.1916081 -0.2353316 0.8074778 0.552188 -0.2075282 0.1851614 0.9790098 -0.08517736 -0.1971266 0.9803326 -0.009445965 -0.9703984 -0.1915545 0.1470841 -0.6408572 -0.7631335 0.08324295 0.6190982 -0.7674915 -0.1663556 -0.01155257 -0.9990955 -0.04092544 -0.3465832 -0.9376773 0.02532368 0.1782535 -0.9802305 -0.08587235 -0.9730715 0.1768681 0.147816 -0.8553183 0.5025148 0.1261328 0.9514647 -0.1981644 -0.2354697 -0.4356172 -0.3329367 -0.836296 0.468685 -0.5927425 0.6549738 0.165038 0.9839292 -0.06816112 0.2438807 0.2905137 0.9252698 0.2861747 -0.86619 0.4096571 0.2885325 -0.8395982 0.4602434 0.2290486 0.8073897 -0.543745 -0.618351 0.528297 0.5818458 0.323946 -0.3993362 0.8576652 0.4421076 -0.6737985 0.5920612 0.003527879 0.9999938 3.548e-4 0.1917284 0.007257044 0.9814212 0.1322064 -0.03079062 0.9907439 0.1943196 -0.001511514 0.9809371 0.2080737 -0.01649713 0.9779741 0.1970039 0.001883924 0.9804009 0.1943175 -0.001034379 0.9809382 0.1943249 -0.001031816 0.9809368 -0.9809302 0.003829181 0.1943233 -0.9809772 0.002920985 0.1941016 -0.9809314 0.003387928 0.1943251 -0.9809913 0.003045856 0.1940281 0.6699816 0.7320138 -0.1236146 0.09589546 0.9953876 0.002782166 0.9647586 -0.1769747 -0.194733 0.9575509 -0.2169072 -0.1898625 -0.3387482 -0.9385513 0.06611406 -0.6465564 -0.7519025 0.12887 -0.8273999 -0.5366531 0.1655688 -0.9657377 -0.1703103 0.1958195 -0.9652487 0.1769892 0.1922754 -0.2212964 -0.9522932 0.2101565 0.9768265 -0.1353394 -0.1658114 0.9775328 0.09992438 -0.1855931 0.9644241 0.1815691 -0.1921429 0.8444839 0.5095517 -0.164937 0.6322772 0.7638523 -0.1294426 0.3377248 0.9385195 -0.07157534 -0.6287745 0.7682145 0.1203719 0.6973243 0.7040902 -0.1341485 0.6846209 0.7174623 -0.1286168 0.4506517 0.8887356 -0.08403646 -0.4427474 0.8918159 0.09294873 -0.338805 -0.9385294 0.06613439 -0.002868294 -0.9999917 0.002929747 0.3321844 -0.9408462 -0.06679922 0.6278293 -0.7682204 -0.1251711 0.847753 -0.502925 -0.1684679 0.01192718 0.9867554 -0.1617766 0.1173683 -0.0662617 0.9908754 0.9744716 0.02881729 -0.2226542 0.9648924 -0.1799274 -0.1913346 0.3125646 0.05771309 0.9481417 0.3102949 0.0574277 0.9489042 0.3352513 -0.9413691 0.03782796 0.8885448 -0.4577642 0.03066098 0 2.19969e-6 1 -0.5559228 0.8312066 0.006760537 -0.5288394 0.8484593 0.02111905 -0.8865365 0.462566 -0.009258687 0.9999638 -6.23464e-4 0.008491873 0.1938361 -0.9810335 -9.75726e-4 0.9836175 0.1800782 0.00828588 -3.14563e-4 -0.9999613 0.008804798 -0.999962 2.10227e-4 0.008723318 0.8582275 -0.04480785 0.5113101 0.4090163 -0.8179761 0.4045007 0.3963046 -0.8830985 0.2511569 0.2650851 -0.0653364 0.9620089 0.3456795 -0.6901359 0.6357815 0.3844251 -0.3182251 0.8665739 0.3764662 -0.6960043 0.6114338 0.3463459 -0.6944266 0.6307268 0.4139595 -0.8558428 0.3101141 0.4673994 -0.8597669 0.2057637 0.877139 -0.4610875 0.1342594 0.94946 -0.03175538 0.3122779 0.7248567 -0.5816938 0.3690735 0.4137704 -0.8057035 0.4238349 -0.2587089 0.1168261 -0.9588646 -0.2747057 0.1383461 -0.9515237 -0.379742 0.4818177 -0.7897137 -0.3563873 0.7838901 -0.5084334 -0.3475394 0.650254 -0.6755636 -0.3075487 0.3595127 -0.8810021 -0.5134779 0.6335539 -0.5787487 -0.426536 0.3811804 -0.8202248 -0.8936705 0.2281364 -0.3864026 -0.9470552 0.09773445 -0.3058341 -0.7706654 0.6202504 -0.1461657 -0.4415979 0.8747281 -0.1996052 -0.4008133 0.8741161 -0.2743533 -0.3138344 0.3827896 -0.8688959 -0.3282061 0.90002 -0.2867836 -0.3450338 0.6806729 -0.6462478 -0.3563495 0.8202145 -0.4475077 -0.7354996 0.582346 -0.3462854 -0.9998458 -0.001098275 0.01753246 -0.9980334 -0.03576022 0.05148416 5.71085e-6 -0.9998477 0.0174598 -2.81169e-5 -0.9998478 0.01745218 0.9998476 -1.85019e-5 0.01745843 0.8947971 0.4325163 0.1107603 -0.08714056 -0.9960432 -0.01745152 -0.08714091 -0.9960432 -0.01745241 -0.08804655 -0.9960036 -0.01499664 -0.0897606 -0.995808 -0.01759201 0.003416717 -0.002711594 0.9999906 -0.9983139 3.21905e-5 -0.05804723 -0.01928448 -0.01889491 0.9996356 0.007141828 -0.9987971 -0.0485118 0.02337419 -0.998305 -0.05330073 0.002643525 -0.9988763 -0.04732137 0.9986293 5.91394e-4 -0.05233728 -7.08974e-5 0.9998477 -0.01745617 1.24049e-5 0.9998478 -0.01745265 1.56947e-6 0.9998477 -0.01745259 0 0.9998478 -0.01745253 -0.9986104 0.001445949 -0.05267924 0.0025931 0.9999406 0.01058304 -4.46729e-4 0.9999597 0.008975148 0.9985677 0.006570518 0.05309921 0.9984963 3.456e-4 0.05481964 0.09223568 -0.9957323 0.003163576 -8.76618e-6 -0.9998477 0.01745617 0 -0.9998477 0.01745223 0 -0.9998477 0.01745229 8.64006e-7 -0.9998478 0.01745229 8.42643e-7 -0.9998477 0.01745223 0 -0.9998478 0.01745235 -2.4582e-4 -0.9998432 0.01770794 0.9999618 -4.44135e-4 0.008743107 0.5455219 -0.8379964 -0.01295977 -0.4136291 -0.9055308 0.09447252 -0.9982842 -0.05854427 -0.001170933 -0.9997659 -0.01964324 0.009067714 -0.6074734 0.7706658 0.1924846 0.9998477 0 0.01745736 0.9998477 0 0.01745736 -0.08714306 -0.996043 0.01745015 -0.9997431 -0.006441593 0.02173548 -0.01142656 0.03723937 -0.9992411 0 0.01182699 -0.9999301 0.8394131 -0.5418177 -0.04265475 0.9986297 0 0.05233424 -0.4672968 0.3436375 0.814584 0.02924442 0.2824919 0.9588239 -0.09885561 -0.1725526 -0.9800271 -0.07208609 -0.07951956 -0.9942234 -0.9908321 0.1345705 0.01194643 -0.02250283 -0.009937942 0.9996975 0.06800717 -0.5820895 0.8102759 -0.02942806 -0.343537 0.938678 0 -0.3342652 0.9424791 0.6847904 0.7286678 0.01026362 0.025581 0.7957916 0.60503 -0.01564615 0.8272492 0.5616174 0.4804367 0.8293758 0.2851603 0.7923108 0.5871715 0.1657506 0.6305547 0.6509736 0.4226514 -0.412633 -0.8789391 -0.2391654 -0.9920395 -0.1130125 -0.05555069 -0.4305548 -0.8805883 -0.1979573 -0.7959464 -0.5786641 -0.1778126 -0.9610131 -0.2467125 -0.1248474 -0.4098497 -0.8810855 -0.2360335 -0.4753106 -0.8487063 -0.2318996 -0.5915215 -0.4516982 -0.6678856 -0.5619331 -0.3114041 -0.7663281 -0.7516306 -0.402634 -0.5224341 -0.8022022 -0.5492219 -0.2341518 -0.9998807 0.01034933 0.01147216 -0.9998409 0.002420186 0.01767432 -8.59538e-7 0.9998478 0.01745194 0.9998477 -1.00655e-4 0.01745635 0.9998459 1.20946e-4 0.01756215 0.9044369 -0.4179948 0.08528947 -0.08839124 0.9959906 -0.01377046 -0.0871424 0.996043 -0.01745116 -0.08714282 0.9960429 -0.01745384 -0.9985354 0.01470816 -0.05206584 -0.9985463 0.005386888 -0.0536319 0 0.02611219 0.9996591 -0.7887814 0.6016477 0.1258727 -0.4071556 0.7045138 0.5812786 0.007353425 0.9991196 -0.04130464 -0.001147806 0.9985799 -0.05326181 9.93408e-5 0.9986211 -0.05249875 -9.77743e-4 0.9986063 -0.05276918 0.9989038 -4.64589e-4 -0.0468105 0.9984755 0.009418249 -0.05438798 3.56753e-5 -0.9998477 -0.01745557 -8.17769e-5 -0.9998477 -0.0174542 -2.55558e-5 -0.9998478 -0.01744478 1.73776e-7 -0.9998477 -0.01745223 0 -0.9998478 -0.01745241 -0.9986293 -2.68073e-4 -0.05234056 -0.5805212 0.03189015 0.8136205 -0.6795079 -0.003364861 0.7336605 0.002752661 -0.9999381 0.0107795 -4.78779e-4 -0.9999594 0.008996725 2.45158e-6 -0.9999619 0.008726716 0.376062 -0.9228797 0.08288884 0.5429104 -0.8367353 0.0715714 0.9985896 0.002514421 0.05303204 0.9986295 3.96594e-5 0.05233633 -2.8536e-5 0.9998476 0.01746374 0 0.9998478 0.0174514 0 0.9998478 0.01745253 0 0.9998477 0.01745259 7.76574e-5 0.9998489 0.01738458 -7.87504e-5 0.999849 0.01738184 -1.20875e-7 0.9998478 0.017452 1.69579e-4 0.9998478 0.01744985 -2.83298e-5 0.9998484 0.01741123 0.9995192 0.02959156 0.009254097 -0.9983541 0.05733472 0.001333892 0.08714324 -0.9960429 0.01745271 0.08713054 -0.996044 0.01745218 0.9998477 0 0.01745736 -0.08715111 0.9960423 0.0174517 -0.08714354 0.9960429 0.01745057 -0.08714336 0.996043 0.01745033 -0.9985639 -0.04348766 0.03128945 -0.8307829 -0.4025411 -0.3843963 0.9986296 0 0.05233424 -0.4827038 -0.3451122 0.8049191 0.2065944 -0.1487038 0.9670605 0.001519381 0 0.9999989 -0.7560675 -0.1613583 0.6342915 -0.01114881 -0.3401811 0.9402939 -0.9988065 -0.03275084 -0.03623294 -0.102953 -0.1824834 -0.977804 -0.9899642 -0.1340243 0.04481714 -0.03161275 0.008695185 0.9994624 0.4518741 0.3781502 0.8079679 0.006207525 -0.8182654 0.5748072 0.314459 0.9298959 0.1908119 0.314448 0.9299004 0.1908082 0.3144483 0.929899 0.1908146 0.314456 0.9298819 0.1908852 0.3143708 0.9299283 0.1907994 0.3144489 0.9299 0.1908087 0.1294199 0.9745674 0.1829453 0.3144482 0.9299001 0.1908092 0.3144479 0.9298964 0.190828 0.3145196 0.9297082 0.1916252 -0.3144486 -0.9299001 -0.1908086 -0.3144488 -0.9298995 -0.1908115 -0.3144487 -0.9298996 -0.1908105 -0.3144486 -0.9299001 -0.1908091 -0.3134053 -0.9288553 -0.1974971 -0.3341195 -0.9230036 -0.1908628 -0.3144486 -0.9299002 -0.1908087 -0.3144484 -0.9299001 -0.1908093 -0.3144691 -0.9298917 -0.1908162 -8.52324e-7 0 1 -5.19199e-4 0.002427041 0.999997 -0.112267 -0.2665567 0.9572584 5.04322e-4 -0.005761921 0.9999833 2.74125e-7 0 1 -3.78544e-5 -1.53863e-4 1 1.38172e-4 -9.69586e-5 1 1.17692e-4 8.9459e-5 1 3.9632e-5 -2.95489e-5 1 -3.92018e-6 -1.6088e-5 1 0.03126955 -0.03607565 0.9988598 0.01444202 -0.03408598 0.9993146 0 -4.89906e-4 1 -0.3328204 -0.911752 -0.240705 -0.3581342 -0.2616065 -0.8962712 -0.2884436 -0.07460713 -0.9545859 -0.2640329 -0.1385434 -0.9545117 -0.2772597 -0.168435 -0.9459159 -0.346364 -0.6808974 -0.645299 -0.3235369 -0.397338 -0.858747 -0.3354715 -0.5111973 -0.7912877 0.3144485 -0.9299002 0.1908087 0.3144482 -0.9299002 0.1908088 0 0 1 0.04836875 -0.01039868 0.9987754 0 -4.67971e-5 1 -0.3144477 0.9298999 -0.1908111 -0.3179036 0.9272536 -0.1978338 -0.3144488 0.9298995 -0.1908112 -0.3144485 0.9299002 -0.1908085 -0.3144119 0.9299997 -0.1903836 -0.3178308 0.9399011 -0.1247788 0.9999934 0.001450181 -0.003369033 0.9999123 0.01183646 -0.005935788 -3.05791e-7 0 1 1.92323e-7 0 1 0.6338704 0.2143461 0.7431448 0.9421166 0.3185755 0.1045274 0.9999183 -0.01262962 -0.001977741 -0.2411077 0.5415338 -0.8053622 0.4634207 -4.65679e-4 0.8861383 0.467427 -2.15321e-4 0.8840317 0.5119946 0.0046283 0.8589764 0.5984355 -0.007522165 0.8011358 0.4896714 -0.008343756 0.8718672 0.72417 -0.03287827 0.6888374 0.7975148 0.01739883 0.6030485 0.9036982 0.007494032 0.4281048 0.6021412 0.003212809 0.7983832 0.4981452 -2.1045e-4 0.8670936 -0.4889014 0.00179255 -0.8723372 0.55972 1.89062e-4 0.8286818 0.5828983 0.002358675 0.8125416 0.6886528 -0.01451164 0.724946 0.6566253 -0.005764544 0.7541949 0.8205198 0 0.5716183 0.6894436 9.95341e-4 0.7243387 0.7930926 -4.19629e-4 0.6091011 0.8113862 -0.002176105 0.5845064 0.9180015 0.00237751 0.3965698 0.9505186 -0.08506113 0.2987961 0.9941146 3.08973e-4 0.1083331 0.8060222 -0.3786841 0.4548919 0.9357196 -0.05847692 0.347864 0.9818558 0.06351822 0.1786748 0.9984573 0 0.0555275 0.9984572 0 0.0555275 0.9505222 0.08467501 0.2988942 -0.8591199 -0.01296371 -0.5116103 0.9222848 -0.0185495 0.3860657 0.9417845 0 0.3362173 0.8094036 0.00689131 0.5872123 0.7584982 0.002730369 0.6516695 0.7628071 0.01075172 0.6465368 0.1804004 -0.1005882 0.9784364 0.8145872 0.01403361 0.5798715 0.875304 -0.1160547 0.4694405 0.9355106 -1.98364e-5 0.3532988 0.9679927 6.38895e-4 0.2509781 0.970959 0.006415963 0.2391601 0.7458967 0.03365403 0.6652109 0.6296312 0.02263623 0.7765644 0.3530071 0.007814168 0.9355881 0.2235457 3.4848e-4 0.9746934 0.2361836 6.09984e-4 0.9717082 0.2370364 0.003343999 0.971495 0.2223967 -7.23623e-5 0.9749563 0.2286487 1.88089e-4 0.973509 0.2420117 -1.20444e-4 0.9702733 0.2603632 0 0.9655108 0.2566546 2.3002e-4 0.9665033 0.2522354 -9.00389e-5 0.9676659 0.239445 1.55458e-4 0.97091 0.2608546 0 0.9653782 0.2281143 0.004597306 0.9736236 0.2371318 -8.33692e-5 0.9714776 0.2482365 -0.002486169 0.9686963 0.3306949 3.88963e-4 0.9437376 0.3376227 -3.04632e-5 0.9412816 0.3118942 0.05277991 0.9486497 0.3877898 -3.8025e-4 0.9217479 0.8568009 -0.01572412 0.5154076 0.9342461 -0.08122128 0.3472571 0.9707806 0.02140301 0.2390128 0.9582197 -0.06737393 0.2779857 0.9923042 0.001105785 0.1238196 0.9350816 0 0.3544328 0.8757302 0.1116725 0.4697083 0.9335138 0.00149554 0.3585383 0.948942 -0.01467728 0.3151091 0.926005 0.04341518 0.3750064 0.9131687 -0.0642066 0.4024931 0.896079 -0.002020359 0.4438901 0.9191679 -0.03846257 0.3919833 0.2222867 8.23112e-5 0.9749814 0.3827115 1.88951e-4 0.923868 0.2702834 -0.001072347 0.9627802 -0.6632064 0.03544628 -0.7475968 -0.8039167 0.0198636 -0.5944103 -0.9485165 -2.96572e-4 -0.3167278 -0.9325534 -5.66655e-4 -0.361032 -0.8352454 3.19878e-4 -0.5498774 -0.740814 6.39764e-4 -0.67171 -0.5934073 1.16423e-4 -0.8049023 -0.4122219 1.7914e-5 -0.9110835 -0.3684235 -2.64617e-4 -0.929658 -0.2717009 9.88049e-4 -0.9623813 -0.2712311 -0.002196431 -0.9625118 -0.2973822 5.70795e-4 -0.9547584 -0.2823256 -2.65953e-5 -0.9593186 -0.8424088 0.009824275 -0.5387494 -0.4604702 1.45187e-5 -0.8876752 -0.7928085 -3.34967e-4 -0.6094709 -0.9167705 0.004233062 -0.399392 -0.9012318 -0.01273673 -0.4331504 -0.8547192 -0.01053363 -0.5189839 -0.9694796 0.002366483 -0.2451605 -0.9592835 0 -0.2824451 -0.9530653 -0.001650333 -0.3027607 -0.9724334 0.009915709 -0.2329702 -0.9592834 0 -0.2824454 -0.9347574 -0.00107491 -0.3552855 -0.953647 0 -0.3009275 -0.9798465 0.009700834 -0.1995168 -0.98855 -0.02328693 -0.1490865 -0.7528424 -0.6527952 0.08418333 -0.9348685 2.72157e-4 -0.3549943 -0.93237 7.94582e-4 -0.3615047 -0.9536474 0 -0.3009263 -0.9536327 -1.28606e-5 -0.3009728 -0.9536584 1.09636e-5 -0.3008916 -0.9660652 -0.003072738 -0.2582803 -0.9858944 8.443e-4 -0.1673667 -0.9884755 -4.775e-4 -0.1513805 -0.9879361 3.75655e-4 -0.1548619 -0.9719245 -0.004615724 -0.235248 -0.9719038 0.007652342 -0.235254 -0.9921563 4.94207e-4 -0.1250034 -0.9950965 0 -0.09891003 -0.9985356 0.002343535 -0.05404907 -0.3214295 8.69388e-4 -0.9469332 -0.3308613 9.32687e-5 -0.9436794 -0.2593553 4.90678e-4 -0.9657819 -0.222183 0 -0.975005 -0.2716669 0 -0.9623914 -0.23113 -0.002227067 -0.9729204 -0.2538394 8.96176e-4 -0.967246 -0.2580083 0 -0.9661428 -0.2580057 0 -0.9661434 -0.268531 1.72458e-4 -0.9632711 -0.2297055 -2.58367e-5 -0.9732602 -0.2274022 1.11509e-4 -0.9738009 -0.339821 -0.00479716 -0.9404779 -0.4127032 6.0618e-5 -0.9108656 -0.9575477 -0.00749284 -0.2881775 -0.9784114 0.007036983 -0.206547 -0.9979036 -0.03268104 -0.05586045 -0.9845172 0.05957818 -0.1648527 -0.8967887 0.01184999 -0.4423005 -0.4576537 0.001047849 -0.88913 -0.460847 0 -0.8874796 -0.4408888 0.003402411 -0.8975554 -0.2651358 0 -0.9642111 -0.9170117 -0.001007914 -0.3988593 -0.9119954 0.001016199 -0.4101994 0.1924883 -0.1005913 0.97613 0.3434267 -0.8984894 -0.2734505 0.3543286 -0.9261399 -0.1292908 -0.006256103 0.04023754 0.9991706 0.01166743 -0.03112602 0.9994475 -0.7218704 0.006574988 0.6919971 -0.6389755 0.01996159 0.7689682 -0.5512203 -0.005048096 0.8343445 0.3144481 -0.9299002 0.1908087 0.2578178 0.1137945 0.9594691 0.3683066 0.8715777 0.323578 0.4313858 0.2903043 0.8541837 0.3105676 0.3986048 0.862938 0.296507 0.2297732 0.9269778 0.1928438 0.1000474 0.9761157 0.9999828 -0.001803934 -0.005581557 0.9999963 -0.00184071 -0.002022027 0.999985 -8.983e-4 -0.005422055 0.9971643 0.01065546 0.07449823 0.9999957 -0.002205729 -0.001975119 -0.2505851 -0.9668154 0.04975205 -0.09125238 -0.9515851 -0.2935283 0.08046126 -0.952374 -0.2941257 -0.02940434 -0.99928 0.02397739 -0.4054022 -0.02060204 0.9139063 -0.7508711 0.001702368 0.6604467 -0.4042752 -0.02073198 0.9144024 0.1355639 -0.01771265 0.9906103 -0.891898 0.237855 0.3846336 0.9970078 -0.004160106 0.07718986 0.2454433 -0.9623528 -0.1167685 0.2173836 -0.9739527 0.06450283 -0.1434589 -0.9745924 -0.1720153 -0.1638773 -0.9810545 -0.1033272 -0.2529573 -0.9510387 -0.1775896 -0.6935048 -0.6642249 0.2790278 0.999962 -1.12473e-4 0.008716881 0.999962 0 0.008729934 0 -0.999962 0.008726596 -3.44511e-6 -0.999962 0.008727073 0.999962 -1.02016e-4 0.008725881 0.004552721 0.999952 0.008684813 -1.9087e-7 0.999962 0.008726358 0 0.9999619 0.008726418 0.9999619 0 0.008726358 2.425e-7 0.9999619 0.008726477 0 0.999962 0.008726418 -0.9999613 -0.001200258 0.008713901 -2.3587e-5 -0.999964 0.008487343 -6.24952e-4 -0.9999617 0.008730411 -0.004156768 -0.01258015 0.9999123 -5.3317e-6 0.999962 0.008726894 0.9999607 0 0.008868694 -9.06721e-6 0.9999619 0.008726418 0 0.999962 0.008725166 0.9999619 0 0.008729934 -2.7821e-7 -0.9999619 0.008726418 -7.6091e-4 -0.9999612 0.008776605 -0.9999625 0 0.008657872 -0.9999613 0.001187622 0.008714079 -4.11195e-7 -0.9999619 0.008726477 0 -0.999962 0.008726418 -7.60034e-5 -0.9999622 0.008694529 -0.999962 -7.58825e-6 0.008726537 -0.1382698 -0.5067412 0.8509377 -0.4233027 -0.2782617 0.8621979 -0.1890159 -0.9436054 0.2718124 0.07909208 0.04921585 -0.9956517 0.02139389 0.08400142 -0.996236 -0.2031108 0.5173932 -0.8312944 0.05148196 0.9257521 -0.3746101 -0.1735354 0.9527062 0.2494726 0.1149551 0.7731814 0.6236794 0.2180653 0.0357052 0.9752808 -0.0204333 0.9997548 0.008546292 0.9997751 -0.02028787 0.006188511 0.9999619 0 0.008728682 0.9999753 0 0.007030606 0.06891059 -0.9974703 -0.0174455 -0.1925527 -0.9690535 0.1544636 -0.2770646 -0.001988172 -0.9608492 -0.2999267 8.16652e-7 -0.9539623 -0.2006677 0.008879542 -0.9796192 -0.3002238 1.43832e-4 -0.9538688 -0.1733477 -0.01748704 -0.9847055 -0.7239898 -0.003372251 0.6898025 0.193325 -0.06200158 0.9791738 0.6128709 0.05098491 0.7885367 0.9873563 0.002443075 0.1584987 0.8145805 -0.05555897 -0.5773836 0.5782521 0.01168781 -0.8157744 -0.478576 -0.03407186 0.8773848 0.09652549 0.9819828 -0.1624582 -0.001334071 0.9999987 -9.66484e-4 -0.8251886 -0.4526922 -0.3378366 1.3813e-4 -0.9998506 -0.01728957 0.9421171 -0.3185741 0.1045267 -5.52779e-4 0.9998415 0.01780039 -4.09756e-4 0.9998302 0.01842826 0.4814375 0.8434414 0.2383794 0.5144834 0.8295058 0.2173179 0.9296343 0.3648731 -0.05145573 0.3543262 0.9261426 -0.1292787 0.9972341 -0.003537654 0.0742405 0.8480587 0.01553809 -0.5296745 0.7829607 -0.04146921 -0.6206874 0.9999824 0.002649962 -0.005308926 0.2038855 0.03803998 0.9782555 0.2365223 0.003978312 0.9716179 0.7078776 -0.619453 0.3393927 0.8955535 -0.4121798 0.1676061 0.8426332 0.0181061 0.5381836 0.1547375 0.9865051 0.05351638 -0.371857 0.9215803 0.11141 -0.1971053 0.980248 -0.01623535 0.2503722 0.9681176 -0.007882654 0.03195422 0.9933097 0.1109724 -0.5320993 -0.8376378 -0.1234238 -0.04253178 0.151 0.9876185 -0.09632337 -0.2414655 0.9656171 -0.04045182 0 0.9991815 -0.001249074 -0.998658 -0.0517773 0.001614511 -0.9987542 -0.04987591 6.00987e-4 -0.9987633 -0.04971671 0.02819663 -0.9995908 0.004811882 0.02114647 0.9972344 -0.07125037 0.00194019 0.9965414 -0.08307605 0.009022116 0.9993486 -0.03494507 0.005205214 0.9976465 0.06837016 -0.003457486 0.995728 0.09227132 0.9700371 4.30456e-4 0.2429566 0.9487951 -0.0278756 0.31466 -0.8965127 0.004222512 0.4429982 -0.2429845 -0.05161339 0.9686561 0.2953816 0.0526055 0.95393 0.9999182 0.01264071 -0.001977741 0.664376 -0.1224294 0.737303 0.6338705 -0.2143394 0.7431466 -0.6143628 -0.4699612 -0.633794 0.5461934 0.07731986 -0.834083 -0.1494713 -0.5801293 -0.8006924 -0.574704 -0.3125067 -0.7563431 -0.7282878 -0.01324903 -0.6851433 0.09382718 0.3930036 0.9147376 0.1873068 0.7834751 0.5925226 -0.06575918 0.9068402 0.4163134 0.4460823 0.8017505 0.3977521 0.4550517 0.7794276 0.4306051 -0.6774778 0.07099109 0.7321094 -0.2716625 0.4949995 0.8253334 0.171627 -0.03200662 0.984642 0.6929901 0.177146 0.6988448 0.3144507 0.9298993 0.1908094 0.3144477 0.9299003 0.1908093 -0.905028 -2.79386e-4 0.425352 -0.9049654 -2.3494e-4 0.4254853 0.2856371 0.05126589 0.9569657 -0.02078378 -0.008354425 0.9997492 0.9409757 -0.07660132 -0.3296923 0.302383 0.03457075 -0.9525595 -0.9038615 0.04768615 -0.4251593 -0.9600816 0.007863759 -0.2796099 0.9689513 -0.01569813 -0.246753 0.9903803 0.02433878 -0.136215 0.09630131 -0.9842823 0.1480353 -0.08004158 -0.980449 0.1797592 -0.08499407 -0.9831723 0.1617041 0.6961684 0.04193663 -0.7166526 0.02719056 -0.8611396 0.507641 -0.8348603 0.4285687 -0.3454524 -0.4403269 0.6311935 0.6385193 0.1172668 0.0059641 -0.9930825 1 1.22553e-6 3.12079e-6 -0.6408458 0.5977048 -0.4817318 1 0 -1.07065e-6 1 0 -1.80797e-7 -0.4596124 -0.7343113 -0.4995433 0.003718793 0.9999932 2.92766e-4 3.31262e-4 0 1 -1 -2.82241e-5 -2.00503e-5 -0.9776954 -0.08030796 0.1940681 -1 0 2.09595e-5 -1 -1.74943e-6 0 0.5695669 0.1844335 0.8009856 0.9987677 -0.0369715 0.03311127 0.7135996 -0.06591987 -0.6974454 -0.1715771 0.9532222 0.2488548 0.08468127 0.9744762 -0.207907 0.9777941 -0.1588572 -0.1366872 0.08692455 -0.9950418 0.04833209 0.1118847 -0.4666008 -0.8773629 -0.2860288 -0.5536695 -0.7820726 0.04938435 -0.3487315 -0.9359207 0.3825084 0.2888255 0.8776486 -0.9525523 -0.01011186 -0.3042073 0.3304134 0.9029653 -0.2747379 0.3024168 0.6054724 0.7361707 -0.403014 0.9097148 0.09999418 -0.2003502 0.1179437 0.9725992 -0.1171394 0.1883652 0.9750882 0.2016749 -0.1153987 0.9726306 -0.1081554 -0.5488916 0.828867 -0.3110429 -0.8533767 0.4183307 0.2137576 -0.9478529 0.2363955 0.3208791 -0.9377711 -0.1327478 -0.2026361 0.668893 0.7152068 0.1041028 0.8752266 -0.4723782 0.3630255 0.8397008 0.4038754 0.3110756 0.8152644 -0.4884423 0.7400263 -0.3045397 0.5996804 0.9352855 -0.04114705 -0.3514941 0.6590098 -0.0781688 0.7480614 0.8064488 0.1362186 0.5753998 0.9628147 0.1453649 0.227721 0.9802579 0.09525525 -0.1732656 0.9385786 -0.2929218 -0.1823929 0.4687858 -0.7286831 0.4992604 0.9974663 -0.07060837 -0.0086838 0.9996435 0.0263592 0.004274725 0.9999766 6.43751e-4 0.006819665 0.9960942 0.08702695 -0.01492613 0.9958269 0.00703299 0.09099227 0.9861862 0.1560276 -0.05560737 0.9910666 -0.09552973 0.09306544 0.06991094 -0.7205842 0.689834 0.03672671 -0.0860961 -0.9956098 -0.2223269 0.2052795 -0.9531166 0.1745413 -0.4354824 -0.8831141 -0.08349531 -0.8850506 0.4579454 0.1101984 -0.9530595 -0.2820177 0.1158241 -0.9584749 0.2605968 0.9239457 -0.07886976 -0.3743047 0.01690131 0.9998193 0.008713066 0.2551334 -0.04565936 0.9658273 0.183011 -0.01322358 -0.983022 0.3536798 0.5208208 -0.7769533 0.3884364 -0.5333462 -0.7514381 0.2776094 -0.7852232 0.553496 0.2708115 -0.1096304 0.9563694 0.144877 0.112684 -0.9830122 0.007640004 -0.1964967 -0.9804748 -0.02430361 0.8760496 0.4816082 0.252 -0.005417644 0.9677121 0.2872613 0.2023652 -0.9362314 0.04323965 -0.7748488 0.6306661 0.08572518 0.6111516 0.7868577 0.1091926 0.8367353 -0.5366109 -0.7588703 0.6505841 -0.02926188 -0.5453718 0.2000617 -0.8139687 -0.3528917 -0.3912495 -0.8499361 -0.5479555 0.04481518 -0.8353062 -0.9072666 -0.04621148 0.4180094 -0.9813337 0.03407686 -0.1892696 -0.7682024 -0.3447802 -0.5394365 -0.7146388 0.3334815 -0.6148833 -0.826252 -0.2197992 -0.5186483 -0.9548189 -0.155251 0.2534132 -0.9579814 0.2038114 -0.2018234 -0.3863599 -0.02474117 0.9220163 0.1593918 -0.2913179 0.9432541 -0.5801934 -0.645013 -0.4973267 -0.07083451 0.622488 0.7794172 -0.1720178 0.9568663 0.23413 0.1837487 -0.9165086 0.3553147 -0.670551 -0.680357 0.295763 -0.4919714 -0.8703782 0.02014863 0.6274622 -0.3011212 0.7180649 0.9724313 0.03974229 0.2297787 0.5711494 0.7871677 0.2327134 -0.371964 -0.5565916 0.7428652 -0.5921699 -0.1979132 0.7811308 -0.5188228 0.3843537 0.7636068 0.4370676 0.5138751 0.7381764 0.8184251 -0.5313283 0.2187936 -0.1101551 -0.9758587 -0.1885887 0.935026 -0.3280574 0.1345536 -0.2575165 0.9381171 0.2315634 0.005843818 -0.0113244 -0.9999188 0.003115177 -0.06217795 -0.9980603 0.2285702 -0.8839257 -0.4079596 -0.1404321 -0.07019072 -0.9875992 -0.2082594 0.03363919 -0.977495 0.001737892 -0.04597371 -0.9989411 -0.2743813 -0.9562585 -0.1014142 -0.18979 -0.9818021 -0.006657302 -0.3127484 -0.9498341 -0.001901805 -0.3124715 -0.9498625 0.01108068 0.3291107 0.8954586 -0.2997334 0.2633489 0.9315302 -0.2507968 -0.5330182 -0.8145801 0.2288031 -0.2606086 -0.9255242 0.274751 -0.3536487 -0.8745574 0.3317863 -0.5520743 0.6609597 0.5082778 0.04054629 0.8717212 0.4883218 -0.03217983 0.9788795 -0.2018897 0.4979293 0.8559265 -0.1394854 0.3119219 0.950107 -0.001247644 0.3081402 0.9513409 0 0.3121036 0.9500371 -0.004575371 -0.365399 -0.9047285 -0.2189751 -0.6046127 0.7965114 0.003659665 -0.7058103 0.3499754 0.6159133 -0.1439326 0.9895483 0.008806705 -0.0349006 -0.9692614 -0.2435454 -0.4944335 -0.8549453 -0.1568576 -0.04059022 0.99689 -0.06754904 0.6692833 0.7393155 0.07397705 -0.9875671 -0.1530264 -0.03597527 -0.9432989 0.3316512 -0.01395225 -0.7897526 0.6119188 -0.04296964 -0.3480958 0.937183 -0.0227468 -0.7933952 0.6073755 -0.04023981 0.1484146 -0.8569537 0.493562 -0.04160672 0.06249505 0.9971777 0.02787423 9.5947e-4 0.999611 -0.5988467 -0.6612185 0.4518548 -0.2568095 -0.5292501 -0.8086676 -0.4876613 0.1264922 -0.8638207 -0.1068376 0.09399151 -0.9898239 -0.05051696 -0.04833239 -0.9975531 0.02885621 -0.07717555 -0.9965999 0.01611852 -0.07211726 -0.9972659 0.1388628 0.01326942 -0.9902228 0.02140909 -0.1145599 -0.9931857 0.03145366 0.9995013 0.002824306 -0.8775332 0.4795151 8.2428e-4 -0.9792276 -0.2027649 6.30354e-5 -0.99797 -0.05871808 -0.02466332 -0.9887439 0.148732 0.01625859 -0.8925921 0.4505035 0.01805859 -0.8352512 -0.5498685 3.81233e-4 -0.8327165 -0.5536996 0 -0.08936977 -0.9959986 0 0.756807 -0.6535489 0.01082503 0.9922877 -0.1239285 0.002617955 0.9989836 0.03934741 -0.02198958 0.9947356 -0.1013928 0.01485323 0.8894532 -0.4567354 0.01630699 -0.09085398 -0.9958643 1.26897e-4 0.590733 0.806295 -0.03037965 0.512083 0.8589357 6.8308e-4 -0.8744321 0.4851453 0.001647353 0.02515083 0.006188869 -0.9996646 0.009209632 -0.02479726 -0.9996501 0.07376509 0.03672367 -0.9965993 0.04320901 0.06191122 -0.9971459 0.1655959 0.2412324 -0.9562348 0.2572505 -0.1091696 -0.9601585 0.008247315 0.02178925 -0.9997286 0.005348086 0.002671539 -0.9999821 0.4439827 -0.8960138 -0.006218492 0.5551872 -0.8298044 0.0564965 0.9949678 0.09719133 0.02435284 0.998827 0.02210998 -0.0430811 0.989497 0.144554 0 0.8914397 0.4531395 0 0.8181214 -0.5682031 -0.08844649 0.941766 -0.3361879 -0.007382452 0.9780802 0.1944627 -0.0744549 0.9732445 0.2257162 0.04298186 0.9999911 0.00175774 -0.003834247 0.6271337 0.7789116 0 0.1933271 0.9811344 0 -0.7766761 0.6294557 0.02365738 -0.996022 -0.08224731 -0.03428739 -0.9382246 -0.3460271 0 -0.9979757 -0.05930376 0.02297443 -0.9520537 -0.2963555 0.07594352 -0.7860378 -0.6181784 0 -0.4224922 -0.9063394 0.007015049 0.8423197 -0.5389745 0.002026021 0.8459247 -0.5314419 0.04450953 -0.3841859 -0.923254 0.001869022 0.8354236 -0.547129 -0.05213028 0.002020835 0.01026266 0.9999454 -0.01104325 0.0652517 0.9978078 -0.7944654 0.3981584 -0.458579 -0.3060165 0.3968117 0.865387 0.1489148 0.9883189 0.03240817 0.9172127 0.389611 -0.08321195 -0.903411 -0.4167143 -0.1009839 0.4208999 -0.9010738 -0.1044476 -0.05625933 0.1500442 -0.9870773 -0.3851413 0.922848 0.004223227 0.261222 -0.9644272 -0.04053866 0.7707518 0.6371234 -0.003946244 0.9494431 -0.3113994 0.03985375 -0.4366402 0.8994678 0.01740682 -0.7815562 0.6056876 -0.1493741 -0.9981818 -0.005993843 -0.05997782 -0.7597966 -0.650121 -0.00719583 0.6167575 -0.7822432 0.08778423 0.8982455 0.4159442 0.1419349 -0.1325756 0.0035097 -0.9911667 -0.2036057 -0.2528817 -0.9458307 0.1063634 -0.05686902 -0.9926998 -0.0944522 0.1673284 -0.9813665 2.81864e-6 0 -1 0.151074 0.3240958 -0.9338837 0.187649 0.143028 -0.9717669 0.01399415 3.55841e-4 -0.9999021 -0.06046158 -0.3068478 -0.9498363 4.04231e-7 0 1 0.3101713 0.9506807 0 0.3101817 0.9506773 2.20493e-6 0.3101724 0.9506803 -1.83739e-6 -0.3101775 -0.9506788 0 -0.3101754 -0.9506794 -1.31243e-7 -0.3101763 -0.9506791 3.1833e-6 -0.3101715 -0.9506807 0 -0.310177 -0.9506788 -1.45342e-6 -7.69961e-7 0 1 0.3140373 -0.08205711 0.945858 -0.306609 -0.9280154 0.2116095 0.3418397 -0.9142062 0.2176528 0.547517 -0.8288629 0.1149413 0.9070185 0.3681402 0.204427 0.2083003 0.9633315 0.1691254 -0.9979955 0.04872077 -0.04038971 -0.09082406 -0.9955304 0.02588999 0.6338766 -0.3978061 -0.6632878 0.485625 0.8443531 0.2263545 0.01029628 0.03155314 0.9994491 0.001265347 8.30994e-4 0.9999989 0.001820743 -5.93891e-4 0.9999982 -8.88415e-7 0 1 0.6723225 0.7364828 0.07466942 0.7420414 0.6687631 0.04615843 0.9721929 0.2333658 0.0195294 0.09639865 -0.9948396 -0.03164803 -0.6700412 -0.7385902 0.07436025 -0.6222828 -0.7825116 -0.0209735 -0.965726 -0.2589416 0.01796448 -0.7503238 0.6594405 0.04639512 -0.8309283 0.5464423 0.1046851 -0.03899359 -0.9981771 0.0460658 -0.7420834 -0.668868 0.04390662 0.03905302 0.9981359 0.04690104 -0.07919454 -0.203661 0.9758332 0.04073941 -0.2642466 0.9635944 0.3032334 -0.07259982 0.9501467 0.1503251 -0.01161581 0.9885685 -0.03670108 -0.05443167 0.9978428 0.01288217 -0.09272193 0.9956088 0.1800619 0.04908674 0.9824298 0.01007151 0.09104257 0.9957961 0.004105985 0.01142591 -0.9999263 0.003693163 -0.004608035 -0.9999826 0.005860865 -0.001913011 -0.9999811 3.19132e-7 0 -1 -3.63983e-4 0.006017565 -0.9999818 -0.008680701 0.006707251 -0.9999399 6.26148e-4 0.01409113 -0.9999006 4.15785e-4 -0.00685352 -0.9999765 0.009093344 -0.007572591 -0.9999301 -0.002375006 -0.02044266 -0.9997882 -0.008006334 0.002612292 -0.9999646 -0.819281 0.572817 0.02568215 0.8939073 0.4476796 0.02264666 0.3907568 -0.8044005 0.4474922 -0.7106145 0.7035135 -0.009798347 -0.3931692 0.7174361 -0.5750681 -0.4117144 0.7131435 -0.5673778 -0.5363832 0.6293783 -0.5622953 0.6229595 -0.5787181 0.5263143 -0.443247 0.7522343 -0.4875198 -0.214303 0.7879244 -0.5772777 -0.2834641 0.7757844 -0.5637435 -0.6647402 -0.7468235 -0.01937025 -0.9006726 0.4075886 0.1505343 0.5548056 -0.8199629 0.1408963 0.4120005 -0.9102564 -0.04109674 -2.6014e-4 0.004971504 0.9999877 -0.004274368 -0.001434326 0.9999899 8.58948e-4 -0.002747952 0.9999958 6.7191e-4 0.002975106 0.9999954 0.03650987 0.04846775 0.9981573 -0.4311921 -0.248466 0.8673742 0.06972736 0.0179277 0.997405 -0.6229126 -0.3596379 -0.6947233 -0.8466745 -0.4947062 -0.1959798 0.353398 0.2075928 -0.9121487 -0.8362745 -0.5067588 0.2093817 -0.7349157 -0.4115219 -0.5390257 -0.5414421 -0.3141382 -0.7798446 -0.6678563 -0.3835116 -0.6378769 0.8650256 -0.1114256 -0.4891986 -0.8524731 -0.5055488 0.1330791 -0.7785494 0.3429002 -0.5256238 -0.8619567 -0.4976485 -0.0968334 0.4090614 0.2314925 -0.8826552 0.6881619 0.3991203 -0.6059177 0.3167923 0.1829239 0.9306888 0.6154625 0.3243882 0.7183162 0.6957581 0.3792477 0.6099934 0.807276 0.4755035 -0.3495739 0.313138 0.1679746 0.9347349 -0.81526 -0.4147503 0.4041454 -0.08915883 -0.8222709 -0.562069 0.461439 0.2741308 -0.8437573 -0.6554123 0.1925424 -0.7303165 0.005511164 -0.9912164 -0.132135 0.434491 -0.6846411 -0.5852214 0.2983055 -0.7951928 -0.5279036 0.8430513 -0.5013548 -0.1946998 -0.7823384 0.4719933 -0.40641 -0.8407114 0.3776336 -0.3880687 -0.8241955 0.4107382 -0.3898666 -0.8630496 -0.5002762 -0.06978118 -0.8607413 -0.5081245 -0.03056126 -0.9054856 -0.4039793 -0.1299867 -0.8802647 -0.4725849 -0.04239881 -0.8694729 -0.4930118 -0.03092628 -0.8655573 -0.4999978 -0.02851408 -0.860781 -0.5085549 -0.0206893 -0.8719269 -0.4882333 -0.037041 -0.878939 -0.4749954 -0.042961 -0.8458734 -0.5321566 0.03616285 -0.8805828 -0.4536903 -0.1368905 -0.8807054 -0.4716052 -0.04411929 -0.1054639 -0.9852989 0.1344009 0.5540115 -0.8119899 0.1836951 0.4264596 -0.8855797 0.1840674 0.4123549 -0.8913261 0.1884183 0.6133799 -0.7875469 -0.05945587 0.2600982 -0.6348506 -0.7275395 0.4763005 -0.8604189 0.1811552 0.3567293 -0.9157805 0.1846361 0.6059919 -0.7735642 0.1853983 0.2938514 -0.9404739 0.1707638 -0.003329694 -0.01212048 -0.999921 -0.02473795 -0.01171839 -0.9996253 -0.4216922 -0.842795 -0.3344732 -0.5928222 -0.1788677 -0.7852187 0.698285 0.4642603 0.544849 0.963672 0.2590992 -0.06483894 0.5194482 0.849723 -0.09024614 0.4921238 0.451025 -0.7445741 0.9556184 -0.1416992 0.2582921 -0.3020921 0.5353733 0.7887432 -0.4377264 0.6771763 0.5914625 -0.6099776 -0.7764979 0.1580457 -0.7712473 -0.4346736 0.4650126 0.8605621 0.5091541 -0.01396447 0.8465053 0.5304892 -0.04483377 0.8654899 0.5000997 -0.02877074 0.8655139 0.5000698 -0.02856642 0.8674526 0.4972381 -0.01674211 0.8655966 0.4999167 -0.02873563 0.8216519 0.5515532 -0.1437964 0.8651366 0.5004088 -0.0336101 0.8655986 0.4998033 -0.03059142 0.8667181 0.4980416 -0.02746587 -0.08322972 0.1500589 -0.9851676 -0.5119203 0.8367316 -0.1944686 0.4671745 -0.7553525 0.459555 -0.003912687 0.01224869 0.9999173 0.01468944 0.009980082 0.9998424 0.6349462 0.7026157 0.3212078 0.5192682 0.8462182 -0.1194792 -0.9947038 0.03510326 -0.09660261 -0.3132998 0.6089977 0.7286736 -0.6830162 -0.249055 -0.6866299 0.9709203 -0.005909204 0.2393301 -0.7148112 -0.6934642 0.09029161 -0.4515636 -0.8710213 0.1934224 0.7854815 0.3347464 0.5205419 0.1123182 -0.2337924 -0.9657773 0.3709769 -0.5546041 -0.7448427 -0.4930307 0.8482651 -0.1933056 0.08144265 -0.1408002 0.9866826 -0.08506226 0.1474535 -0.9854044 0.4364116 -0.7853879 0.4389886 0.4370307 -0.7847113 0.4395822 -0.6821635 -0.2704331 -0.6793519 0.2250221 -0.4204044 0.8789911 -0.7082206 -0.6448466 0.287396 -0.967343 -0.2019978 -0.1531158 -0.6807519 -0.3894791 -0.6203894 -0.9670658 0.1940505 -0.1647068 -0.9838814 -0.1518794 -0.09439361 -0.7406188 -0.4927828 -0.456781 0.9201483 -0.05963301 -0.3870027 0.3082479 0.170656 -0.9358738 -0.3663967 0.7457623 0.5564101 0.8305203 0.5078834 0.228671 0.6210402 0.7775361 -0.09872478 0.9783762 0.1378878 0.1541661 0.9561805 -0.07878166 0.2819795 0.8150507 0.3861828 0.4319204 -0.3375754 0.6050255 0.7211012 0.4571785 -0.76774 0.4489582 0.07360589 -0.1550693 0.9851578 0.08272278 -0.1428887 0.9862757 -0.002124905 0.003561735 -0.9999914 0.8700663 -0.4692559 0.1509431 0.8526749 -0.4993308 0.15367 0.9059704 -0.4014317 0.1344265 6.21222e-4 0.91616 -0.4008126 -4.92736e-5 -2.61072e-5 1 -4.71454e-7 2.26222e-7 1 -0.7143945 0.5484824 -0.43452 -0.4201732 0.7910271 -0.4446693 -0.4216287 0.7901759 -0.4448051 -0.3064898 0.8436498 -0.4408164 -0.5272549 0.7485352 -0.4021161 -0.1675295 0.8563464 -0.4884718 -0.5180645 0.7303104 -0.4452593 -0.5828629 0.683111 -0.4400344 -0.4660093 0.7657339 -0.4432685 0.5687487 -0.5839341 -0.5792633 0.5173119 -0.6409273 -0.5670984 0.2976436 -0.7675371 -0.5677104 0.2781544 -0.7811308 -0.5589855 0.2212926 -0.7845475 -0.5792366 0.5118722 -0.5967748 -0.6179375 0.4789517 -0.6609539 -0.577707 0.3694275 0.2092159 -0.9054017 0.864221 0.4989582 0.06451791 4.68681e-7 0 1 2.79745e-7 0 1 1.37499e-6 0 1 -1.93728e-7 0 1 -7.20316e-7 0 1 -7.24697e-7 0 1 -0.8642222 -0.4989581 0.06450408 -0.4368441 -0.2522122 -0.8634561 -0.2207432 -0.1304218 -0.9665727 0.7492935 -0.6599814 -0.05462604 -0.08633047 -0.9959344 0.0257284 -0.9649583 -0.2623491 -0.005340158 0.6393515 0.5137174 0.5721226 0.5544916 0.7612056 0.336311 -0.2541348 -0.9671192 -0.009802997 -0.5044304 -0.6473866 -0.5713498 -0.4247564 -0.6992058 -0.5750594 0.1899471 0.8287719 0.5263624 -0.2760165 -0.7822373 -0.5584979 -0.2736859 -0.7823563 -0.5594772 -0.5752289 -0.5795468 -0.5772672 0.7616366 0.6137586 0.2078705 0.9992262 -0.0213834 -0.03301334 -0.9547727 -0.2966223 -0.02060282 0.6533094 -0.7535324 -0.07331949 -0.9709452 -0.2344346 0.04801797 -0.7669323 0.6380911 -0.06822466 0.2687687 0.952836 -0.14095 -0.001270294 0.01285254 0.9999166 0.001990795 0.00214827 0.9999957 0.2121354 0.785596 0.581238 -0.002935051 -9.10241e-4 0.9999954 0.5872533 -0.3707391 0.7195042 -0.06020903 0.007371783 0.9981586 -0.0502482 0.05131471 0.9974177 0.622848 -0.3595992 -0.6948012 0.851734 -0.4858752 -0.1961497 0.6286343 -0.3056042 0.7151399 -0.3701664 0.2099326 -0.9049338 0.54281 -0.311846 -0.7798138 0.7754182 -0.4255962 0.4664704 0.7252949 -0.4233947 0.5428482 -0.3361933 0.8048372 -0.4890924 -0.4050266 0.2385267 -0.882643 -0.6897406 0.3964104 -0.6059016 -0.6145985 0.3246529 0.7189362 -0.3408285 0.1990204 0.9188182 -0.6762248 0.412863 0.6101345 -0.5641652 0.3257139 -0.7587017 -0.4661666 0.2974967 0.8331773 0.3207607 -0.1693136 0.9319043 -0.7260411 0.4132313 0.5496401 -0.8565324 0.4967879 0.1398358 0.7564943 0.3341865 -0.5621706 -0.468177 0.2625834 -0.8437182 0.3756935 0.718616 -0.5851885 0.5394976 0.6558803 -0.5279806 0.5623177 0.663488 -0.4935409 0.01270663 0.9807881 -0.1946618 -0.01752734 -0.9135246 -0.4064059 0.09323501 -0.9168842 -0.3881117 0.1579937 -0.915126 -0.3709211 0.8647689 -0.4972958 -0.06979852 0.870423 -0.4913588 -0.03050613 0.8026057 -0.5821848 -0.1299428 0.8493664 -0.5260964 -0.04241859 0.8652334 -0.500539 -0.02884435 0.865825 -0.4995344 -0.02850282 0.8642578 -0.5022369 -0.02857738 0.8361251 -0.5470937 -0.03979337 0.8487561 -0.5269395 -0.04413485 0.9223862 0.3637573 0.12994 0.8700636 0.4692614 0.1509408 0.4261808 0.8857899 0.1837014 0.3753605 0.9249536 -0.0597102 0.5070168 0.8426853 0.181151 -0.02728283 0.6014689 -0.7984302 0.4845021 0.8543151 0.1881584 0.01215988 0.00317347 -0.999921 -0.0349636 0.02089399 -0.9991701 -0.03016906 0.009998142 -0.9994949 -0.6747121 0.2189577 0.7048555 0.7896735 -0.5742976 -0.215866 0.4668048 -0.8832134 -0.04502654 -0.706224 0.7050218 -0.06474548 -0.9956045 0.02498465 -0.09026408 -0.6353912 0.1997187 -0.7459159 -0.7981216 0.3848717 -0.4635468 0.3175281 0.593936 -0.7391996 -0.3548186 0.8985345 0.2583401 -0.2886313 0.9171345 0.2748749 -0.6323665 0.3435008 0.6943485 -0.6886063 0.3894402 0.6116843 -0.3126375 -0.529356 0.7886952 0.9774559 -0.1399881 0.1580609 0.761994 -0.4505554 0.4651508 -0.8712216 0.4906919 -0.0139448 -0.8813783 0.470359 -0.04398596 -0.8775072 0.4777631 -0.0415135 -0.8658334 0.4995051 -0.02876317 -0.8658198 0.4995399 -0.02856981 -0.8656691 0.4998014 -0.02855712 -0.8662648 0.4987477 -0.02891284 -0.8650025 0.501412 -0.01888537 -0.8884633 0.4358318 -0.1438183 -0.8646855 0.5015518 -0.02765607 -0.8646539 0.5016191 -0.02742546 0.4668071 0.7744806 0.426932 -0.01598674 0.007733643 0.9998424 -0.7517104 0.626183 0.2069454 -0.9924822 0.02664935 -0.1194531 0.9630919 0.2150287 -0.1619151 -0.8449656 0.4744303 -0.2468785 -0.7075097 0.2726951 -0.6519719 0.5573773 -0.822112 -0.1160275 -0.4570711 -0.7215887 0.5199961 0.8205214 0.2665633 -0.5056568 0.8194988 -0.4953269 -0.288224 -0.5638754 0.8050824 0.1840838 -0.4802989 0.8438125 0.2393609 0.9579512 -0.2723609 0.09027278 0.758094 -0.3765876 0.5324241 -0.6826502 0.5128776 0.520524 0.1463084 0.214154 -0.9657805 -0.4881696 -0.8510687 -0.1933203 0.08121353 0.1409326 0.9866825 0.4610671 0.7708376 0.4395754 0.2515152 0.4049726 0.8790549 0.9125615 -0.2908994 0.2874177 0.6585431 -0.7368184 -0.1530347 0.7632007 -0.4579991 -0.4558088 0.6777002 -0.3948209 -0.6203538 0.7681944 -0.6099094 0.1946483 -0.02432686 -0.9836227 -0.1785905 0.2884746 -0.9428805 -0.1666098 0.8092198 0.4371244 0.3925373 0.8045353 -0.365931 0.4677794 -0.4084275 0.8267037 -0.3869728 -0.7490403 0.4275267 -0.5061222 0.2759624 0.4912291 0.8261591 -0.9896873 -0.02035474 -0.1417914 -0.6243776 0.7635139 0.1649219 -0.4098416 0.8674793 0.2819741 -0.7420168 0.5127647 0.4318374 -0.3090173 -0.5189084 -0.797021 0.4622453 0.7762387 0.4286989 0.097494 0.1412788 0.9851575 -0.002022147 -0.00362122 -0.9999914 -0.4993273 -0.8445743 -0.1933041 -0.4900533 -0.8484265 -0.2000512 -0.1461575 0.9806896 0.1299459 0.006162881 0.9881023 0.1536753 -0.1051552 0.9853264 0.1344417 -0.8718345 -0.3198899 -0.3709114 4.92717e-5 -3.19783e-5 1 -1.11958e-6 -5.08257e-7 1 -0.1175636 -0.8929588 -0.4345151 -0.5607413 -0.697353 -0.4463945 -0.5773732 -0.6872577 -0.440814 -0.6578325 -0.5733064 -0.4884428 -0.3001558 -0.8463352 -0.4400265 -0.392987 -0.8048192 -0.4447778 0.4663891 0.6670371 -0.5809843 0.5373908 0.6314684 -0.5589802 0.5688281 0.5838751 -0.5792447 0.3329837 0.7452363 -0.5777064 -0.4103884 0.2369374 -0.8805919 -0.3658983 0.2153235 -0.9054029 -0.03021329 5.69292e-5 0.9995436 5.98464e-7 0 1 8.32423e-7 0 1 7.20341e-7 0 1 -1.95135e-7 0 1 0.005002379 0.01429957 0.9998853 0.370268 -0.2076017 -0.9054298 0.2233195 -0.1259536 -0.9665734 0.9046845 0.4260487 -0.005360424 0.9175626 -0.3969435 0.02269297 0.08234614 0.9965558 -0.009795427 0.9024505 0.4307426 -0.006633818 0.296863 0.7623474 -0.5750644 0.2816605 0.7737901 -0.5673767 0.1373479 0.8154547 -0.5622893 0.1359609 0.8182916 -0.5584924 0.2913994 0.8230515 -0.4875169 0.4237781 0.7132659 -0.5582687 0.4325895 0.7039791 -0.563276 0.4722382 0.6669397 -0.5763528 0.4011192 0.7195927 -0.5668243 -0.9978442 -0.03880327 0.05292767 0.8887311 0.4579653 -0.02061831 0.7796705 -0.6257949 -0.02224224 -0.2715271 -0.9520572 0.1409266 -0.4325364 -0.900678 -0.04112821 -0.7742176 0.6286592 -0.07331383 0.03664219 0.9947267 -0.09579271 0.9154685 0.3995156 0.0480082 -0.003853559 0.002361595 0.9999899 0.002724647 0.001403689 0.9999954 0.6297087 -0.1642262 0.759274 -0.1483759 0.05765271 0.9872491 -0.6757199 0.2454537 -0.6950935 -0.9206844 0.329714 -0.2088759 -0.3813223 0.1484639 0.9124429 -0.6435651 0.1812214 0.7436282 -0.9231298 0.3134005 0.222737 -0.7876338 0.298458 -0.5390325 -0.2299983 0.8187302 -0.5261004 0.03556168 -0.01324999 -0.9992797 0.6441502 -0.2629608 0.7182772 0.6120807 -0.2227765 -0.7587673 0.9297744 -0.3404966 0.1399348 0.4048937 0.7109722 -0.5749605 -0.2737928 0.6258117 -0.7303406 -0.4175029 -0.7396681 -0.5278092 -0.4385335 -0.7510625 -0.4935521 -0.1776996 -0.9041813 -0.3884317 0.1577963 -0.9680897 -0.1946859 0.07284885 -0.9888694 -0.1297321 -0.3190733 0.8725411 -0.3699519 -0.9389422 0.3428703 -0.02876895 -0.9383682 0.3444333 -0.02882623 -0.9358898 0.3505321 -0.03517836 -0.9273526 0.371577 -0.04413503 -0.9513693 0.3059241 0.03615373 -0.9390774 0.3409219 -0.04365813 -0.9390937 0.3417865 -0.03584921 -0.9305865 0.3637068 -0.04154717 -0.7529153 -0.6399235 0.1536769 -0.822294 -0.5529432 0.1344866 -0.8450031 -0.5187163 0.1300129 -0.4177709 -0.8888009 0.1884163 -0.3191046 -0.6071866 -0.7276653 -0.2024997 -0.9615861 0.1853267 -0.3529823 -0.9179251 0.1811547 0.1319402 -0.5879197 -0.7980867 -0.472185 -0.8619471 0.1846309 -0.2030359 -0.9614594 0.1853975 -0.5315026 -0.8296646 0.1707678 -0.3288074 -0.9254636 0.1881562 0.03805971 -0.01450544 -0.9991702 -0.0248745 0.01141935 -0.9996255 0.03141939 -0.004603266 -0.9994957 -0.8094847 0.2977998 0.5060138 -0.1341235 0.9720259 -0.192812 0.9886911 0.1178937 -0.0926876 0.652991 -0.07675623 -0.7534662 0.9025281 -0.2927701 -0.3157987 0.5054398 -0.8232741 0.2583611 0.2244076 0.5985021 0.7690491 0.2374697 0.7705044 0.5915498 -0.5250158 0.2283188 0.8198957 0.9431932 -0.3319518 -0.01395183 0.9336282 -0.3567597 -0.03257423 0.9436412 -0.3288608 -0.03731012 0.9383125 -0.3447643 -0.02659386 0.8600869 -0.4976029 -0.1124365 0.9406146 -0.3386467 -0.02371925 0.9392401 -0.3419043 -0.030487 0.06158047 0.1601672 -0.9851672 0.05784708 0.1593472 -0.9855264 0.3165625 0.9293602 -0.189942 -0.2777617 -0.8433828 0.4599501 0.00686711 0.01087212 0.9999173 0.01746296 -0.005413413 0.9998329 0.9897752 0.0919162 -0.1090709 0.0038836 -0.8005543 -0.5992478 0.6778113 -0.3106535 -0.6663831 -0.6306492 0.7706378 -0.09164631 0.4561767 0.758093 -0.466045 0.2665981 0.6305607 0.7289162 -0.1781504 -0.7399421 0.648651 0.7290692 -0.6655253 0.1597945 -0.9903067 0.1070939 0.08845084 -0.8179041 0.230597 0.5271224 -0.6398553 0.08934789 0.7632838 -0.2111236 -0.4655793 0.8594549 0.8849344 -0.3743122 0.2770951 0.8257977 -0.3995396 0.398028 -0.3740634 -0.9116657 -0.170124 0.05817836 0.1599789 -0.9854046 -0.3208048 -0.8392531 0.43902 -0.645611 0.348626 -0.6794456 -0.1773576 -0.4424635 0.8790736 -0.2960368 -0.5728992 -0.7642963 -0.7359422 0.2711347 -0.620383 -0.8741046 0.4497327 0.183526 -0.8266672 0.1409296 0.544757 -0.7495084 0.655017 -0.09586405 -0.8521168 0.2208834 0.4744548 -0.8505323 0.2520285 -0.4616021 0.8253795 -0.290418 -0.4841549 0.8730917 -0.09733515 0.4777414 0.5643382 0.7974155 -0.2136608 0.9825108 0.1501697 -0.1100986 0.7024045 -0.6968907 0.1448146 0.5542607 -0.7831245 0.2819773 0.7283652 -0.3637163 0.5806846 0.0547195 0.2541816 0.9656074 0.3148924 0.9336711 0.1705904 0.1584627 0.4329367 -0.887387 0.3341062 0.9209024 -0.2007782 -0.3204298 -0.8447102 0.4287066 -0.07151687 -0.1560627 0.9851548 0.1996771 -0.9681655 0.1509463 0.1655126 -0.9741604 0.1536784 0.8029951 0.4664929 -0.3709223 0.4311479 0.7841187 -0.4463963 0.4709921 0.7639589 -0.4410592 0.2343387 0.8851103 -0.4020761 0.226438 0.8662998 -0.4452531 0.2472581 0.8608384 -0.4447704 -0.1517952 -0.8108423 -0.5652371 -0.3434944 -0.7378842 -0.5809807 -0.4195798 -0.7151867 -0.558982 -0.458781 -0.673807 -0.5792272 -0.1983706 -0.7917751 -0.5777035 0.505271 -0.1839007 -0.8431382 0.9377344 -0.341302 0.06455481 -1.80652e-6 3.82688e-7 1 0 0 1 6.29629e-7 0 1 -9.20085e-7 0 1 -2.75321e-7 0 1 -0.9409218 0.3386139 0.002630293 -0.9377347 0.3413074 0.06452268 -0.4740099 0.1725254 -0.8634521 -0.4006872 0.1401485 -0.9054326 -0.2418018 0.08526349 -0.9665723 0.9876329 0.1552398 0.02195537 -0.4638015 -0.8855464 0.02637928 -0.8523914 -0.5100829 -0.1150844 -0.8308278 -0.5530716 -0.06194281 -0.2529903 0.8276225 0.501036 0.5351088 0.8336465 0.1367194 0.1717091 -0.8025268 -0.5713726 0.2816635 -0.7737964 -0.5673666 0.3058655 -0.8177676 -0.4875473 0.06686079 -0.814467 -0.5763447 0.7525665 0.6512401 -0.09762287 0.9766759 -0.07882696 0.1997268 0.1355578 -0.9785014 -0.1554322 -0.5406775 0.8409881 0.0201711 1.30408e-4 -0.004550755 0.9999896 0.1507197 0.05120718 0.9872494 0.9172404 0.3392421 -0.20877 0.6094747 0.2748473 0.7436395 0.9086338 0.3533032 0.2226242 0.5878007 0.2153624 -0.7798138 -0.8326611 0.259749 -0.4890871 -0.6217463 -0.2298282 -0.7487393 -0.03576636 -0.01271462 -0.9992793 -0.347801 -0.126525 0.9289919 -0.6625398 -0.2126272 0.7182135 -0.5148921 -0.1885737 0.8362573 0.8748392 0.2668527 0.4042848 -0.9311194 -0.3368129 0.139906 0.2307754 0.7942963 -0.5619932 0.6430031 0.2098311 -0.7365583 -0.3089761 0.7496708 -0.5852586 -0.1556622 0.8349123 -0.5279117 -0.4451371 0.8068401 -0.3884097 -0.743179 0.6401403 -0.1946929 -0.6913734 0.7107657 -0.1296725 0.6885523 -0.6006058 -0.4064092 0.7403925 -0.5475709 -0.3898527 0.8052904 -0.4633035 -0.3699423 0.9486699 0.2864941 -0.1339651 0.9383991 0.3446018 -0.02562981 0.9924796 0.101379 -0.06860548 0.9402444 0.3392854 -0.02873897 0.9422651 0.3330135 -0.03519302 0.9400619 0.3397765 -0.02890819 0.9394837 0.3295811 -0.09352463 0.9385125 0.3424806 -0.04360479 0.9386049 0.3401611 -0.05754363 0.9466644 0.31953 -0.04155969 0.1654921 0.9741656 0.1536683 0.2745717 0.9521166 0.134479 0.3138566 0.9405261 0.1300184 -0.2512906 0.9493946 0.1884223 -0.1458783 0.6703388 -0.7275751 -0.1922976 0.9638121 0.1846293 -0.3430241 0.920288 0.188161 0.0053851 0.01135534 -0.999921 0.026398 0.007245302 -0.9996253 -0.02703827 -0.01668024 -0.9994953 0.8115649 0.2922003 0.5059461 0.7274218 -0.6585461 -0.1928071 0.8661801 -0.4791858 -0.14182 -0.659095 -0.7466247 -0.09025216 -0.8078289 -0.3640457 -0.463555 -0.2490783 0.7313634 -0.6348761 -0.8880255 0.368538 0.2749376 -0.740906 -0.2771934 0.611737 0.2127999 -0.6027378 0.7690406 0.7224154 0.6674921 0.1804725 0.5490018 0.1625956 0.8198535 -0.9359019 -0.3519847 -0.01394087 -0.9445805 -0.3266471 -0.03270161 -0.9342604 -0.3546348 -0.03730672 -0.9404339 -0.3389386 -0.02654701 -0.9392121 -0.3418481 -0.0319451 -0.897144 -0.410268 -0.1637468 -0.9392719 -0.3418158 -0.03050148 -0.9403199 -0.3392361 -0.02678376 0.05591005 -0.1622315 -0.9851676 -0.2935185 0.8553282 0.42692 -0.5537168 0.5708364 0.6062538 0.7068907 -0.3841946 -0.5938856 -0.9651165 -0.1378527 0.2225914 -0.4967115 -0.7270651 0.473977 0.4543333 0.8759887 -0.1619418 -0.7189674 -0.1979038 -0.6662732 -0.6637525 -0.3667065 -0.6518888 0.9938638 -0.08316534 -0.07292646 0.516338 0.02868175 -0.8559045 0.4891945 0.01264309 -0.8720832 0.8274431 0.5545358 0.08847767 0.547567 0.342845 0.7633006 -0.5283119 -0.00941348 0.8489982 -0.2994625 0.9388087 -0.1701775 0.1328669 -0.490617 -0.861186 -0.04385423 0.1659342 0.9851613 -0.05585998 0.1529362 0.9866561 0.05818235 -0.159979 -0.9854043 -0.29341 0.8492298 0.4389982 0.8674395 -0.02032351 0.4971274 0.7904428 0.6056702 0.09145462 0.9874029 -0.1102642 -0.1134781 0.6743905 -0.7070655 -0.2127342 -0.3459165 -0.1179007 -0.9308283 -0.7602994 -0.276633 -0.5877237 -0.2864804 0.81844 -0.4980815 -0.7336916 -0.6717664 -0.1021103 -0.9853632 0.04870986 0.1633614 -0.9279776 0.2436102 0.2819783 0.1321375 -0.3279117 0.9354217 -0.2274621 0.4565535 -0.8601279 -0.2974991 0.8530629 0.4286932 -0.04548156 0.1655649 0.9851496 -0.0566402 0.1550949 0.9862746 0.00150299 -0.003846645 -0.9999915 0.3264227 -0.9252389 -0.1933425 -0.7753624 0.6132138 0.150937 -0.7529831 0.6398459 0.1536678 0.6072182 -0.665113 -0.4346388 0.2763785 -0.8519923 -0.444662 0.173803 -0.8777903 -0.4464045 0.2779859 -0.8513895 -0.4448146 0.1553593 -0.8840493 -0.4408179 0.1303199 -0.8879687 -0.4410538 0.0162996 -0.8724249 -0.4884764 0.3259699 -0.8350174 -0.4432716 0.3639281 -0.8183706 -0.4447764 -0.2111846 0.7860383 -0.5809862 -0.1597877 0.8075965 -0.567676 -0.3569785 0.7340312 -0.5777236 -0.5052841 -0.1839087 -0.8431284 3.32734e-7 0 1 0 0 1 -9.41368e-7 0 1 0.9384455 0.3454179 0.002621769 0.4739941 0.17252 -0.8634619 0.397035 0.1501971 -0.9054303 0.2400512 0.09011596 -0.9665685 0.7706274 -0.623575 -0.1314829 0.9958515 -0.07194 0.05571824 -0.7791578 0.61961 -0.09485214 -0.6236346 -0.7731015 -0.1157326 0.1746197 -0.9843916 0.02194035 0.05604517 0.9972487 0.04851883 -0.7469943 -0.6616926 -0.06451666 0.0934472 -0.06175464 -0.9937072 0.06322544 -0.04093348 -0.9971595 0.06756103 -0.02703815 -0.9973488 -0.004920482 -0.0264616 -0.9996377 -0.09265631 0.1261683 -0.9876722 -0.2071133 0.05283421 -0.9768893 0.09865856 0.1060414 -0.9894553 0.1460794 0.002483665 -0.9892697 9.12519e-4 -0.02461838 -0.9996965 -0.405487 0.7443804 0.5305454 0.5585855 0.3669539 0.7438595 0.3955929 0.7917532 0.4654386 -0.5486376 -0.8169373 -0.1777923 -0.5370551 -0.2973936 0.7893852 0.7596421 -0.6475373 -0.06032669 0.8163275 -0.5705132 -0.09013551 -0.6624439 0.7490816 -0.006709158 0.9890404 0.1475443 0.005452513 -0.2587562 0.9656986 0.02171134 0.452892 -0.247544 -0.8565109 0.4400919 -0.3751804 -0.815818 -3.3538e-4 -0.002470731 -0.9999969 0.001643538 -0.006265282 -0.999979 -0.2151025 0.1485951 -0.9652204 -0.01722264 0.06427776 -0.9977834 0.05826526 0.03068792 -0.9978294 0.649447 -0.1886765 -0.7366273 -0.01262569 0.02379477 -0.9996371 -0.003163695 -0.01856142 -0.9998228 -0.7478227 -0.132337 0.6505753 0.913015 0.00574553 0.4078856 0.3662896 0.7424262 0.5609237 0.4081671 0.6416028 0.6494194 0.02698916 0.4367101 0.8991975 -0.1569833 -0.4691575 0.8690499 -0.2349028 -0.3519644 0.9060584 0.332407 -0.9431157 -0.00622183 0.9333689 -0.358827 0.008117258 0.6629202 0.7456461 -0.06744444 0.3871026 -0.9217208 -0.02413511 0.7061002 0.7061079 -0.05323648 0.03298074 0.999452 -0.002841413 -0.3303226 0.9433304 -0.03185713 -0.01889771 -0.2914903 -0.9563872 -0.01031965 -0.1388204 -0.9902639 0.06201529 -0.0212574 -0.9978489 -0.003481805 0.1167287 -0.9931578 0.05394077 0.05394077 -0.9970862 -0.377654 -0.4327468 -0.8186011 -0.2411767 0.03375911 -0.9698939 0.1615703 0.02577304 -0.9865246 1.98386e-4 0.004201829 -0.9999912 0.002024769 0.006236195 -0.9999786 0.1800304 0.1498116 0.972186 0.9389074 -0.02979946 0.3428775 0.5624053 0.3064977 0.7679581 0.3857206 -0.7632702 0.5183032 0.3989467 0.7937445 0.4591418 -0.6825597 -0.410285 0.6047963 -0.2428535 0.4898419 0.8373035 0.686258 -0.724528 -0.06410241 0.9506349 0.3054817 -0.05453658 -0.8129175 0.5728062 -0.1051594 0.1515061 -0.9884462 0.004493117 0.3575232 0.9339041 -5.99054e-4 -0.2587778 0.9657761 0.01762312 -0.5285877 0.8488574 -0.006023705 -0.6433339 -0.759471 -0.09656852 0.003395676 -0.004544973 -0.9999839 0.005437493 -0.01917338 -0.9998014 0.06775331 0.05604606 -0.9961267 -0.1933297 0.1285822 -0.9726718 -0.2216951 0.2592477 -0.9400223 -0.2513279 0.06895881 -0.9654424 -0.2252244 0.1477889 -0.963033 0.07641392 0.04974991 -0.9958343 0.6057537 -0.7546913 0.251999 -0.5484796 -0.8169926 -0.178026 -0.1489739 0.0223158 0.9885894 -0.7540853 -0.5791633 0.3097186 0.5299317 -0.3740594 0.7610861 -0.7026379 -0.7026476 -0.1121889 -0.7951942 -0.6027539 -0.0659852 -0.2587443 -0.9656327 -0.02459484 0.2057991 -0.9766243 -0.06206429 0.9498344 -0.3105056 -0.03742933 0.6520832 0.7520943 -0.0956124 -0.6903509 0.7117047 -0.12997 -0.965663 -0.2587417 -0.02340501 0.7068848 -0.706901 -0.02459669 0.979598 -0.1830481 -0.08295327 0.2587533 0.9657188 -0.02083188 -0.01024872 -0.002746045 -0.9999437 -0.06558948 -0.04556488 -0.9968059 0.01993185 -0.07438409 -0.9970305 0.05679589 -0.05679589 -0.996769 0.176387 -0.03302919 -0.9837666 -0.03258264 0.2742679 -0.9611012 -0.1546116 0.4387556 -0.8852056 0.2013913 -0.06063878 -0.9776322 0.01696652 -0.003662288 -0.9998494 1.35612e-4 -9.13046e-4 -0.9999997 -0.3932687 0.9060338 0.1563412 0.4539026 0.3982601 0.7970957 -0.6309069 -0.2485676 0.7349629 0.297572 0.9546704 -0.007442355 -0.7333881 0.6791964 -0.02888417 -0.04279077 -0.9979689 -0.04719299 0.8022959 0.5947458 0.05097991 0.1553044 0.9857298 -0.06494039 -0.6210599 0.7837282 0.007414579 -0.8892181 0.4574825 -9.80768e-4 -0.9645479 -0.2584571 -0.05335974 0.08163505 -0.07975018 -0.9934666 0.08910572 -0.005839526 -0.9960051 -4.35623e-4 -8.94103e-5 -1 -4.79441e-4 -4.79488e-4 -0.9999998 -0.1909432 0.1096739 -0.9754549 -0.2411302 0.06007111 -0.9686319 0.08053642 0.09373074 -0.9923349 0.1886407 -0.002556681 -0.9820429 -0.001041054 0.001382648 -0.9999986 0.2577608 0.3396126 0.9045567 0.889666 0.01004391 0.4565014 0.3433966 -0.7428168 0.5747191 -0.5491533 -0.817111 -0.1753866 -0.3076364 0.3758081 0.8741443 -0.3442139 -0.2853328 0.8944843 0.4443253 -0.8950331 -0.0386132 0.8572542 -0.5139009 0.03195482 0.970357 0.2301272 -0.07381707 0.1112405 0.9919829 -0.05996364 -0.961269 0.2753084 -0.01292788 0.5046174 -0.8613156 -0.05913382 0.5282918 0.8490581 -0.002849221 0.2157177 0.9760093 -0.02952885 -0.4629657 0.8856613 0.03559327 -0.4670425 -0.8841948 -0.008418262 0.05897676 -0.5064495 -0.8602505 0.1315326 -0.009196341 -0.9912692 -0.6051159 -0.2500798 -0.7558405 -0.2584105 0.01776093 -0.965872 -0.2574029 0.02468878 -0.9659888 0.07079738 0.02510797 -0.9971747 -0.1412636 -0.2704674 -0.9523088 0.005469977 -0.007295966 -0.9999585 -8.38825e-4 0.002760648 -0.9999958 -0.2516775 -0.4246814 0.8696576 -0.5861666 -0.2036616 0.7841753 0.5281261 -0.8491652 -0.001226365 0.9976968 -0.03910064 -0.05542922 0.3134101 0.9461801 -0.08073079 -0.7109686 -0.695041 -0.1069661 0.9403496 0.338539 0.03367525 0.5127883 0.8584852 -0.007177293 -0.973488 -0.2281276 0.01670229 -9.48516e-4 -0.007918059 -0.9999682 -0.01535081 -0.2148334 -0.9765301 0.08810162 0.07942426 -0.9929401 -0.1265323 -0.1118264 -0.9856391 -0.3273359 0.03242993 -0.9443514 -0.2171995 0.1256615 -0.968005 0.08121913 0.1005853 -0.9916079 -6.00381e-4 -0.008827269 -0.9999609 0.006992399 0.005460917 -0.9999607 0.002539634 -0.008890211 -0.9999573 0.5591991 0.3506968 0.7512044 0.1347045 -0.9877211 -0.07913208 0.3999851 0.7921608 0.4609698 0.8444269 -0.5327509 -0.05585569 0.76632 -0.6419692 -0.02508473 0.9160915 0.3968939 -0.0570231 -0.3269917 0.9384133 -0.111611 -0.9654782 -0.2467086 -0.08358675 -0.1814476 -0.9830391 -0.02666682 0.0327593 -0.9994629 -9.86775e-4 -0.01552349 0.9998775 0.002014577 0.05367201 -0.1754467 -0.9830248 0.05273681 -0.1690604 -0.9841939 0.06214523 0.06671941 -0.9958347 -0.5736318 -0.1536988 -0.8045641 -0.5140613 -0.1984125 -0.83449 -0.04145652 0.1229296 -0.9915492 0.1972408 0.07843428 -0.9772124 -0.1209014 -0.1977602 -0.9727661 0.002086997 -0.005378484 -0.9999834 0.002075731 -0.005413293 -0.9999833 0.2885078 0.1702145 0.9422263 -0.3401591 0.8538714 0.3939489 -0.1819499 -0.4281813 0.8851864 -0.5700128 -0.2719847 0.7753127 0.759758 -0.6476355 -0.05775851 0.008349895 -0.9999616 0.002678632 -0.7903041 -0.6126455 0.009232997 0.03726577 -0.166 -0.9854214 0.053801 -0.04587715 -0.9974973 0.09142345 0.01364934 -0.9957186 0.05420172 0.05420094 -0.9970579 0.07849657 0.1826584 -0.9800379 -0.407796 -0.2833727 -0.8679876 -0.4078432 -0.3103886 -0.8586751 -0.1937646 0.2093285 -0.9584555 -0.1886188 0.1154863 -0.9752363 0.1241015 0.002328634 -0.9922669 -0.4532898 0.02895778 0.8908928 -0.3111158 0.5043802 0.805486 0.350401 -0.5787993 0.7363496 0.3354476 0.5988216 0.7272466 -0.1304722 -0.3742401 0.9181076 -0.04726719 0.4357757 0.8988134 -0.2228524 0.9359174 -0.2727555 0.3159291 -0.3937317 0.8632289 0.5492594 -0.8355025 -0.01580673 -0.330828 0.9434286 -0.02226001 -0.9790878 0.1910245 -0.06997644 0.4713397 0.881951 -0.001177906 -0.464981 0.8835783 -0.05551844 -0.5279307 0.8492873 5.75374e-4 0.094204 -0.01796704 -0.9953908 0.07001847 -0.0200715 -0.9973438 0.03444451 -0.001119077 -0.999406 0.03714627 0.3066844 -0.9510862 -0.5308745 -0.2455344 -0.8111013 -0.4257445 -0.1562681 -0.8912473 -0.2583952 0.01784604 -0.9658744 0.07778358 0.1018546 -0.9917538 -0.1431307 0.009820938 -0.9896551 -0.137782 -0.3278126 -0.9346417 -0.001705408 0.0055449 -0.9999832 -0.4967535 0.6087334 0.618611 -0.4034819 -0.0483489 0.9137095 -0.8208749 -0.5642302 0.08836656 0.6111469 -0.3577629 0.7060491 0.8497765 -0.5271347 0.003015816 -0.7137045 0.6990739 -0.04383796 -0.9390706 -0.3396097 -0.05302613 0.5126671 0.8585622 0.006599605 -0.4688948 0.8832484 -0.003196835 -0.8500726 0.5266394 0.00525099 -0.1233348 -0.9920803 -0.02377176 0.09257519 -0.1105673 -0.9895478 0.1038689 0.002927005 -0.9945867 0.09491711 -0.03745734 -0.9947803 -0.01439231 0.1221876 -0.9924027 -0.02568745 0.2535755 -0.9669745 -4.85184e-4 0.002156913 -0.9999976 -4.95311e-4 -2.33028e-4 -1 0.05055445 -0.02216917 -0.9984753 9.34395e-4 0.002097189 -0.9999974 -6.8098e-4 -0.00624001 -0.9999803 -0.7478221 -0.1323447 0.6505744 -0.1281697 0.2012133 0.971126 -0.2226322 0.3053874 0.9258367 0.9743434 0.04072856 0.2213506 0.3631368 -0.4373277 0.8227249 0.3530497 -0.688216 0.6338096 -0.04473984 0.2011574 0.9785367 -0.2236119 0.1254796 0.9665674 -0.2591978 0.2923233 0.9205236 -0.6168676 0.7851336 -0.05513435 0.9883576 0.1418082 -0.0551359 0.3720998 0.9281922 0.001068592 -0.9385361 -0.3311991 -0.09724879 -0.3788577 -0.92395 -0.05275696 -0.03846645 0.05830186 -0.9975576 -0.09981411 0.02674567 -0.9946467 -0.06564509 -0.02311402 -0.9975753 0.1124379 -0.3067294 -0.9451321 0.005231499 0.005230128 -0.9999727 7.46215e-4 1.99664e-4 -0.9999998 0.1109765 -0.3146479 -0.9426988 5.6341e-4 -1.70971e-4 -0.9999999 6.00052e-4 0.006723999 -0.9999773 1.57111e-4 3.91956e-4 -1 0.004368662 -0.03193801 -0.9994804 -1.57168e-4 -3.92284e-4 -1 0.8553853 0.3810457 0.350885 -0.3805522 -0.4310936 0.818131 0.2226871 -0.6968484 0.6817718 -0.1781784 0.8592768 0.4794746 0.4384548 0.6243911 0.6464465 0.5806599 0.4598633 0.6718333 0.2310295 -0.5132287 0.8265722 0.9269765 -0.3741142 0.02744656 0.2381634 0.971171 0.01025325 -0.7333455 0.6791487 -0.03101003 -0.9104857 0.4076231 0.0697081 -0.4853681 -0.8743035 0.003378391 0.1696549 0.02222639 -0.9852529 0.2274512 0.1211023 -0.96623 -0.2250458 0.3719221 -0.9005712 -0.2103819 0.05074936 -0.9763013 0.1897425 0.04510116 -0.9807975 -0.002364814 -0.004221081 -0.9999883 0.00149542 -0.006220281 -0.9999796 -0.001111388 0.00256747 -0.9999961 -0.8539842 -0.2220753 0.4705247 0.2577639 0.3396111 0.9045563 -0.3502206 0.8698586 0.3474068 0.6185958 0.4126157 0.6686462 0.5133206 0.1170355 0.8501793 0.6562306 -0.3183136 0.6841329 -0.3442135 -0.2853345 0.8944839 -0.4385616 -0.2198072 0.8714061 0.8212725 -0.5693673 -0.03650206 0.7671455 -0.6414154 -0.008615493 0.9515593 0.3071435 -0.01407194 -0.7331465 0.6789223 -0.03950667 -0.9378328 -0.3391332 -0.07388228 -0.1827754 -0.9831464 -0.004060924 0.9748462 0.222494 0.0130971 -0.3110918 0.9500524 0.02494734 -0.7069231 -0.7069316 -0.02252638 0.08609443 -0.1004549 -0.9912098 -4.79437e-4 -4.79502e-4 -0.9999998 -0.1699818 0.1229791 -0.9777436 0.1347278 0.03671807 -0.9902021 -0.06248199 -0.03138393 -0.9975526 0.03775495 -0.1070188 -0.99354 -3.70442e-4 0.001625597 -0.9999986 9.84094e-4 -0.005745708 -0.9999831 -7.71377e-4 -2.48962e-4 -0.9999997 -0.3542253 0.4973327 0.7919499 0.8509958 0.1833981 0.4921092 0.4893685 0.4100511 0.7696601 0.4008224 -0.6374654 0.6580117 -0.5480206 -0.8175329 -0.1769564 -0.4653157 0.604891 0.6462107 -0.2979781 -0.3777523 0.8766483 -0.5302554 -0.2489265 0.810472 0.8568828 -0.5121809 -0.05850422 0.7593885 -0.6505928 -0.007641017 0.9552847 0.2953807 -0.01347684 -0.4270966 0.9041332 -0.01147377 -0.2689278 -0.9595339 -0.08350199 0.2587456 -0.9656823 -0.02255314 0.9762233 0.2165065 0.0106365 0.5173062 0.8557499 0.009310305 -0.5279385 0.8492824 5.76297e-4 -0.9381247 -0.3462094 -0.007817327 -0.3472017 -0.9360201 -0.05759578 0.001818597 -0.006791234 -0.9999753 0.2443975 -0.06513184 -0.9674853 0.2857848 0.06877559 -0.9558227 0.02867579 0.03739565 -0.9988891 -0.4320854 -0.1650652 -0.8865979 -0.2583951 0.01784855 -0.9658744 -0.2509432 0.0672394 -0.9656637 -0.142163 -0.3679474 -0.9189148 2.87099e-4 0.006692767 -0.9999777 -0.0240978 0.9917328 -0.126037 0.002213954 -0.002422332 -0.9999946 0.1174566 0.1085124 0.9871318 -0.5137349 0.6189528 0.5941161 0.7296292 0.2510581 0.6360904 0.4869931 -0.1601298 0.8586013 0.370622 -0.8712817 0.321726 0.2010456 -0.3371821 0.9197223 -0.6840566 0.2693004 0.6778966 0.7070865 0.707103 0.00584203 0.6549338 0.7556859 -8.0532e-4 0.9659273 0.2588126 -8.22282e-4 0.9907376 0.1355842 0.007487595 0.9658901 -0.2588129 -0.008499383 0.7070941 -0.7070953 0.005842447 -0.2588102 -0.9658908 -0.008501291 -0.7070927 -0.7070968 0.005842387 -0.9659119 0.2588052 0.005839228 -0.2588164 0.965909 0.005839109 -0.001564145 4.18843e-4 0.9999987 -0.01524388 -0.05691552 0.9982627 0.01297038 -0.03953939 0.9991339 8.43559e-4 0.005539894 0.9999844 -1.04468e-4 -1.07438e-4 1 0 1.38527e-4 1 -0.4869334 -0.02923476 -0.8729498 -0.3171781 -0.6031199 -0.7318775 -0.2087025 -0.5580028 -0.8031663 -0.3492188 0.1542945 -0.9242509 -0.01090645 0.3779591 -0.9257581 0.9658867 0.2588255 -0.008499383 0.9517555 -0.3066785 0.01047885 -0.210249 0.9775918 0.01047986 0.2588162 0.9658893 -0.008502125 0.7070745 -0.7070879 -0.008500337 0.2588232 -0.9659071 0.005841016 -0.9658901 -0.2588127 -0.008500039 -0.9659084 0.2588183 0.005839049 -0.2588135 0.9659097 0.005840003 0.1143199 0.1143234 0.986844 7.50623e-4 -3.59477e-4 0.9999997 -0.01457244 -0.0544086 0.9984124 4.14414e-4 4.13825e-4 0.9999999 0.1072229 -0.1464012 0.9833972 -0.001203477 -0.003818988 0.999992 -0.6598072 -0.6028283 -0.4486119 -0.1956517 0.2856231 -0.9381577 -0.2207501 0.3801795 -0.8981832 -0.1785823 -0.5086538 -0.8422468 0.7438323 0.00969243 -0.6682961 -0.3048353 -0.4343721 -0.8475828 0.7414773 0.6708961 0.01048207 0.9658903 0.2588122 -0.008497595 0.9517462 -0.3067073 0.01048147 0.2102509 -0.9775912 0.01048147 -0.9517517 0.3066902 0.01047706 -0.2102445 0.9775927 0.01048046 0.2588216 -0.9659075 0.005841791 -0.2588116 -0.9658904 -0.008501589 0.09199309 -0.003404676 0.9957539 0.1244555 -0.1244538 0.9843893 -0.01359629 0.01359927 0.9998151 6.18665e-4 1.65477e-4 0.9999999 -0.02773422 -0.02773493 0.9992305 0.1141441 -0.123372 0.9857741 -0.004939079 0.01841831 0.9998182 -0.001207113 -0.003830611 0.999992 -0.6215466 -0.3636546 -0.6938554 -0.8577755 -0.3189688 -0.4030883 -0.1879592 -0.6139267 -0.7666587 0.04754006 0.8742328 -0.4831742 -0.176316 -0.004005551 -0.9843255 0.1863682 -0.1670508 -0.968174 0.9658903 0.2588123 -0.008498966 0.9517523 -0.3066884 0.01048219 -0.2102672 0.9775878 0.0104773 0.9659084 -0.2588183 0.005844473 0.2588032 -0.9659125 0.005844116 -0.7070986 -0.7070909 0.005843281 -0.7070856 0.7070769 -0.008503973 -0.2588032 0.9659125 0.005838453 0.01551848 0.08553594 0.9962143 0.03794938 0.03795522 0.9985587 0.0438131 -0.04381453 0.9980785 -0.1144865 -0.01240152 0.9933474 -0.1437246 -0.03851056 0.9888681 -0.1369581 -0.1369616 0.9810627 0.001218616 0.003864228 0.9999919 -0.001210629 -0.003841221 0.9999919 -0.04006052 0.3630253 -0.9309177 0.1948816 0.02418512 -0.9805285 0.1409169 0.2367929 -0.9612865 -0.324918 0.3813256 -0.865459 -0.5245312 0.2849826 -0.8022794 -0.2349838 -0.8568186 -0.4589603 0.9659253 0.2588199 -8.2289e-4 0.755681 -0.6549395 -8.02171e-4 -0.7414656 -0.6709091 0.01048189 -0.2102463 0.9775923 0.01047813 0.2588086 0.9658913 -0.00850445 0.9658901 -0.2588129 -0.008498609 -0.2588208 -0.965888 -0.008500099 -0.7070922 -0.7070974 0.005844056 -0.9658899 -0.2588134 -0.008499562 -4.58178e-6 -2.09726e-5 1 0.07740098 0.02074009 0.9967844 0.05992203 -0.0160557 0.998074 -4.04267e-4 0.001505136 0.9999988 -0.02408069 -0.0766189 0.9967696 -0.0041399 0.01544451 0.9998722 -5.75019e-6 4.75896e-5 1 -1.04466e-4 -1.07436e-4 1 -0.9724174 0.1446402 0.1829859 -0.111974 0.2971614 -0.948239 -0.6703683 0.2062057 -0.7128013 0.1815643 0.7942417 -0.5798403 -0.2181313 0.7055226 -0.6742823 -0.4791737 0.1360173 -0.867117 0.4237952 0.3684383 -0.8274363 0.148842 -0.5381906 -0.8295764 0.654945 0.7556762 -8.06027e-4 0.9659221 0.2588319 -8.20769e-4 0.990738 0.1355804 0.0074898 0.7556869 -0.6549326 -8.00186e-4 0.1355575 -0.9907413 0.007491886 -0.7414699 -0.6709043 0.01047992 -0.9517465 0.3067067 0.01047492 -0.2102531 0.9775909 0.010477 0.9658868 -0.2588249 -0.008496046 0.7070974 -0.7070922 0.005845308 0.2588202 -0.9659252 -8.19238e-4 -0.9658868 -0.2588254 -0.008502244 -0.7070899 0.7070727 -0.008504509 -0.2588124 0.96591 0.005836009 -0.01747202 0.08711504 0.9960451 0.00657624 0.006577372 0.9999568 -3.49863e-5 3.64135e-5 1 0.006059527 -0.0226317 0.9997255 -9.37989e-4 0.08571159 0.9963196 0.001084268 -0.001082062 0.9999989 0.001325249 -3.54907e-4 0.9999991 0.005822598 0.005224645 0.9999695 -0.02256876 0.08421427 0.9961921 8.44225e-4 0.005539834 0.9999844 -5.75024e-6 4.75899e-5 1 0.101482 0.3861398 -0.9168412 0.9424369 0.09126257 -0.321689 0.4180006 -0.6288418 -0.655617 0.1838946 -0.5659992 -0.8036342 0.1890165 0.6110855 -0.768666 0.2417166 0.07089483 -0.9677536 0.5434278 -0.8393926 0.01031476 -0.4552091 -0.8903249 0.01031213 -0.9986231 -0.05090677 0.01266813 -0.543405 0.839354 0.01400285 0.4551987 0.8903301 0.01031225 0.1413676 -0.1174884 0.9829608 0.1317991 -0.1325091 0.9823799 -0.1486847 0.3833532 0.9115554 -0.01236402 0.2615252 0.9651176 -0.002874314 -0.001884639 0.9999941 -2.01803e-5 -3.83689e-5 1 0.002869129 0.001882016 0.9999941 0.03705835 -0.1855452 -0.9819368 0.3045265 -0.5573034 -0.7724485 0.2741097 -0.6648508 -0.694865 -0.5032832 0.1263527 -0.8548339 0.1464372 0.6086582 -0.7798023 0.4831559 0.8755294 -0.002951323 0.6350777 0.7722824 0.0160129 0.9993262 0.03345906 0.01509052 0.7429299 -0.6691717 0.01626712 -0.378239 -0.9256353 0.01159691 -0.743198 0.6688739 0.01626253 0.7413083 -0.6709616 0.01650661 -0.999898 -0.01419746 -0.001630604 -0.7069501 0.7069377 0.02146166 -0.01336282 0.9997993 0.01492428 -0.2060031 0.2059995 0.9566227 -0.1214672 0.1324563 0.983718 -0.07439351 -0.01761591 0.9970734 -0.001184821 -0.004362404 0.9999898 6.08461e-4 0.005726516 0.9999834 -0.4364809 0.5554249 -0.7078047 -0.7848939 -0.1518991 -0.6007231 0.3936254 -0.7766218 -0.4918513 0.2080329 0.1191176 -0.9708417 0.01493823 -0.2176835 -0.9759051 -0.7750195 -0.4845454 -0.4056607 0.8498864 -0.5188663 -0.09203827 0.5569655 -0.8283976 0.0595557 -1.8165e-5 -7.80155e-5 1 0.05844634 -0.003979027 0.9982827 5.08105e-5 -6.36374e-5 1 -1.30701e-4 6.28734e-5 1 -1.65013e-4 0 1 0.00120151 -0.002157628 0.999997 -0.04267346 -0.0488165 0.9978958 -0.05385202 0.01333993 0.9984599 5.59029e-4 -2.69208e-4 0.9999998 -0.818106 0 -0.5750675 -0.5383716 -0.6671687 -0.5148223 0.7593699 0.3634392 -0.5396938 0.7554082 0.1716517 -0.6323719 0.5533824 0.6939069 -0.4607181 -0.2039552 0.8935964 -0.39986 0.03250437 0.7968427 -0.6033118 -0.06215256 0.6271539 -0.7764117 0.7151243 0.6870936 0.1284514 0.9529902 0.303 -8.51701e-4 0.6913151 -0.716735 0.09151166 -0.7151209 -0.6870971 0.1284515 -0.691311 0.716739 0.0915113 0.7373138 -0.6723566 0.06561172 -0.2140733 -0.9767444 -0.01195919 4.60081e-6 5.22512e-6 1 0.00198847 7.72388e-4 0.9999978 1.72213e-6 -4.20823e-6 1 -0.003084123 -0.002285838 0.9999927 -0.002558767 0.00240451 0.9999939 -2.08543e-6 -1.23701e-6 1 -1.481e-6 -2.51198e-6 1 2.10282e-6 -3.09054e-6 1 7.66243e-4 0.002359807 0.999997 0 4.20845e-6 1 -0.8161455 0 -0.5778465 -0.8036482 0.02099263 -0.5947342 -0.789705 0.38509 -0.4775688 -0.5786834 -0.7256554 -0.3722229 -0.1893913 -0.8297865 -0.5249622 0.7755115 -0.07903563 -0.6263669 0.78772 -0.379348 -0.4853785 -0.9474334 0.1076511 -0.3012992 0.1878233 0.8228917 -0.5362572 -0.1696503 0.7432927 -0.6470972 -0.5427281 0.6740676 -0.501078 0.03552651 -0.6645727 -0.7463787 0.4908908 0.02941846 -0.8707244 -0.8195746 0.5503276 0.1594899 0.9031306 0.4182425 0.09709948 -0.8756646 -0.4812662 0.03993093 -0.8483102 -0.405146 -0.34092 -0.9031675 -0.4191617 0.09269249 0.5650008 0.349183 0.7475596 0.6746132 0.2135493 0.7066072 0.5434249 0.3274729 0.7729495 -0.00724709 -0.007264137 0.9999474 -0.5863944 -0.3258712 0.7415859 -0.5798577 -0.3272837 0.7460902 -0.633338 -0.4339935 0.6407284 -0.5492647 -0.36958 0.7494792 -0.2322195 0.5044921 0.831602 -0.2830325 0.3780959 0.8814398 0.05753868 0.04799795 0.9971888 -0.008490741 -0.00494188 0.9999518 0.6314342 -0.4100393 0.658148 -0.5923211 -0.2745018 0.7574989 0.5951135 0.2895965 0.7496492 -0.02822613 0.06887298 0.9972261 0.02748733 0.07786828 0.9965847 -0.05227029 -0.06476891 0.9965304 0.06177169 -0.2012547 0.9775894 -0.5816608 -0.2656899 0.7688171 -0.5929156 -0.283906 0.7535572 -0.5482517 -0.8105052 -0.2061588 -0.8754377 -0.4342723 0.212171 0.4790241 0.2048752 0.8535585 -0.161548 0.08422338 0.9832644 -0.1541803 0.2242107 0.9622671 -0.06430768 -0.2086157 0.9758812 -0.06046837 0.141988 0.9880198 -0.1124883 0.1904422 0.9752324 0.2672493 -0.9498757 0.1622155 0.2424798 -0.4898802 0.8373894 0.1549668 0.1445544 0.9772868 0.3567045 -0.4594641 0.8134217 0.7817252 0.1144205 -0.6130365 0.836582 -0.5326776 0.1280043 0.6215666 0.3606519 -0.6954029 0.7316036 0.6467878 0.2154575 0.884628 0.460891 0.07080268 0.8571392 0.5127741 0.04873615 -0.8365712 -0.540025 0.0923143 0.4180539 -0.9082174 -0.01929157 0.5900338 -0.8073709 0.003526747 -0.2982901 -0.953648 -0.03973138 -0.2996494 -0.9514034 -0.07100594 -0.8628888 -0.4980357 -0.08592683 -0.9561021 0.2908061 -0.03606754 -0.965178 0.2498281 0.07757222 -0.8420438 0.4848442 -0.2364078 -0.5095708 0.8590646 -0.04843175 -0.1956721 0.9806635 -0.003430902 0.8626976 0.4980986 -0.08746886 0.9763193 -0.1970351 -0.08931905 0.9688759 -0.2417364 -0.05332112 -0.2566133 -0.1477323 -0.9551571 -0.2631791 -0.1519521 -0.9527053 -0.08940219 -0.05160486 -0.9946579 -0.4479617 -0.3490788 -0.8230884 -0.5486493 -0.4490924 -0.7051951 -0.6120767 -0.3534231 -0.707428 -0.6124233 -0.3535225 -0.7070782 0.6121287 0.3535614 -0.7073138 0.6123949 0.3535506 -0.7070888 0.4218972 0.2874484 -0.8598699 0.2582791 0.1491208 -0.954492 0.08916914 0.0514813 -0.9946852 0.4347862 0.2504691 -0.8650007 0.5475361 0.2697121 -0.7921235 0.525274 0.8054431 0.274497 -0.6167469 -0.3368403 0.7114506 -0.6125904 -0.3537995 0.7067949 -0.6123588 -0.3535466 0.707122 -0.5985834 -0.3657755 0.7126755 -0.7651199 -0.6438879 2.19472e-4 0.8423597 0.5234079 0.1283533 0.6348429 0.4196205 0.6487627 0.1526122 0.2011744 -0.9675942 -0.3589003 0.6238237 -0.6942871 -0.3515943 0.6082653 -0.7116143 0.5475919 0.6684126 -0.5033566 0.5295091 0.7170471 -0.4532809 -0.500289 -0.06207054 -0.8636308 -0.4173049 0.01452672 -0.9086505 -0.9726064 -0.07103753 -0.2213382 0.8310148 0.479605 -0.2817686 -0.8858512 -0.09507471 -0.454124 -0.8376703 -0.4832354 -0.2545427 0.3820471 -0.6029784 -0.7003265 -0.5319823 -0.7110709 -0.4597533 0.116006 -0.2006436 -0.9727717 0.3508464 -0.6069692 -0.7130886 -0.1536122 -0.1527668 -0.9762508 -0.4901399 -0.5779192 -0.6525123 -0.9978104 0.06343609 -0.0187152 0.08711385 -0.9954683 -0.03813225 -0.8707729 -0.4909262 -0.02731245 -0.8660277 -0.4967455 -0.05692201 0.8643039 0.4974377 -0.07439488 -0.02838397 0.4041522 -0.9142513 -0.4539557 -0.2290068 -0.8610924 -0.4731813 -0.2343236 -0.8492302 -0.54446 -0.3251569 -0.7731987 -0.611697 -0.3754739 -0.696309 -0.6090455 -0.3747135 -0.6990374 0.8447455 -0.04498314 -0.5332745 -0.6920937 -0.3674772 0.6212623 -0.5048562 -0.6146542 0.6060698 0.07548528 0.8089758 -0.5829754 0.2141879 0.9721244 0.09538209 0.214272 0.9765828 -0.01932901 0.8659022 0.4980511 -0.04645913 -0.8637609 -0.4996381 -0.06541419 0.6881369 0.3936915 -0.6094871 0.417411 0.2719148 -0.8670816 0.01220786 0.313925 -0.9493693 0.6809595 0.3909417 -0.6192404 -0.7897617 0.58218 0.1932436 -0.6195064 -0.3581491 -0.6985278 -0.3077701 0.6092391 0.7308251 -0.2211977 -0.137423 0.9654982 -0.1563781 -0.06114572 0.9858028 -0.004871547 -0.05298566 0.9985834 0.2163094 0.1248838 0.9683049 -3.51384e-4 -6.30677e-5 1 0.04396796 -0.07614076 0.9961272 -0.4638847 -0.2678253 0.8444411 0.8742089 0.485163 -0.01938527 0.6564758 0.03698611 0.7534399 -0.8570774 -0.5149899 -0.01427835 0.5095722 0.2465054 0.8243612 0.3521959 0.2014927 0.9139796 0.856893 0.4425286 0.2643916 -0.3419358 -0.9313918 -0.1248568 0.7836005 0.5204731 0.3392317 0.8883181 0.459003 -0.01440358 -0.8391756 -0.4864981 0.2431134 -0.7861974 0.5313433 0.3155442 -0.1133457 0.9327502 0.3422423 0.4340439 -0.7976419 0.418776 -0.6315726 0.6161478 0.4706146 -0.8281776 -0.5496349 0.1096524 0.8500738 -0.05208033 0.5240824 0.5005246 -0.8653661 0.02483183 0.4324143 -0.8913303 -0.1361919 0.5285817 -0.8473063 0.05170583 -0.562275 0.8259696 0.04026418 -0.5025656 0.8415976 0.1978411 0.4959538 -0.8668671 0.05071032 0.4999097 -0.8657233 -0.02477204 0.6663444 -0.7391489 -0.09820491 0.4567892 -0.8848536 0.09153145 -0.4979209 0.8649671 0.06250411 0.8189484 0.5562285 0.1411857 -0.4937372 0.8691359 -0.02875173 8.41937e-4 -0.001637756 0.9999983 -8.03387e-4 3.28541e-4 0.9999997 -0.4585773 0.8885568 0.0131734 0.5007043 -0.8589062 0.1075896 0.5595903 -0.8212721 0.1112237 -0.2661362 0.961217 0.07234299 -0.5031145 0.8629786 0.046301 0.3866491 -0.6799858 0.6229942 0.1630619 0.01272761 0.9865338 0.4931012 -0.3228073 0.8078655 0.3850984 -0.6975129 0.6042971 -0.03196871 0.5450714 0.8377799 0.1333134 0.1259643 0.9830364 0.06375122 0.08601248 0.9942524 -0.2783491 -0.166269 0.9459791 -0.1507105 0.02495777 0.9882628 0.1570952 0.1378934 0.9779093 0.2188383 0.1364279 0.9661766 -0.8656169 -0.4976028 0.0556674 -0.8649762 -0.4991377 0.05174612 0.8696919 0.4923271 0.03535938 0.8638835 0.5004609 0.05695873 0.5669775 -0.8126039 0.1349498 0.478519 -0.8745197 0.07896238 -0.4614532 0.8845128 0.06854456 -0.001832187 -0.007728457 0.9999685 -0.0540108 -0.02375859 0.9982577 -0.4551331 0.8832799 0.1125639 -0.477545 0.8733528 0.09594601 0.8691563 0.491703 0.05287361 0.8652731 0.5002561 0.03234785 -0.8631007 -0.5014697 0.05987805 -0.8697552 -0.4922458 0.0349307 0.5345434 -0.8400477 0.09264546 -0.005792915 8.10109e-4 0.999983 0.02539306 0.008314311 0.999643 0.4480274 -0.8911253 0.07188451 0.8591515 0.5020217 0.09916228 -0.6441138 0.7635362 0.04615014 -0.3836483 0.921594 0.05897963 0.8602328 0.5006766 0.09655338 0.003983139 -0.1175836 0.9930551 0.036897 0.6684288 0.7428604 0.4921163 0.2104407 0.8447108 0.6486255 0.3679459 0.6662589 -0.05589973 -0.07687878 0.9954722 0.9387888 -0.03234887 -0.3429713 -0.09155279 0.2278246 0.9693886 -3.46657e-4 -0.0262776 0.9996547 -0.05817085 0.03281021 0.9977674 0.2250018 -0.3058993 0.9250946 -0.1368247 0.5987335 0.789175 -0.6611842 -0.4009495 0.6340938 0.4620028 -0.674844 0.5754469 -0.8392851 -0.4868214 0.2420856 -0.041817 0.1619077 0.9859195 -0.5033782 0.4827282 0.7166478 -0.4807056 0.6700512 0.5656443 -0.3093078 -0.9318963 0.1894682 -0.5393894 -0.3491579 0.7662559 0.5863044 0.2866083 0.7576957 -0.08259838 0.9799413 -0.1813632 0.001539051 -0.02080148 0.9997825 -0.8529145 0.5193926 0.05261498 0.2577013 -0.2856016 0.9230504 0.8970395 -0.4389163 0.05169749 -0.661627 0.1749377 0.7291409 -0.1613681 -0.2707884 0.9490174 0.6139334 -0.351383 0.7068351 0.6118952 -0.3532801 0.7076564 0.6263219 -0.3350771 0.7038781 0.4700546 -0.2731429 0.8393102 -0.6278632 0.2864961 0.7236767 -0.6340026 0.3075843 0.7095299 -0.7898153 0.61057 0.05827802 0.1573854 0.4736545 0.8665341 0.7175788 0.2536689 -0.6486392 -0.04554021 -0.0588749 0.9972261 -0.06120014 -0.0396977 0.9973359 -0.03492689 0.2040776 0.9783315 0.00977391 -0.07028925 0.9974788 -0.09106099 0.02594667 0.9955072 -0.4979334 0.2947756 0.8155794 -0.6996008 0.4707235 0.537567 0.6019725 -0.3563368 0.7146001 0.4316877 -0.1586688 0.8879582 0.04775971 0.06377702 0.9968208 -0.06161618 0.02588838 0.9977642 0.08482682 -0.01185673 0.9963252 -0.001192927 6.83336e-4 0.9999991 0.08961254 -0.02340424 0.9957017 -0.5032775 0.2226175 0.8349571 0.7706753 -0.5282484 0.3563894 -0.422078 0.3080455 0.8526185 -0.9029181 0.4108474 -0.1262673 -0.8683406 0.4926454 0.0573157 0.4084823 -0.2187002 0.8861787 -9.72294e-4 -0.002450644 0.9999966 -0.4142181 0.2331903 0.8797986 -0.02404075 0.2022162 0.9790459 -0.08236294 0.081429 0.9932703 0.08503031 0.2174702 0.9723562 0.1155174 0.1090932 0.9872966 -0.0121932 0.02213019 0.9996808 -1.67174e-4 -1.98945e-4 1 0.003039002 -0.005034923 0.9999827 0.1511432 -0.04325485 0.9875651 0.04584759 0.2195809 0.9745165 0.04684603 0.1504783 0.9875028 0.07499796 0.08925873 0.9931809 -0.292208 -0.1403857 0.945995 0.004105448 -0.9761441 0.2170853 0.7512973 -0.3681573 -0.547734 0.8609747 -0.5054374 0.05706006 0.8617346 -0.5039522 0.0586999 -0.8643896 0.4977756 0.07106387 0.9862252 -0.1520575 -0.065104 -0.9060052 0.3917891 0.1601744 -0.498934 -0.8643996 -0.06227564 -0.9739807 -0.1915985 -0.1210441 -0.9754098 -0.2059131 -0.07858514 -0.9689965 -0.2414338 -0.0524922 -0.8628057 0.4981909 -0.08586126 -0.3188673 0.9438527 -0.08640557 -0.3208016 0.9425526 -0.09317147 0.03287214 0.9874686 -0.1543542 0.4717577 0.8810546 -0.03446221 0.7612066 0.6185635 -0.1947911 0.8632423 -0.4983808 -0.0801829 0.3169583 -0.9444548 -0.08684802 -0.2582365 0.1490893 -0.9545085 -0.3235659 0.1934507 -0.9262192 -0.5803042 0.3089409 -0.7535269 -0.0891745 0.05148512 -0.9946845 -0.5335114 0.2170585 -0.8174663 -0.6123657 0.3535535 -0.7071127 -0.6123623 0.3535569 -0.7071138 -0.6850104 0.4209583 -0.5946049 0.6123276 -0.3533869 -0.7072289 0.6121652 -0.3536991 -0.7072134 0.6272312 -0.3523811 -0.6945564 0.612419 -0.3535694 -0.7070584 0.5103979 -0.2124493 -0.8332822 0.3032628 -0.1870118 -0.9343758 0.2629973 -0.1517837 -0.9527823 0.08938598 -0.0516358 -0.9946577 0.088817 -0.05127882 -0.9947272 -0.9529806 0.002512454 0.3030213 -0.6796817 0.06379395 0.7307278 -0.6119334 0.3533002 0.7076134 -0.6125492 0.3539656 0.7067474 -0.6141415 0.3468545 0.708888 -0.8297388 0.5452967 0.1191018 -0.9322483 0.3597792 0.03836953 -0.8383986 0.5279176 0.1356131 0.9465171 -0.3225775 -0.007030785 0.3057769 -0.9520009 0.01395982 0.4806851 -0.5968894 0.64239 0.582538 -0.3679699 0.7247397 0.2152734 -0.06445914 -0.9744243 0.9871447 -0.03896093 0.1550078 0.1156532 0.2007119 -0.9727996 0.3509411 0.6084283 -0.7117974 0.8528697 -0.139806 -0.5030583 0.8858861 -0.09984314 -0.4530311 -0.1620795 0.7852295 -0.597616 0.8305801 -0.4797266 -0.2828415 0.8118072 -0.4734604 -0.3417667 -0.5256402 0.7188415 -0.4549389 0.5236583 -0.7231298 -0.4504057 0.5198844 -0.7297616 -0.4440364 -0.1141706 -0.1977495 -0.9735812 -0.1157701 -0.2008069 -0.9727662 -0.3501968 -0.6072662 -0.713155 -0.2092143 0.05668866 -0.9762253 -0.982082 0.02798527 0.1863649 -0.1502303 0.004013895 0.9886429 -0.8554503 -0.09280079 -0.5095026 -0.3815527 0.06701618 0.9219146 0.1213258 0.7224616 -0.680683 0.8593158 -0.5111749 -0.01663488 0.863782 -0.4987795 -0.07141304 -0.3671082 0.1882447 -0.9109312 -0.4007143 0.2798213 -0.8724265 -0.4278243 0.3070901 -0.8500954 -0.7021319 0.40272 -0.5872201 -0.4349944 -0.7681261 -0.4698535 -0.3161627 0.9249714 -0.2108776 0.8178846 0.2639074 -0.5112904 0.8933488 0.445026 -0.06228822 0.8685717 -0.4949762 -0.02412337 0.8651794 -0.4991124 -0.04849326 -0.8637512 0.4988588 -0.0712316 0.2504992 -0.1364256 -0.9584562 0.8319079 -0.4848521 -0.2699027 0.6663101 -0.4211603 -0.6153495 0.6913626 -0.4028691 -0.5997617 0.6643711 -0.3810032 -0.642999 -0.792833 -0.5828792 0.1779549 -0.6183043 0.35842 -0.6994533 -0.6582518 0.3634783 -0.6592329 -0.9482107 -0.174488 -0.2654248 -0.2521948 -0.6409944 0.7249303 -0.3720775 -0.5926204 0.7143945 0.3431446 0.590707 0.7302857 -0.2296349 0.1228609 0.9654911 -0.1306943 0.1049844 0.9858486 0.01882874 -0.1071909 0.9940602 0.02503359 0.07847267 0.996602 -0.4829696 0.274762 0.8314122 0.4316874 -0.9017911 -0.02047032 0.1639773 -0.9267938 0.3378826 -0.8533528 0.4924193 0.1712091 0.4308909 -0.253815 0.8659741 0.4229637 -0.2457146 0.8721961 0.8371472 -0.4944898 0.2338039 0.8400345 -0.4074151 0.3582669 -0.3673514 0.2118145 0.9056421 -0.5472154 0.2646985 0.794034 -0.8324777 0.4835623 0.2704598 -0.4623031 -0.8805533 0.1044119 0.4481629 0.8622724 0.2358739 -0.901827 0.3965238 0.1716892 0.8097627 -0.571982 0.1308482 0.4481643 -0.7017475 0.5538042 -0.4993007 -0.8662021 0.01981878 -3.68655e-4 -7.83379e-4 0.9999997 -0.4996675 -0.8650952 0.04407662 -0.4949482 -0.8684738 0.02792507 0.5005697 0.8576899 0.1174653 0.47022 0.8791894 0.07693654 -0.4623904 -0.8823485 0.08750057 -0.5048707 -0.8619027 0.04721599 0.4873989 0.8667382 0.1058637 0.8919275 -0.440021 0.1041486 0.8746173 -0.4699351 0.1191874 0.8908481 -0.4328845 0.1378433 -0.8908022 0.4497015 0.06511598 -0.7954345 0.5844725 0.1602371 -0.8693349 0.4923949 0.04247725 0.5057136 0.8621525 -0.0307728 0.5333102 0.8458257 0.01261925 0.4970692 0.859652 0.1179859 0.5031661 0.8629449 0.04636931 0.3034034 0.9510033 0.05949097 -0.4619672 -0.8681398 0.1814377 -0.4992908 -0.8653035 0.04425644 0.6994379 0.7110258 0.07231146 0.3098748 0.9471751 -0.08268618 0.4958347 0.8671804 0.04632848 0.4974811 0.8661233 0.04840677 -0.2905985 -0.6732429 0.679924 0.5245003 0.3125866 0.7919528 -0.1324391 0.1318162 0.9823871 0.1598627 -0.02605962 0.9867953 -0.006717681 0.004612147 0.9999669 0.0758565 -0.1345055 0.9880052 0.2512091 -0.1520045 0.9559229 0.1396283 0.1302149 0.9816049 -0.08780926 -0.1171949 0.9892194 -0.251481 0.152119 0.9558333 -0.2539845 0.1530057 0.9550294 0.06608402 -0.1157146 0.9910818 -4.12876e-4 1.00962e-4 1 -0.8646269 0.4994419 0.05457359 0.8612242 -0.5070479 0.03457611 0.8654249 -0.4978593 0.05635499 -0.4630818 -0.8762285 0.1333372 -0.5167147 -0.8508856 0.09486699 0.5321646 0.8439913 0.06693005 0.5090176 0.8594127 0.04807341 0.02210325 -0.01345348 0.9996652 0.5379033 0.8406729 0.06268417 -0.8612828 0.5071012 0.0322532 -0.5306138 -0.8466222 0.04098713 0.02274733 -0.01911026 0.9995586 -0.8634124 0.4944472 0.1002052 0.3596262 0.931141 0.06037825 -0.8938217 0.4351115 0.1084471 0.8650845 -0.4987807 0.05335414 -0.09267497 -0.004837214 0.9956847 0.138481 0.04358452 0.9894056 0.1359239 -0.1177489 0.9836971 0.6283521 0.1430814 0.7646577 0.6327962 -0.3851754 0.6717209 -0.4532617 0.2747313 0.8479838 -0.1741383 0.2527678 0.9517271 -0.6828446 -2.14921e-4 0.7305637 0.1920369 0.283554 0.9395313 -0.2872632 -0.406623 0.8672587 0.006309092 0.07617008 0.9970749 0.4402555 0.7294417 0.5235359 0.2336485 0.5589012 0.7956367 0.3685287 -0.4508756 0.8129563 -0.08460038 -0.9009941 0.4255027 0.2505018 0.9578032 0.1409321 -0.8170859 0.529804 0.2273288 -0.8869414 0.4561024 0.07283937 0.767054 -0.4428994 0.4641858 -0.32407 0.2696417 0.9067921 0.1648421 0.9281057 0.3338368 0.8817352 -0.4676072 -0.06234192 -0.6752291 0.4588944 0.5774788 -0.8353277 0.5464639 -0.06004202 0.8338879 -0.4809986 0.2706872 -0.6766188 0.3592278 0.6427615 0.6024465 -0.3785677 0.7026697 0.07340139 0.8174636 0.5712841 -0.8437662 0.5236514 -0.1176777 -0.9133803 0.3740999 0.1605792 0.8520925 0.4805072 0.2074879 0.06422299 0.9704759 0.2324911 0.361523 -0.1580585 0.9188682 -0.6186295 0.1176041 0.7768313 -0.8838913 0.4540644 0.1120789 0.1949576 -0.1699476 0.9659758 0.1104383 0.2557792 0.9604064 0.1034469 0.4248402 0.8993386 0.9444125 -0.3252458 0.04795998 0.8910256 -0.4405643 0.109438 -0.6835831 0.02577632 0.7294175 -0.5926465 0.2477132 0.7664257 -0.8377271 -0.2353605 0.4927666 -0.6725575 0.2447844 0.6983888 -0.184592 0.06313973 0.980785 -0.7388212 0.2307398 -0.6331686 0.676179 -0.1967768 0.7099725 0.6487713 -0.2800917 0.7075624 -0.07211893 0.2976962 0.9519328 -0.1647995 0.006142735 0.986308 0.2080651 0.2074597 0.9558606 -0.01649725 0.006047785 0.9998456 -0.06887388 0.05357408 0.9961858 -0.09265834 0.04740053 0.9945691 -0.07709997 -0.162583 0.983678 0.09314692 -0.01612508 0.9955219 0.2485287 0.6142148 0.7489818 0.6429696 -0.2878083 0.7097581 0.6257665 -0.2986482 0.7205731 0.4495668 -0.1633321 0.8781871 0.6590104 -0.2383697 0.7133619 -0.1644799 0.04478096 0.9853635 -0.065593 -0.04182606 0.9969695 0.1287885 -1.80647e-4 0.991672 0.1173029 0.130332 0.9845068 -0.02636849 -0.07536488 0.9968073 0.09622275 0.1899808 0.9770612 0.9539498 -0.269096 0.1325421 -0.3127624 0.1661216 0.9351916 -0.05641949 0.005306005 0.9983931 -0.002206623 0.002349019 0.9999949 -0.05858498 0.005358994 0.9982681 0.001844823 -9.07374e-4 0.999998 0.1303356 0.07999819 0.9882374 -0.1215949 -0.4952583 0.8601942 0.02387005 -0.01524335 0.9995989 0.007350921 0.002038419 0.999971 -0.01097035 9.75072e-4 0.9999395 0.01117128 -0.003440916 0.9999318 -0.073605 0.2557075 0.9639481 -0.06640523 0.1643434 0.9841654 0.1592795 0.2814643 0.94626 -0.06711196 0.1139701 0.9912148 -0.7740406 -0.6275199 0.08414357 -0.07960492 0.9948012 0.0635128 -0.6682182 0.2437813 -0.7028906 -0.8963233 0.4218416 0.1365816 -0.9639617 0.2614519 0.04920321 0.9459664 -0.2939479 0.1369027 2.08638e-7 0 -1 -1.30399e-7 0 -1 0.1675447 0.9799223 -0.108079 0.3299733 0.9393455 -0.09352928 0.3419016 0.9377885 -0.06046581 0.9144098 0.4011541 -0.05413389 0.9361687 -0.3408884 -0.08592623 0.4021253 -0.9141973 -0.05038517 0.4506251 -0.890229 -0.06655371 -0.2459703 -0.9691738 0.01416784 -0.5657846 -0.8227942 -0.05383044 -0.9259929 -0.3596267 -0.1149165 -0.9231271 -0.3771392 -0.07485014 -0.9364289 0.3418939 -0.07880121 -0.4770247 0.8742073 -0.09060412 -0.4763176 0.8748801 -0.08778649 0.2801821 -0.1019783 -0.9545148 0.09699261 -0.03531193 -0.9946585 -0.6644554 0.241813 -0.7071248 -0.6644418 0.241863 -0.7071205 -0.6554213 0.2724903 -0.7043948 -0.6645008 0.241873 -0.7070617 -0.4356407 0.1502522 -0.8874917 -0.2765055 0.09825468 -0.9559764 -0.2865983 0.1041947 -0.9523681 -0.1016754 0.03723353 -0.9941206 -0.0963748 0.03507792 -0.9947268 -0.5310577 0.1966015 -0.8242123 -0.9610484 -0.094837 0.2595996 0.9594328 0.1045688 0.2618284 0.6238347 -0.2498998 0.7405271 0.5864373 -0.2234112 0.7785748 -0.8959037 0.4404371 0.05806887 -0.9385705 0.3375937 0.07152676 -0.4296554 0.1623636 0.8882761 -0.2347164 0.01080811 -0.9720039 -0.07904481 -0.2177463 -0.9727994 -0.07763195 -0.2132869 -0.9739004 -0.8896588 -0.0552814 -0.4532674 0.3688639 -0.3482258 -0.8617878 0.2694555 -0.3276872 -0.9055467 0.6435971 -0.7197048 -0.2603995 -0.8831969 0.317114 -0.3455463 0.6426181 -0.6164621 -0.4549905 -0.6423507 0.6180015 -0.4532766 0.8959994 0.07509797 -0.437659 0.9536718 0.03953814 0.2982397 0.792999 0.5370728 -0.2875856 0.8944559 -0.3255565 -0.3065318 0.7540259 0.02221882 -0.6564689 0.8103356 -0.02981674 -0.585207 0.8561565 -0.3181457 -0.4071602 0.6665491 -0.7387062 -0.1001278 0.451222 -0.226357 -0.8632273 0.6353377 -0.2178006 -0.740884 0.2315563 0.1984751 -0.95236 0.6942211 -0.230623 -0.6818139 0.3729956 -0.8252096 -0.4241504 -0.9143728 0.3353543 -0.2268477 0.9372628 -0.341479 -0.07021749 -0.2703782 0.09084969 -0.9584581 -0.9034765 0.3330276 -0.2698569 -0.4603587 0.1943604 -0.8661951 -0.5005612 0.2527741 -0.8279757 -0.4683598 0.1227414 -0.8749707 0.6899694 0.6821467 0.2421122 0.06790816 -0.9828261 0.1715849 0.2828838 0.6461698 0.708831 0.1152667 -0.02479988 0.993025 0.2417637 -0.09648859 0.965526 -2.45209e-4 0.001030206 0.9999995 -0.06157141 0.03138601 0.9976091 -0.01908934 0.01018249 0.999766 -0.001530647 -0.004203498 0.9999901 -0.08044064 0.02592784 0.9964221 -0.006619215 0.006685674 0.9999558 0.5151414 -0.2098198 0.8310265 -0.3165395 0.4685979 0.8247539 0.9611626 -0.2633125 0.08266204 0.7766638 -0.6297487 0.01449465 -0.3908209 0.1222267 0.9123156 -0.8150812 -0.4687179 0.3405085 -0.5652262 0.6601495 0.494694 -0.8952999 0.4139538 0.1645613 0.9005506 -0.4347492 0.001349747 -0.4813069 -0.8483217 0.2206671 0.6832263 0.3285198 0.6521323 -0.9220103 0.3682568 0.1195163 0.3952227 0.9120115 -0.1097009 -0.3193776 -0.9466708 0.04257237 -0.3349735 -0.9319951 0.1384848 -0.3404036 -0.9379789 0.06573468 0.3389151 0.9397481 0.04483324 0.5258211 0.8451314 -0.09625518 0.093656 0.9933762 0.06657534 -0.8993258 0.4295967 0.08160805 0.8984852 -0.4086571 0.160386 0.2665299 -0.6902574 0.6726861 0.91086 -0.3994697 0.1037214 -3.2075e-4 -8.03843e-4 0.9999997 -5.14834e-4 -0.001903593 0.9999981 -0.341269 -0.9383995 0.05423903 0.3327931 0.879022 0.3414223 -0.1689885 -0.9727671 0.158642 -0.343099 -0.9380593 0.04824906 0.3234278 0.9135534 0.2466062 0.3419025 0.9387235 0.04360109 -0.3457904 -0.9371259 0.04716295 -0.09881746 0.2238008 0.9696124 0.1679294 0.7129976 0.68076 -0.2811977 -0.7405205 0.6103748 0.1143355 -0.1180404 0.9864046 0.07896494 -0.5849552 0.8072125 -0.09924745 0.1206744 0.9877185 0.2987477 -0.1061118 0.9484146 0.05463099 0.1298415 0.9900286 0.05711674 0.1035425 0.9929837 0.2737891 -0.1060299 0.9559274 0.2835949 -0.1076768 0.9528797 -0.0295034 0.05417335 0.9980956 0.08216094 0.2017083 0.9759935 -0.08823549 0.103528 0.9907051 0.09651267 -0.1173838 0.9883857 -0.294033 0.1101253 0.9494299 0.9382314 -0.3417158 0.05433624 -0.9361538 0.3498454 0.0349906 -0.9386681 0.3401008 0.05686551 0.3050184 0.943754 0.1276408 -0.3821851 -0.9183035 0.1032149 -0.9354655 0.3496003 0.05180776 0.9361649 -0.3498077 0.03506875 0.9583278 -0.265707 0.1049176 0.9388308 -0.3425635 0.03531312 0.04376572 0.997506 0.05537432 -0.9576771 0.28412 0.04615718 0.9381263 -0.3439221 0.04045814 -0.9351145 0.3400902 0.09949672 0.08869361 0.005578339 0.9960433 -0.1505861 0.09593671 0.983931 -0.6856131 -0.2415387 0.6867269 0.5156858 -0.1946523 0.8343732 -0.08592188 -0.0726487 0.9936497 -0.1860266 0.1642969 0.9687108 0.2843134 0.180919 0.9415064 0.2328212 -0.8735225 0.4274959 0.9515398 0.006809234 0.3074504 -0.01824194 -0.1525505 0.9881274 0.2178661 0.4540015 0.8639543 -0.3351246 -0.942071 0.01391762 -0.1491646 -0.7856912 0.6003661 -0.4021416 -0.9020584 0.1567571 -0.3161917 -0.7226691 0.6146318 -0.519787 -0.8111249 0.2681381 0.2798116 -0.3852431 0.8793709 -0.622219 0.2877376 -0.7280458 -0.2747959 0.7218177 0.6351901 0.1858682 -0.1307802 0.9738324 -0.6316974 0.5375412 -0.5585768 -0.008629083 -0.545712 0.8379285 0.1389932 0.2118314 0.9673719 -0.06304639 -0.08688187 0.9942217 -0.5705164 0.8201237 -0.04368442 -0.1802539 -0.08468073 0.9799683 0.954252 0.05692052 -0.2935358 -0.9265274 -0.3372232 0.1668159 -0.9099414 -0.411493 0.05177003 -0.9803129 0.04531013 0.1921815 0.6745766 0.2333632 0.7003485 0.2048857 0.07735133 0.9757246 -0.593383 -0.282199 0.7538304 -0.7078536 -0.2818456 0.6476932 -0.6599722 -0.2469465 0.7095451 0.05366837 -0.03815025 0.9978299 0.02261823 -8.80256e-4 0.9997438 -0.02677655 -0.02671802 0.9992843 -0.01903891 0.4027106 0.9151293 -0.08720552 -0.01224702 0.996115 -0.6654793 -0.2514159 0.7027998 -0.653393 -0.23269 0.7203701 0.6627342 0.2394518 0.7095395 0.4354004 -0.8329108 0.3415936 0.634413 0.2273665 0.7387996 0.05607384 -0.001652598 0.9984253 -0.0220232 0.001569449 0.9997562 0.5492179 -0.359003 0.7546367 -0.1906686 -0.6207854 0.7604414 -0.4734221 -0.1755311 0.8631688 0.9210394 0.3355901 0.1976509 0.9215599 0.3382989 0.1904767 0.3755721 0.135994 0.9167613 -0.1277844 -0.01257109 0.9917223 0.009483814 0.001336693 0.9999542 -0.478362 -0.184996 0.8584557 -0.1044088 -0.01158022 0.994467 -0.06648945 0.03500711 0.9971729 0.5503845 0.7344265 0.3971079 0.06450092 -0.7120493 0.6991605 0.1524687 -0.1663348 0.9742106 -0.1288341 -0.003020465 0.9916616 0.002162158 -5.60996e-4 0.9999975 -4.06313e-5 -5.55816e-4 1 -0.001001536 0.01613312 0.9998694 -0.02803105 0.005315721 0.9995929 0.02718287 0.1543218 0.9876467 -0.5661646 -0.5104209 0.6472467 -0.1299734 0.4898585 0.8620589 -0.06863695 -0.2973425 0.9523007 0.0868833 0.9864358 0.1392687 0.7229772 -0.6777864 0.1338267 0.6667806 0.2475106 -0.7029525 0.992421 -0.0635814 -0.1051573 0.9214968 0.3116137 0.2318199 -0.8928365 -0.4202752 0.1619011 0.07477366 -0.9969314 -0.02316933 -0.4676614 -0.8809326 -0.07246088 -0.457241 -0.8869783 -0.06480967 -0.938736 -0.3388797 -0.06273305 -0.9266988 0.3216179 -0.1943998 -0.8705009 0.4860265 0.07750201 -0.8003122 0.5919663 0.09527117 -0.3609174 0.9315884 -0.04337936 -0.3528757 0.934342 -0.04983985 -0.3405686 0.9362117 -0.08672297 0.2081718 0.9777064 0.02747309 0.1030825 0.9913994 -0.08063071 0.3326581 0.942421 0.03436809 0.9370136 0.3400229 -0.07993853 0.9274195 -0.3443245 -0.1460608 -0.3629583 -0.1165277 -0.9244905 -0.4936251 -0.1513591 -0.8564022 -0.6644569 -0.2418406 -0.707114 0.664339 0.2423194 -0.7070608 0.6669099 0.2404665 -0.705271 0.6645318 0.2418577 -0.7070378 0.05367863 -0.1164299 -0.9917473 0.430291 0.1649193 -0.8874973 0.3381784 0.1121062 -0.934381 0.2853473 0.1039105 -0.9527747 0.09700489 0.03528046 -0.9946585 0.09636837 0.03507554 -0.9947276 -0.6657721 -0.232896 0.7088773 -0.6415371 -0.2011282 0.7402551 -0.9557002 -0.2914003 0.04150933 -0.9485467 -0.315102 0.0311461 0.9023822 0.393274 0.1761875 0.9056871 0.3810998 0.1857255 0.8039669 -0.01997059 0.5943388 0.6433917 0.2880104 0.7092934 0.1694928 0.117553 -0.9784955 0.7789459 0.6142281 -0.1263619 -0.2457126 0.6805784 -0.6902452 -0.07764899 0.2133377 -0.973888 0.8804044 0.3247887 -0.3455439 -0.8885086 0.05919355 -0.4550262 -0.9049427 -0.3289867 -0.2699012 -0.6394077 -0.6276751 -0.4440518 0.07941508 -0.2177591 -0.9727663 0.2400944 -0.6586128 -0.7131507 0.2463262 -0.6819257 -0.688695 -0.1924294 -0.9459976 -0.2608822 -0.2293062 -0.9070418 -0.3531205 -0.2315132 -0.9389696 -0.2544363 -0.897747 -0.323934 -0.298525 -0.9115044 -0.3320952 -0.2426365 -0.5365326 0.09480434 -0.8385374 -0.223511 -0.9729255 -0.05881381 -0.9604724 0.2202737 0.1702127 -0.8437587 0.4793818 -0.2413803 0.9373393 0.3418245 -0.06746304 -0.390543 -0.1654894 -0.905588 -0.5211312 -0.1581478 -0.8386965 -0.4570984 -0.1997941 -0.8666853 -0.6557604 -0.2601279 -0.7087396 -0.6955069 -0.2852435 -0.6594743 0.374144 -0.8437505 -0.3848395 -0.4872459 -0.8651182 -0.1190049 0.3985862 0.907946 -0.129473 0.9160137 0.3308498 -0.2268421 0.1989035 0.9738509 -0.109781 0.416785 0.8789694 -0.2317392 0.7830902 -0.6193661 -0.05617302 -0.9374907 -0.341054 -0.06923538 0.2654781 0.104183 -0.9584713 0.906172 0.3256285 -0.2698488 0.6262708 0.1797508 -0.7586005 -0.006332337 -0.993857 0.1104912 -0.6853708 0.7086725 0.1674821 -0.683937 -0.253584 -0.6840508 0.2398801 -0.6315925 0.7372575 0.5404757 0.1902837 0.8195597 -0.003150939 -0.001783847 0.9999935 0.1766507 0.04192423 0.9833804 0.005342721 0.001172542 0.999985 0.2418443 0.09556722 0.9655973 0.008784472 0.003197252 0.9999563 -0.6725643 -0.2447979 0.6983776 0.8071793 -0.4360126 0.3979378 0.6659536 0.2423914 0.7055155 0.9046383 0.3292874 0.2705541 0.9633311 0.2656208 -0.03793156 0.08648067 0.9260652 0.3673207 -0.4692179 -0.7978841 0.3784387 0.9270932 0.3382328 0.1615448 -0.8949003 -0.3627012 0.2600026 -0.8970852 0.2542632 0.3613703 -0.2834585 0.9535651 0.1018084 0.1483575 -0.9536177 0.2619226 -0.6445783 0.7008386 0.3055226 -0.02190607 -0.998313 0.05377185 -0.2856349 -0.7190378 0.6335594 -0.9235975 -0.3637412 0.1210794 0.957985 0.2520329 0.1369102 0.273106 -0.9518918 -0.1389788 0.3414213 -0.9398511 0.010558 0.335583 -0.9416102 0.02746689 -0.3426522 0.9330543 0.10954 -0.3635639 0.9274448 0.08756351 -0.3389757 0.9174097 0.2084583 -0.3386733 0.9314758 0.1328657 0.3376531 -0.9401249 0.04642778 0.5335451 -0.8436707 0.05957621 0.09562772 -0.9926539 0.07411873 0.3531261 -0.9349469 -0.03429663 -0.9570205 -0.2351953 0.1696911 -0.4388607 0.8618299 -0.2542648 -0.341059 0.9398804 0.01742345 -3.87949e-4 1.94743e-4 1 -0.3073872 0.9504355 0.04675006 -0.3383477 0.9311552 0.135908 0.309475 -0.8882964 0.3393446 0.3312568 -0.9376583 0.1051955 0.3713279 -0.9284318 -0.01140463 -0.133597 0.9892457 0.05953919 -0.1686974 0.9728555 0.158409 0.3427283 -0.01891493 0.9392442 -0.2630482 0.7415632 0.6171627 3.02725e-7 0 1 0.06652402 -0.004547834 0.9977746 0.3007708 0.1148374 0.9467573 0.2243206 0.03402483 0.9739212 -0.009373426 0.1778838 0.9840069 -6.11418e-4 -0.0011155 0.9999992 0.03042852 -0.1380174 0.9899623 -0.002728044 -9.95242e-4 0.9999959 0.07040828 -0.2127365 0.9745696 0.1800578 0.1060163 0.9779263 0.3907499 0.08269071 0.9167752 -0.9383789 -0.3413013 0.05439245 0.9420058 0.3337651 0.03501504 0.3170185 -0.944397 0.08725649 -0.297665 0.949076 0.1032012 -0.2966183 0.9493243 0.1039281 0.9413324 0.3334917 0.05173772 0.9393644 0.3411887 0.03442203 -0.9370713 -0.3439698 0.05985194 -0.9419887 -0.3338042 0.03510218 0.3771739 -0.921788 0.08970373 -0.008303403 1.01214e-4 0.9999656 0.2186874 -0.9752842 0.03156864 0.3232852 -0.9442327 0.06253999 0.454994 -0.8867638 0.08142924 0.9342253 0.3393698 0.109779 -0.9338421 -0.3398688 0.1114825 -0.9348289 -0.337793 0.1095031 -0.07908463 0.9947508 0.06493508 -0.2541525 0.9581601 0.1316661 0.9366284 0.3483597 0.03705239 0.06596058 0.007370948 0.9977951 0.00139445 -0.004132568 0.9999905 0.2720776 0.04486304 0.961229 0.3722842 0.6794458 0.6322641 -0.494491 -0.1858962 0.8490709 -0.4202494 -0.5267522 0.7388658 0.2689204 -0.705429 0.6557833 0.08831053 -0.1017258 0.990885 0.08647429 -0.3515145 0.9321801 0.01081174 -0.1350259 0.9907831 0.03184115 -0.04579764 0.9984431 0.01190072 0.1526157 0.988214 -0.2008925 -0.6221668 0.7566709 -0.7741208 0.6290569 0.07088327 0.5172729 -0.4759683 0.7112545 0.6867456 0.4241486 0.5903207 -0.6598007 -0.05621808 0.7493348 -0.2265908 -0.08691179 -0.9701047 -0.746728 0.3027796 0.5922178 0.9260432 0.3762511 -0.02965611 -0.1939593 -0.09387636 -0.9765076 0.01496422 0.6905416 0.7231379 -0.7132033 0.0269376 0.7004395 -0.6406661 -0.6366095 0.4292732 0.9068318 -0.009811878 0.4213786 0.9221037 0.01236999 -0.3867452 0.05669862 0.01194757 -0.9983199 0.8224816 -0.004013419 0.5687775 0.9297749 -0.002322733 -0.3681215 -0.4500951 -0.009237587 -0.892933 -0.8840578 0.00936681 0.4672838 -0.9142739 0.0128507 0.4048928 -0.7750191 0.002679705 -0.6319321 -0.0304684 0.01005017 0.9994853 -0.907214 0.008631765 0.420581 -0.8362865 0 -0.5482929 -0.9983923 0 -0.05668216 0.7931865 0.0103228 0.6088915 -0.9670692 -0.01065254 0.2542905 0.9972701 0.005072712 -0.07366544 -0.5482743 -0.008332252 0.8362571 0.9983255 0.01157724 0.05667799 -0.8929504 0.00744915 0.4500934 -0.9068329 -0.009810566 0.4213764 -0.4220343 -0.009791851 0.9065271 -0.05667674 0.002682149 0.998389 0.4076284 -0.007440209 0.9131177 0.9071874 0.00702697 0.4206683 0.922618 -0.007999897 -0.3856322 0.4112932 0.0147742 -0.9113835 -0.354668 -0.004496693 -0.9349815 -0.9035796 0.01519316 -0.4281507 -0.9049244 -0.01478368 -0.4253156 -0.8366216 6.25065e-5 -0.5477813 0.001024186 0.997781 -0.06657314 -0.00287199 0.9980312 -0.06265419 -0.04856884 0.7411397 -0.6695917 -0.1722453 -0.9667447 -0.1890408 0.1502391 -0.9884046 -0.02201414 0.1344317 -0.9900004 -0.04274982 -9.94368e-7 -2.44344e-7 1 1.4397e-7 1.29202e-6 1 2.68992e-4 -5.13907e-5 1 2.55696e-7 0 1 1.98882e-7 0 1 1.39762e-4 4.58547e-5 1 -8.52669e-5 1.60683e-5 1 3.16578e-7 -2.57087e-6 1 5.39407e-6 7.36176e-7 1 1.90179e-7 0 1 -3.68193e-4 -1.42626e-4 1 -8.05331e-5 1.45634e-4 1 -2.07646e-7 0 1 -0.4780932 0.8651056 -0.1517213 -0.9590812 -0.2227131 0.1748209 -0.7855693 -0.5935573 0.1748447 0.5064809 -0.8404613 -0.1926189 0.9154071 -0.1388708 0.3778159 0.9072892 0.3898795 0.1575447 0.06019008 0.7689535 -0.6364651 -0.06078523 0.8703119 0.4887357 -0.9136213 0.1941909 0.357192 -0.9136564 -0.1941974 0.3570988 -0.01566374 -0.6049391 0.7961178 0.4746423 -0.8588524 0.1925803 0.796459 -0.561808 0.2236624 0.670592 -0.07048213 0.7384706 0.9134051 0.4066765 -0.01748174 0.6249943 0.6941199 0.3571833 -1.09432e-6 0 -1 -5.48092e-7 0 -1 -5.13103e-7 0 -1 -0.8195301 0.4922348 -0.2933861 -0.4922243 -0.81953 -0.2934042 0.3338294 -0.8958172 -0.293376 0.6894508 -0.6622568 -0.2933831 0.9085202 -0.2975145 -0.2933875 -0.8743453 0.2922325 0.3874541 -0.8346915 -0.2339952 0.4985343 -0.6894693 -0.6622378 0.2933823 -0.3338362 -0.8958129 0.2933815 0.4922408 -0.8195162 0.2934148 0.9174511 -0.09034657 0.3874546 -0.7403859 0.6407325 -0.2032012 -0.6472922 -0.7479701 -0.1468117 -0.7413696 -0.6702404 -0.03389775 0.2078018 -0.9683129 0.1385229 3.93745e-7 0 -1 -0.4056614 0.9139132 -0.01419889 -0.6657028 0.7440335 -0.05704468 -0.995132 0.08800613 -0.04435372 -0.974766 -0.2144159 -0.06210619 0.3158665 -0.9444885 -0.09038841 0.6730708 -0.7369658 -0.062105 0.9942227 -0.1063934 -0.01420789 0.9834126 0.03403621 -0.1781609 0.6812664 0.7053664 -0.1957913 0.03135484 0.9994965 -0.004882752 -0.6548085 0.755246 0.02880293 -0.8589349 0.5117114 0.01955413 -0.9793674 -0.1890562 0.07139551 -0.8184133 -0.5714991 0.05990451 -0.5160264 -0.8563001 0.02161198 -0.1230702 -0.9917302 0.03640192 0.6534074 -0.7536299 0.07141929 0.9429587 0.1820224 0.2787413 -0.09350883 0.8001978 -0.5924017 -0.5650795 0.5285193 -0.633524 -0.7512954 0.2586737 -0.60716 -0.7829125 0.04561585 -0.6204574 -0.7909945 -0.1394817 -0.5957118 -0.5493843 0.615307 -0.565309 -0.7469785 0.3506522 -0.5648596 -0.6073989 -0.4999517 -0.617345 -0.1812933 -0.7649171 -0.6180895 0.182911 -0.7717216 -0.6090891 0.7357391 -0.3542714 -0.5772172 -0.4166674 -0.7080175 -0.5701751 0.7396934 -0.3190747 -0.5924906 0.7907706 -0.1927793 -0.5809631 0.7822769 -0.1379039 -0.6074748 0.7764132 0.07906377 -0.6252452 0.3988605 0.6592775 -0.6373881 7.42911e-4 6.42358e-4 -0.9999995 -8.07001e-5 6.88929e-4 -0.9999998 8.80761e-7 0 -1 9.80124e-4 4.83145e-4 -0.9999994 -1.76416e-5 -6.23418e-6 -1 4.49738e-5 3.93386e-5 -1 0 0 -1 -3.25563e-7 -1.94128e-7 -1 0.001255154 -0.001553595 -0.999998 0.001399457 0.001328229 -0.9999982 0.01013571 -0.02205592 -0.9997054 -0.001204669 -0.001809537 -0.9999977 -7.95383e-6 3.0927e-5 -1 0.1472116 0.1313368 -0.9803467 0 -9.86684e-6 -1 0.00254786 -0.002014398 -0.9999948 0.009624361 0.00211209 -0.9999516 0.06008124 0.2340329 0.9703705 0 0 1 0.01913523 0.1800796 0.983466 -0.2607781 0.05916815 0.9635839 1.48697e-7 0 1 0.1485791 0.01477193 0.9887903 0.07521229 -0.1014277 0.9919958 0.8359401 -0.5471037 -0.04338085 0.9644965 -0.2625322 0.02869355 0.5598204 0.8252535 -0.07455134 -0.9516267 -0.3071112 0.009459972 0.4585168 0.8878542 -0.03843677 0.9794939 -0.1843901 -0.08119106 -0.973738 0.2264523 0.02353429 0.725005 0.6875235 0.0409789 0.02295404 -0.9968706 0.07564389 0.4121378 -0.9107355 -0.02652019 0.5825911 -0.8123324 0.02652782 0.2828419 0.9590907 -0.01206529 -0.7343462 -0.6786618 0.01240342 -0.755942 -0.6542477 0.02262055 0.7343876 -0.6786179 0.012353 0.7344384 0.678562 0.0124073 -0.2966626 -0.9549025 -0.01235163 0.7559928 0.6541892 0.02261525 -0.9774796 -0.2096745 0.02388393 -0.3071684 -0.9516083 -0.009452879 0 0 1 0 0 1 0 0 1 -1.61382e-7 -4.24256e-7 1 0 0 1 1.70572e-7 0 1 2.78699e-7 0 1 0 0 1 0 0 1 0 0 1 -4.98143e-7 0 1 0 0 1 -0.4265453 0.7718619 0.471475 -0.9667453 0.1866378 0.1748424 -0.9590896 -0.2227417 0.1747381 -0.7855808 -0.5935775 0.1747251 -0.4762321 -0.8617776 0.1747645 -0.04243296 -0.9248877 0.3778654 0.418451 -0.6822133 -0.5995697 0.7127375 -0.2948828 -0.636435 0.3905556 0.45767 -0.7987518 0.1045415 0.8839116 -0.4558196 -0.05812102 0.8323189 0.5512417 -0.800106 0.5643752 -0.2032518 -0.9136427 0.1942149 0.3571244 -0.9136281 -0.1942067 0.357166 -0.7556527 -0.5490062 0.3571851 0.4781028 -0.865113 -0.1516482 0.5977166 -0.4216203 0.681888 0.7316514 -0.1555284 0.6636996 0.5583292 0.4067449 0.7230679 0 0 -1 7.01286e-7 0 -1 0 0 -1 -8.79291e-7 0 -1 -0.3220909 0.8642105 -0.3865202 -0.9151508 0.2997099 -0.2695796 -0.4922221 -0.819535 -0.2933936 0.360694 -0.8534378 -0.3762232 0.8342362 -0.5406825 0.1082232 0.9589003 -0.08855569 -0.2695704 0.8958087 0.3338372 -0.2933931 0.1160548 0.9145446 -0.3874783 -0.1160539 0.9145498 0.3874667 -0.6387156 0.6762769 0.3670039 -0.9122948 0.1617397 0.3762426 -0.6894687 -0.6622372 0.2933853 0.4958222 -0.825529 0.2695595 0.7736358 0.5013971 0.3874128 0.3374978 0.7984834 0.4985174 -0.9482031 0.306014 0.08524268 -0.647289 -0.7479744 -0.1468035 0.7403703 -0.6407563 -0.2031825 0.6473174 0.7479417 -0.1468455 -0.2077664 0.968316 0.1385545 -0.7413693 -0.6702401 -0.03390908 0.7414874 0.6701136 -0.03382855 -0.9380357 -0.208219 -0.2770088 -0.6443995 -0.7642984 -0.02443838 0.6812598 0.705366 -0.1958166 0.1866382 0.9821045 -0.02523922 -0.08568561 0.9945161 0.05996423 -0.9631839 0.01804965 0.2682371 0.2907344 -0.9553131 0.05339014 0.5828814 -0.8118601 0.03365331 0.9302599 0.1796023 0.3199369 0.7890405 0.5509714 0.271746 0.5943902 0.8038361 0.0234127 -0.0940904 0.8052153 -0.5854703 -0.2674917 0.7348701 -0.6232288 -0.4407325 0.6701547 -0.5971998 -0.7351576 0.253063 -0.6288899 -0.6832059 0.4592112 -0.567763 -0.8130188 0.1654643 -0.5582313 -0.8050774 -0.1814993 -0.56472 -0.6035991 -0.4968444 -0.6235493 -0.533075 -0.6288573 -0.566012 -0.370791 -0.6795483 -0.633031 0.02966856 -0.7758062 -0.6302735 0.677069 -0.4582208 -0.5758571 -0.2756733 -0.7739759 -0.5700578 0.2641605 -0.7896037 -0.5538458 0.5429326 -0.6101326 -0.5770291 0.7745147 0.1424388 -0.6163102 0.1277099 0.7667101 -0.6291629 0.8435863 0.03304195 -0.5359762 0.2265758 0.7927271 -0.565904 6.49998e-4 7.03286e-4 -0.9999997 0 0 -1 -1.22487e-6 0 -1 9.79407e-4 4.82798e-4 -0.9999994 -1.30942e-5 -2.21269e-5 -1 -8.72356e-4 -6.25262e-4 -0.9999995 -8.2912e-4 -7.05439e-4 -0.9999995 1.60436e-7 0 -1 -1.80681e-7 0 -1 -8.49991e-7 0 -1 3.26026e-7 0 -1 0.001158118 -0.001519799 -0.9999982 0.001330316 0.001150727 -0.9999985 -1.80005e-7 0 -1 3.13414e-7 0 -1 -2.66743e-7 0 -1 2.53385e-5 2.72174e-5 -1 7.31199e-7 0 -1 -1.65252e-6 0 -1 -1.12555e-6 1.29067e-7 -1 0.1480097 0.2538576 0.9558501 0.09963887 0.2676941 0.9583382 -0.1723533 0.1902817 0.9664819 -0.01325333 -0.226916 0.9738243 -0.0213164 -0.2309081 0.972742 2.25734e-7 0 1 2.21059e-7 0 1 -2.29622e-7 0 1 0.1907167 -0.1277954 0.9732912 0.2070533 -0.2264026 0.9517725 7.13256e-7 0 1 -0.018022 0.9981724 -0.05768257 -0.9930433 -0.116874 -0.01433563 -0.2099015 -0.9776766 0.009471476 0.4121131 0.9104984 0.03399157 -0.6696615 0.7408127 0.05244022 0.5148919 -0.8558182 -0.04961514 0.7341893 -0.6784358 0.02628684 0.8015661 0.5977001 0.01570773 -0.9773181 0.2097 -0.02958613 0.7561056 0.6543574 -0.01098674 -0.3069983 -0.9512505 0.02957469 0.412192 -0.9108745 -0.02013891 0.9708067 0.2392304 -0.01741635 0.2828268 0.9590953 -0.01205688 -0.8124002 0.5827519 -0.02015239 0.2966459 -0.9549078 0.01234525 0.3072597 0.9516027 -0.006622076 -0.7343258 0.6786849 0.01235437 0.741649 -0.6703624 -0.02389538 -0.5977095 0.8015847 -0.01433336 0.6784232 0.7342007 0.02629351 -0.5827692 0.8125942 -0.008416295 0 0 1 -5.79653e-7 5.32536e-7 1 4.98765e-6 2.64347e-7 1 -2.43741e-7 0 1 7.45918e-5 -1.11047e-4 1 -2.62076e-7 0 1 -5.58077e-7 0 1 -1.56656e-4 1.45276e-4 1 5.04808e-6 -7.17647e-5 1 1.2888e-7 0 1 0 0 1 -1.04205e-4 -4.61194e-5 1 -2.87641e-5 5.17722e-5 1 0 0 1 1.29719e-7 0 1 2.1322e-7 0 1 4.87131e-5 -8.85693e-5 1 -0.3795897 0.428398 -0.819992 -0.9693534 0.1792297 0.1680199 -0.6450044 -0.7439365 0.1747223 0.9685275 0.1927291 0.1575122 0.7855796 0.59359 0.1746874 0.02578288 0.9956542 0.08948785 -0.619941 0.437315 0.6514821 -0.9797024 0.1615087 -0.1187352 -0.2886324 -0.8883322 0.3571515 0.06544244 -0.9366434 0.3441171 0.4746457 -0.8588393 0.1926305 0.5977408 -0.4216157 0.6818697 0.7316666 -0.1555233 0.663684 0.7556409 0.5490003 0.3572195 6.01715e-7 0 -1 9.97192e-7 0 -1 6.89161e-7 0 -1 -0.09034591 0.91745 -0.3874575 -0.3166691 0.8657928 0.3874578 -0.5062877 0.7708757 -0.3865537 -0.9532715 0.04667264 -0.2984881 0.9085192 -0.2975134 -0.2933915 0.9142073 0.1216881 -0.3865451 0.8314329 0.5460566 -0.1026726 0.45412 0.8357565 -0.3086848 -0.7732028 0.5172034 0.3669582 -0.5062972 -0.7708964 0.3864996 0.4423565 -0.8141097 0.3762262 0.9174512 -0.09034782 0.3874542 0.8357644 0.4541162 0.3086686 0.5460539 0.8314303 0.1027086 -0.6519268 -0.7532571 -0.08715069 0.6524041 0.7538791 -0.07768642 0.2535942 -0.964157 0.07804679 0.9311572 -0.3534482 0.08955824 0.6769989 0.7346365 -0.04451721 -0.3060315 0.9418148 -0.1390312 -0.4021636 0.9150932 0.02947729 -0.7593526 0.650243 -0.0238291 -0.9747678 -0.2144103 -0.06209605 -0.5055677 -0.8616639 -0.0440067 0.3158183 -0.9445047 -0.0903868 0.8768802 -0.4801805 -0.02253413 0.911047 0.4064427 -0.06926554 -0.08571743 0.9945147 0.05994439 -0.8589383 0.5117071 0.01951867 -0.9793692 -0.1890429 0.07140678 -0.5160387 -0.8562906 0.02169281 0.582875 -0.8118648 0.03365355 -0.2403745 0.771979 -0.5884458 -0.4360953 0.7250107 -0.5330858 -0.587247 0.5105787 -0.6280528 -0.7909924 -0.1394863 -0.5957136 -0.5614836 0.5943309 -0.5757664 -0.7469908 0.3506526 -0.5648429 -0.8050645 -0.1814725 -0.5647467 -0.6074009 -0.4999577 -0.6173382 -0.1812943 -0.7649328 -0.6180698 0.1829127 -0.7717506 -0.6090517 0.3519808 -0.7007997 -0.6204752 0.6461712 -0.4810463 -0.5925009 0.6770682 -0.4581976 -0.5758764 -0.08666718 -0.8255054 -0.5577003 0.7196563 -0.3104394 -0.6210654 0.7955067 -0.1949271 -0.5737356 0.667496 0.3853446 -0.6371489 0.4261843 0.6362397 -0.6430911 -0.05382698 0.8130806 -0.5796575 0.8190674 0.009976804 -0.5736107 0.7562708 0.3368129 -0.5609027 0.5517381 0.623534 -0.5538867 0.24837 0.7970117 -0.5505313 7.40471e-4 6.41381e-4 -0.9999995 0 0.001142621 -0.9999994 0.001625478 9.60062e-4 -0.9999982 -1.80822e-4 1.67122e-4 -1 -8.72882e-4 -6.26005e-4 -0.9999995 -8.30447e-4 -7.0632e-4 -0.9999995 -0.001028239 -9.21876e-4 -0.9999991 0.09707427 0.02987915 -0.9948286 0.003839969 0.002697229 -0.999989 0 0 -1 -2.86614e-7 0 -1 0.001637518 3.51367e-4 -0.9999986 -6.52956e-4 -7.44429e-4 -0.9999996 -0.001734673 -1.71651e-4 -0.9999986 0 0 -1 -0.002136409 0.002755343 -0.9999939 -3.76823e-4 -9.10186e-4 -0.9999996 0.1418216 -0.1690163 -0.9753564 0.1112307 0.1109095 -0.9875864 0 7.36014e-7 -1 -0.3930348 0.2974302 -0.8700915 1.57554e-6 -6.43103e-7 -1 0.08853137 -0.1762673 -0.9803531 3.85669e-7 0 1 -0.09821844 0.02837461 0.9947603 -0.03677141 0.1614688 0.9861925 7.86322e-7 0 1 -3.15977e-7 0 1 -5.7086e-7 0 1 0.1156799 -0.01984763 0.9930883 1.44213e-6 0 1 0.9472194 0.3070966 -0.09201836 -0.8003972 -0.5968807 -0.05565899 -0.9771215 -0.2096956 0.03551608 -0.1782788 -0.9828306 0.04754608 0.324172 -0.9456834 -0.0244041 0.481096 -0.8761892 0.02896797 0.9753202 0.2204495 -0.01235175 -0.6931543 0.7207026 0.01117658 -0.9938336 -0.1090294 -0.02018707 0.4123015 -0.9108247 -0.02014935 0.97078 0.2393386 -0.01741248 0.2826748 0.95914 -0.01206779 -0.7344569 -0.6785429 -0.01235628 0.9949385 0.09844332 0.02015483 -0.734408 0.6785958 0.01235675 0.7344143 -0.6785893 0.01234221 0.7343351 0.6786739 0.01240003 -0.3070753 0.9513853 -0.02388936 -0.2966381 -0.9549102 -0.01235258 -0.5823248 0.811987 0.03968852 -0.977467 -0.2097319 0.02389681 -0.3071017 -0.9516296 -0.00947082 -0.01745295 -0.01744973 -0.9996955 0.9995715 -5.10452e-4 -0.02926874 -0.2410673 -0.5866487 -0.7731299 0.7494596 0.00944817 0.6619827 -0.6206696 0.7823811 0.05146998 0.01745373 0.01745021 0.9996954 0.01744866 0.01744836 0.9996955 -0.9998477 3.00582e-4 0.01744985 -0.9998477 3.05415e-4 0.01745188 8.50914e-7 -0.9998477 0.01745456 4.74919e-7 -0.9998478 0.0174517 5.04281e-7 -0.9998478 0.0174511 5.70309e-7 -0.9998478 0.01745069 0.9998477 -3.05642e-4 -0.01745218 0.9998478 -3.0353e-4 -0.01744967 0.9998478 -3.04139e-4 -0.01745009 0.9998478 -3.01259e-4 -0.01744979 0.4795774 0.6297823 0.6110481 0.9998477 -3.03221e-4 -0.017452 0.9998477 -3.04251e-4 -0.01745295 0.9817741 0.1889496 -0.02043914 0.8944704 -0.4362518 -0.09801679 0.9998478 -3.04939e-4 -0.01744997 0.9998481 -3.04363e-4 -0.01742696 0.9998475 -3.03701e-4 -0.01746779 0.9998477 -3.03546e-4 -0.01744997 0.9998466 -3.03559e-4 -0.01751351 0.9998478 -3.04479e-4 -0.01744961 0.01745206 0.01744931 0.9996955 -0.9998478 3.04342e-4 0.01744866 -0.2751579 -0.01435965 0.9612918 -0.6495739 -0.02105027 0.760007 -0.9741867 0.04450035 0.2213147 -0.8968105 0.03733682 0.4408366 -0.6308732 -0.04317182 -0.774684 0.9410614 0.005905091 0.3381843 0.6760874 0.01286137 0.7367092 -0.9939852 0.03505021 -0.1037538 -0.4798521 0.01734602 -0.8771778 -0.01744073 0.008298516 -0.9998134 0.9904549 -0.002402365 -0.1378166 -0.1566146 0.02363836 -0.9873769 -0.3468159 0.01970642 -0.9377262 -0.9994678 -9.67157e-4 0.03260552 0.3764526 0.01123446 0.9263678 -0.9998477 6.76185e-4 0.01744008 0.2394694 0.03249806 0.97036 0.9084007 0.01011389 0.4179785 0.9998478 2.67048e-5 -0.01745235 0.3140429 -0.03329563 -0.9488248 0.2222354 0.01328772 -0.9749025 -0.4056056 -0.9043006 0.1331341 -0.4684811 -0.8112683 0.3498132 -0.1063297 -0.9825393 0.1526785 0.1646051 -0.9697801 0.1800882 0.1806917 -0.9809138 -0.07182288 -0.5905624 -0.729757 -0.3445155 -0.4254764 -0.826855 0.3678054 1.57838e-4 -0.9998479 0.0174455 2.39497e-6 -0.999848 0.01744091 0.592907 -0.7530404 -0.2852919 0.5503432 -0.8287518 -0.1014539 -6.90407e-4 -0.9998997 0.01415222 0.641793 -0.7668748 0.002185702 7.33345e-4 -0.9999016 0.01401042 -7.76534e-6 -0.9998474 0.01747423 9.74543e-5 -0.9998424 0.01775306 0.01522624 0.9996021 -0.02374243 5.14325e-4 0.9998475 -0.01746332 -0.7406749 -0.04691708 -0.6702235 -0.788136 0.1549068 -0.5956891 -0.8556267 -0.4740669 0.2077585 -0.4467662 -0.3158828 0.8370293 -0.7475528 0.4076388 0.5244001 0.4347987 -0.4550188 0.7771152 0.08023542 -0.4945199 -0.8654551 -1.10788e-6 -0.9998477 0.01745134 -7.39465e-6 -0.9998478 0.01745206 9.45504e-7 -0.9998478 0.01745063 5.84361e-6 -0.9998478 0.01745069 2.26063e-6 -0.9998478 0.01745283 -3.23622e-6 -0.9998477 0.01745462 -2.38678e-6 -0.9998478 0.01745009 -5.62717e-7 -0.9998497 0.01733899 -1.17771e-5 -0.9998477 0.01745194 0.01745456 0.01744979 0.9996954 -0.09221726 -0.01737797 -0.9955873 1.17248e-6 -0.9998478 0.01745241 0.9999565 -1.62236e-4 -0.009327411 0.9999566 -1.6182e-4 -0.009326756 0.01745671 0.01744973 0.9996954 -3.36406e-7 0.9998476 -0.01746141 -4.59057e-6 0.9998478 -0.01745223 -4.37062e-6 0.9998478 -0.01745235 -9.74092e-7 0.9998477 -0.01745223 1.30258e-7 0.9998478 -0.01745265 -1.94823e-7 0.9998477 -0.01745223 -1.3727e-6 0.9998478 -0.01745235 -0.9998906 0.01400017 -0.004785001 -0.9971359 0.001320481 0.07562035 -0.9966184 -0.06820482 0.04582601 -0.9998477 3.04009e-4 0.01745134 -0.9998627 -0.003763675 0.01614272 -0.9982237 0.04944944 0.03323 -0.9982088 -0.05861461 0.01198208 -0.999837 0.004942893 0.01737004 -0.9998477 3.03568e-4 0.01745724 -0.9996981 -1.01252e-4 -0.02456998 -0.9956613 -0.09262555 -0.008900701 -0.9998107 -0.003674805 0.01910775 -0.8652019 -0.499523 -0.04361814 0.8652022 0.4995232 -0.04361015 0.865198 0.4995312 -0.04360049 2.68124e-7 0 -1 0.4995265 -0.8652003 -0.04360926 -0.4995264 0.8652001 -0.04361569 0 0 -1 -0.05428683 0.01697158 -0.9983812 -0.3436699 -0.05497443 0.93748 -0.09571957 -0.9941586 0.04986554 -0.08201968 -0.9958312 0.03991329 -0.8871076 -0.4613363 0.01445561 -0.02910375 -0.0182684 0.9994094 -0.4645454 -0.2625743 0.8457259 -0.8654229 -0.4988894 0.04639548 -0.7435536 0.6666219 0.0523774 0.08989161 0.99474 0.04911154 -0.3039643 -0.952047 0.03481918 0.8915935 -0.4513449 0.03672808 0.4031505 0.2730982 -0.8734341 0.4134801 0.2842682 -0.8650005 0.4629389 0.2520666 -0.8497942 0.4566849 0.2519805 -0.8531968 0.430049 0.2319826 -0.8724917 0.117569 0.06541967 -0.9909076 0.4192165 0.2616529 -0.8693649 0.4237123 0.2653682 -0.866053 0.4306224 0.2578306 -0.8649207 0.4231329 0.2760823 -0.8629816 0.4947258 0.3049452 -0.8137905 0.42692 0.2839269 -0.8585597 0.4210401 0.286536 -0.8605942 0.4175573 0.2785395 -0.8649055 0.09457463 0.07379448 -0.992779 0.4351608 0.2672847 -0.8597639 0.4316943 0.257143 -0.864591 0.4329101 0.2545309 -0.8647561 0.438817 0.2486472 -0.8634896 0.4404766 0.2515901 -0.8617905 0.4372172 0.2405468 -0.8665902 0.4180148 0.2183863 -0.8817999 0.4831195 0.2573126 -0.8368906 -5.27447e-4 -4.69129e-4 -0.9999998 1.44478e-5 1.14301e-5 -1 4.15531e-5 3.09275e-5 -1 -0.002182126 -0.001252651 -0.9999969 -0.001497566 -9.58289e-4 -0.9999985 -6.11514e-5 -4.25589e-5 -1 -5.58919e-4 9.84613e-4 -0.9999994 0.0650447 0.02105975 -0.9976601 1.16214e-6 0 -1 -0.002857387 -0.001774251 -0.9999944 0.04782831 0.03738808 -0.9981556 -0.007040381 -0.0040645 -0.999967 0.05863046 0.03761196 -0.997571 -4.8902e-4 -7.17231e-4 -0.9999997 -6.53675e-7 0 -1 -4.53951e-7 0 -1 -0.003658831 -0.002511739 -0.9999902 0.02537447 0.02694982 -0.9993148 -0.001299917 -6.95941e-4 -0.9999989 0.04205203 0.01266127 -0.9990352 -0.001656115 -0.001795709 -0.9999971 0.01721698 -4.85913e-4 -0.9998517 0.1016002 0.04876154 -0.9936296 0 0 -1 0 0 -1 3.64657e-7 0 -1 -3.81057e-6 -3.26448e-6 -1 0.001123189 6.72694e-4 -0.9999992 -0.8660253 -0.5000003 0 0.3128421 -0.5570704 -0.7692869 0.3137496 -0.556243 -0.769516 0.3204733 -0.510949 -0.7976391 -0.03077983 -0.9671088 0.252494 -0.08698874 -0.8575314 0.5070236 0.8041315 0.3655284 0.4687872 0.0071913 0.003148078 0.9999692 -0.6622043 -0.3850104 0.6428473 -0.5991883 -0.3688924 0.7105575 -0.2714703 0.5023269 0.8209577 -0.353841 0.6225454 0.6980213 0.5586844 0.4054052 0.7235458 0.2675839 -0.4947519 0.8268128 0.3528183 -0.6196451 0.701113 -0.001343548 -0.5074878 0.861658 0.9040316 -0.425834 0.03731352 0.9091625 -0.4150761 0.03369796 0.4936257 -0.8693099 0.02518427 0.5101278 -0.8584797 0.05274796 -0.1042206 -0.9944338 0.01547783 0.001300394 -0.001580834 0.9999979 0.006130576 0.002997875 0.9999768 -0.02306282 0.05194228 0.9983838 -0.8103868 -0.5485773 0.2057577 -0.4060969 -0.3069769 0.8607268 0.6276617 -0.2626231 0.7328505 0.3623453 -0.1979233 0.9107867 0.6152915 0.3669386 0.6976909 0.8660919 0.4995163 0.01919227 -0.005961418 -0.003423869 0.9999765 0.6042819 0.3405346 0.720333 0.5752134 -0.2968087 0.7622559 0.5024027 -0.2145502 0.8375917 -0.7588565 -0.3794969 0.5292627 -0.561351 -0.30308 0.7700829 0.139957 0.4815868 0.8651511 0.09694719 0.9945893 0.03733128 0.8675772 0.4959218 0.03703188 -0.001373231 0.001212239 0.9999984 -0.09533208 -0.6639769 0.7416513 -0.0458315 -0.8739991 0.4837615 -0.0878126 -0.9955277 0.03483778 -0.8675931 -0.4959145 0.03675949 -0.8652663 -0.4998179 0.03868317 -0.9828053 0.1788879 0.0457493 -0.02949935 -0.01321083 0.9994775 0.1493002 -0.4131189 -0.8983553 -4.63164e-4 -0.01016163 -0.9999483 0.07369297 -0.1014306 -0.9921095 -0.8956342 -0.4428313 0.04171383 -0.8928129 -0.4486148 0.04037475 -0.8866892 0.4568936 0.0709275 -0.9931827 0.07833015 0.08632838 0.1907242 -0.2626581 -0.9458515 0.01445984 -0.006525814 -0.9998742 0.8335649 0.5497676 0.05408477 0.9936636 0.01294624 0.1116476 0.5680505 -0.8182044 0.08865755 0.3127834 0.9459312 0.08591097 0.03168976 0.9977173 0.05963349 7.51813e-4 -0.02730602 -0.9996269 -2.57785e-4 -2.81412e-4 -1 0.3168561 -0.5642837 -0.7623558 0.3317348 -0.5418919 -0.7722081 0.4502831 0.888428 0.08911126 0.5584028 0.8011205 0.2153886 -0.8843386 0.442689 -0.148229 -0.5977793 -0.7873621 0.1507341 0.279622 -0.959333 0.03862452 0.9553865 -0.2953577 -8.01668e-4 0.890924 -0.428191 -0.1513507 -0.2182129 -0.9758976 0.002680122 0.4997277 -0.8661801 -0.002105116 0.5000074 -0.8660206 -0.001075685 0.4304019 0.8237016 0.3691477 0.9658115 -0.2592441 9.58867e-4 0.8654034 0.499219 -0.04309761 0.8651984 0.49952 -0.04372251 0.8651894 0.4995439 -0.04362803 -0.8650663 -0.4997382 -0.04384148 -0.8651813 -0.4995588 -0.04361796 -0.8652027 -0.49952 -0.04363697 -0.8652005 -0.4995235 -0.04364103 1.76562e-5 1.01829e-5 -1 3.75484e-7 -3.41588e-6 -1 0 -1.81864e-7 -1 -2.4151e-6 -5.42514e-7 -1 -0.9762066 -0.1847064 -0.1135969 -0.4656106 0.8065087 -0.3643494 -0.9194383 -0.3879415 -0.06430113 0.5553138 0.812564 -0.177106 -7.20252e-4 2.00672e-4 -0.9999998 -3.89299e-5 3.313e-4 -1 7.99518e-5 2.50834e-4 -1 1.34971e-6 0 -1 -9.77819e-7 0 -1 -1.2381e-6 0 -1 2.01123e-6 0 -1 0.866025 0.5000007 -2.99795e-5 -0.2543277 0.9655598 -0.05488032 0.4709609 -0.641804 -0.6052137 -0.7553625 0.6549364 -0.02204322 0 0 -1 1.59166e-7 0 -1 0.04945129 -0.09056288 -0.9946622 0.831587 0.4807376 -0.2781271 0.9987782 -0.01846754 -0.04583835 -0.2527237 0.9283735 -0.2724947 0.6707068 -0.7417227 0 0.7071012 -0.7071086 -0.002331554 0.9659181 -0.2588114 -0.004359364 -0.4156163 0.7060316 -0.5733956 -0.4065449 0.671337 -0.6196999 0.04874873 -0.06524682 -0.9966778 0.4890905 -0.8471307 -0.2077501 0.4999997 -0.8660256 0 0.1848055 -0.3748268 -0.9084888 0.3898828 -0.6226888 -0.6784174 0.4775734 -0.8639045 -0.1599775 0.3280444 -0.6485265 -0.6868773 -0.8660246 -0.5000014 1.10968e-6 -0.8660254 -0.5 9.33916e-7 -0.8660259 -0.4999994 -7.38166e-6 -0.8660255 -0.4999998 5.61764e-6 0.8660258 0.4999995 5.78299e-6 0.9999918 -0.00323528 -0.002460122 0.9998773 -0.01565819 6.10579e-4 1 1.41834e-4 -1.23278e-5 -0.5000205 -0.8660136 1.79687e-6 -0.4694256 0.8828939 0.01175117 -0.4974977 0.8664485 0.04198998 -0.9992873 0.005142688 -0.03739887 -0.0276274 0.8460103 0.5324503 0.5026379 0.7772864 0.3783929 0.4756444 0.3345293 0.8135433 0.4619184 0.3362241 0.8207221 0.4620442 0.3442832 0.8173031 0.4969075 0.2869096 0.8190029 0.2761071 0.1747813 0.9451013 0.4244721 0.3861519 0.8189691 0.5015227 0.2896698 0.8152095 0.5004662 0.2895691 0.8158942 0.4007938 0.2370312 0.8849749 0.4471718 0.2494508 0.8589597 0.4955999 0.2862128 0.8200384 0.4408315 0.264189 0.8578297 0.4996527 0.2961451 0.8140304 0.4967222 0.286783 0.8191597 0.5206128 0.3099597 0.7955422 0.4875007 0.1583272 0.8586476 0.5096047 0.3009768 0.8060497 0.5036665 0.3146809 0.8045472 0.03640675 0.1219458 0.9918689 0.445989 0.250096 0.859387 0.3814753 0.4129514 0.8270115 0.5194313 0.2871739 0.804812 0.2702383 0.1160151 0.9557781 0.3696845 0.3925851 0.8421463 0.6539278 0.2711856 0.7062839 0.4905192 0.3659754 0.7908559 0.06930983 0.8529446 0.5173796 0.001746237 -0.04386466 0.999036 0.8178321 0.3791877 0.4328595 0.5992912 -0.2132309 0.7716104 -0.4524101 -0.2872787 0.8442726 0.6924501 -0.2742691 0.6673001 0.3150618 -0.4472659 0.8370719 -0.2251325 -0.9537003 0.199427 -0.8719237 -0.489577 0.007964134 -0.8631264 -0.5033313 0.04087227 -0.4834218 0.874127 0.04696172 0.8363988 -0.1009914 0.5387371 0.6147705 -0.702431 0.3586753 -0.316821 -0.2551753 0.9135153 0.3222524 0.1479433 0.935022 0.5988414 0.3594908 0.7156503 0.2842935 0.9566277 -0.06356722 0.1039381 0.1851683 0.9771948 -0.01447057 5.88611e-5 0.9998953 -0.001099109 -6.0914e-4 0.9999992 0.02903324 0.01671302 0.9994388 0.003368616 0.002037167 0.9999923 0.004635751 0.003019511 0.9999847 0.01571339 0.007914245 0.9998453 0.002391457 -8.32847e-5 0.9999972 -0.003073394 -0.0018031 0.9999938 -2.89696e-5 -7.10889e-4 0.9999998 0.005564689 0.002066493 0.9999824 0.002820312 0.001378655 0.9999952 5.64199e-4 5.91555e-4 0.9999997 2.69328e-4 4.22396e-4 0.9999999 -0.003294944 -0.001978695 0.9999926 -0.00268054 -0.001256108 0.9999957 -0.00145775 -0.00120449 0.9999983 -0.00280857 -0.001584708 0.9999948 -0.003409266 -0.001986503 0.9999923 0.1436618 0.1046166 0.9840816 -2.4826e-4 -8.47736e-5 1 -9.5106e-5 -2.96317e-4 1 -0.001525223 -8.71589e-4 0.9999985 -0.001169979 -5.45279e-4 0.9999992 -6.16391e-4 -2.76097e-4 0.9999998 -7.62605e-5 3.05388e-4 1 0.2291361 0.1213284 0.9658035 -0.002013564 -0.001790821 0.9999964 -0.001276135 -0.001040816 0.9999987 -0.002262413 -0.001281499 0.9999967 -2.94858e-4 -1.53334e-4 1 -0.008010506 -0.01555746 0.9998469 0.03507226 0.02737462 0.9990099 0.04648673 0.02634793 0.9985714 0.413168 0.0941509 0.9057747 -0.1004568 -0.02133905 0.9947125 -5.56385e-4 -3.36502e-4 0.9999998 -0.07759273 -0.1523292 0.9852793 2.90879e-4 -1.20416e-4 1 -1.78524e-4 -3.41005e-4 1 0.002486824 0.001747846 0.9999955 -0.06852895 0.005150198 0.9976359 -0.2294483 -0.2244805 0.9470808 0.002063333 0.001384198 0.999997 0.002268791 0.001270771 0.9999967 0.002443492 0.001339256 0.9999961 0.001808404 0.001107275 0.9999978 -0.08570969 -0.09353727 0.9919198 0.001973211 0.001045286 0.9999976 -0.1916908 -0.05543947 0.9798884 0.0020262 9.35533e-4 0.9999975 0.002680242 0.00179857 0.9999949 -4.69442e-4 1.38204e-6 0.9999999 0.002835035 0.00166428 0.9999946 -0.1319829 -0.1240636 0.9834576 0.00284636 0.001646399 0.9999947 -4.72961e-4 2.21445e-4 1 -4.2761e-5 3.23617e-5 1 -9.94289e-4 2.65645e-4 0.9999995 4.19639e-4 2.36323e-4 1 0.001420319 0.001757681 0.9999974 5.59357e-4 3.45159e-4 0.9999999 -6.98248e-5 -1.51566e-4 1 1.0897e-4 4.48938e-5 1 -0.0613628 -0.0301811 0.9976592 6.18855e-4 4.77757e-4 0.9999998 -0.0627132 -0.008580386 0.9979948 -0.01142781 0.006369888 0.9999144 2.36201e-4 4.31076e-5 1 -0.03320908 -0.01955449 0.9992572 7.35904e-5 -8.80913e-4 0.9999997 5.49633e-4 2.23611e-4 0.9999999 -0.008009731 -0.02048003 0.9997583 0.003223001 0.001775205 0.9999932 1.60121e-4 -2.08653e-5 1 3.71616e-4 -5.95472e-4 0.9999998 -0.03371274 -0.01955217 0.9992403 0.002017796 0.001116275 0.9999974 1.13918e-4 -2.41195e-4 1 5.42475e-4 3.11819e-4 0.9999998 -9.81788e-6 2.93296e-4 1 6.35912e-5 1.72205e-4 1 -4.8126e-5 -1.18256e-4 1 -0.002208173 3.43545e-5 0.9999976 -4.27828e-4 -2.49613e-4 1 -3.18668e-5 3.29207e-4 1 7.70623e-5 4.44691e-5 1 -2.99346e-4 -1.72913e-4 1 -2.73142e-4 -8.46231e-5 1 -0.002326607 -0.001382946 0.9999964 0.002829074 0.001300454 0.9999952 2.74843e-6 1.67874e-4 1 -6.90227e-4 -4.04323e-4 0.9999997 6.73261e-4 3.63649e-4 0.9999997 0.01262795 -0.01398497 0.9998225 0.8626315 -0.4094271 0.297046 -0.8660264 -0.4999985 3.35761e-5 -0.8660261 -0.4999991 6.69882e-5 -0.8574203 -0.4961318 0.1366886 -0.6235072 -0.359009 0.6945153 -0.7226693 -0.4129455 0.554279 0.5484318 0.3155912 0.7743544 0.2108114 0.1239252 0.9696397 0.8606592 0.5002758 0.09481513 0.865198 0.4995301 -0.04361426 0.8652032 0.4995205 -0.04362177 0.8652004 0.4995257 -0.0436182 0.8652017 0.4995235 -0.04361522 0.8651993 0.4995273 -0.04361832 0.8652011 0.4995248 -0.04361534 0.8652011 0.4995241 -0.04362171 0.8652034 0.4995198 -0.0436235 0.8652046 0.4995193 -0.04360622 0.8651999 0.4995268 -0.0436142 0.8651987 0.4995269 -0.04363864 0.8652033 0.4995189 -0.04363793 -0.8652002 -0.4995259 -0.04361933 -0.8652013 -0.4995237 -0.04362124 -0.8652009 -0.4995244 -0.043621 -0.8651998 -0.4995267 -0.0436173 -0.8652011 -0.4995242 -0.04362076 -0.8651989 -0.4995282 -0.04361724 -0.8651993 -0.4995273 -0.04361945 -0.8652048 -0.4995172 -0.04362791 -0.8651953 -0.4995346 -0.04361563 -0.8652011 -0.4995244 -0.04361921 -0.8652015 -0.4995245 -0.04360955 -0.8652014 -0.4995245 -0.04361063 -0.8651957 -0.4995339 -0.04361557 -0.8652024 -0.4995232 -0.04360622 -0.8651996 -0.4995276 -0.04361063 0.8651996 0.4995256 -0.04363447 -0.8651992 -0.4995295 -0.04359775 0 0 -1 -0.50154 0.8640292 -0.0437203 -0.499581 0.8653087 -0.04074066 -0.00138998 -8.02604e-4 -0.9999988 0.4995335 -0.8651961 -0.04361432 0.4995355 -0.8651938 -0.04363542 0.4995191 -0.865204 -0.04362154 0.02177435 -0.03771406 -0.9990514 0.05428636 -0.01697087 -0.9983812 -2.68128e-7 0 -1 0.4995237 -0.8652019 -0.04360902 -0.499524 0.8652005 -0.04363447 -0.4995188 0.8652036 -0.04363435 0.4995331 -0.8651953 -0.04363524 0.4995229 -0.8652012 -0.04363387 0 0 -1 -0.4995272 0.8651996 -0.04361647 -0.4995203 0.8652039 -0.04360997 2.17892e-7 0 -1 -2.17888e-7 0 -1 0.49952 -0.8652046 -0.04359704 0 0 -1 0.4995145 -0.8652063 -0.04362839 0.4995303 -0.8651978 -0.04361516 -0.008852303 -0.05363541 -0.9985213 -0.4995288 0.865198 -0.04362958 0.4995213 -0.8652036 -0.0436033 0 0 -1 -0.4995071 0.8652111 -0.04361951 -0.4995265 0.8651988 -0.04364079 -0.4995263 0.8651991 -0.04363465 0.4995351 -0.8651947 -0.04362165 -0.008852243 -0.05363506 -0.9985215 -0.4995265 0.8651996 -0.04362416 -0.4995259 0.8652004 -0.04361635 0.4995106 -0.8652085 -0.04363012 0.4995257 -0.8652005 -0.04361569 0.4995229 -0.8652024 -0.04360955 0.02994447 0.01728868 -0.9994021 0.02177482 -0.0377143 -0.9990514 -0.4995095 0.8652099 -0.0436145 -4.35788e-7 0 -1 0.4995285 -0.8651979 -0.04363483 0.4995257 -0.8651989 -0.04364639 0.4995208 -0.8652034 -0.04361391 -0.4995259 0.8652001 -0.04361921 0.4995244 -0.865201 -0.04362189 0.4995237 -0.8652012 -0.04362183 -0.008851766 -0.0536347 -0.9985215 0.02994459 0.01728862 -0.9994021 0.02177459 -0.03771454 -0.9990514 -0.4995236 0.8652014 -0.04361903 -0.4995245 0.8652008 -0.04362255 -0.4995206 0.8652033 -0.04361915 0.4995249 -0.865201 -0.04361391 0.4995221 -0.8652024 -0.04361909 -0.008851706 -0.05363434 -0.9985214 0.02994465 0.01728862 -0.9994021 -0.4995248 0.8652006 -0.04362243 0.4995237 -0.8652014 -0.04361879 0.4995208 -0.8652033 -0.04361653 -0.008851766 -0.0536344 -0.9985214 0.02177464 -0.0377146 -0.9990513 0.4995231 -0.8652019 -0.04361563 0.4995247 -0.8652009 -0.04361873 0.02177464 -0.03771471 -0.9990513 4.35787e-7 0 -1 -2.17894e-7 0 -1 6.62859e-5 -4.47006e-5 -1 0.4995259 -0.8652001 -0.04361921 -0.4995244 0.8652009 -0.04362183 -0.4995247 0.8652008 -0.04362189 0.02994459 0.01728844 -0.9994021 0.02994441 0.01728856 -0.9994021 0 0 -1 0 0 -1 0.8002336 0.4620189 -0.3823151 0.8002549 0.4620251 -0.3822631 0.8002505 0.4620254 -0.3822715 0.8002247 0.462013 -0.3823408 0.8003293 0.4620626 -0.3820617 0.8001073 0.4619565 -0.3826545 0.8003806 0.4620875 -0.3819244 0.8002465 0.4620227 -0.3822834 0.8002707 0.4620421 -0.382209 0.8002437 0.4620202 -0.3822922 0.8002436 0.4620192 -0.3822938 0.800244 0.4620197 -0.3822923 0.8002489 0.4620254 -0.3822752 0.800261 0.4620331 -0.3822405 0.8002331 0.4620128 -0.3823233 0.800215 0.4620008 -0.3823758 0.8002959 0.4620566 -0.3821389 0.800239 0.4620177 -0.3823053 0.8002144 0.4619992 -0.3823789 -0.8002461 -0.462021 -0.3822862 -0.8002598 -0.4620393 -0.3822354 -0.8002509 -0.4620248 -0.3822717 -0.8002533 -0.4620267 -0.3822643 -0.8003279 -0.4620839 -0.382039 -0.8002029 -0.461991 -0.3824132 -0.8002087 -0.4620019 -0.3823879 -0.8002898 -0.4620438 -0.3821672 -0.8002437 -0.4620199 -0.3822925 -0.800208 -0.4620059 -0.3823844 -0.8003293 -0.4620603 -0.3820645 -0.8002158 -0.4620075 -0.3823662 -0.8002562 -0.4620265 -0.3822588 -0.800238 -0.4620193 -0.3823055 -0.8002492 -0.4620228 -0.3822778 -0.8002469 -0.4620233 -0.3822818 -0.8002453 -0.4620215 -0.3822877 -0.8002478 -0.4620234 -0.3822798 -0.8002492 -0.4620238 -0.3822765 0.4995173 -0.8652059 -0.04360318 0.4995183 -0.8652042 -0.04362523 0.004040837 0.003026187 -0.9999873 7.11511e-4 -0.001232445 -0.9999991 0.6199546 -0.5242618 -0.5837858 0.6427026 -0.5087205 -0.5728324 0.7245019 -0.3781132 -0.5763051 0.7624885 -0.3097543 -0.5680348 0.8018555 -0.177336 -0.5705961 0.8058221 0.1306326 -0.577569 0.7909134 0.2214253 -0.5704621 0.747872 0.3411973 -0.5694487 0.7900775 0.230072 -0.568194 0.576843 0.5872074 -0.5678376 0.5706853 0.5913041 -0.5698052 0.1742075 0.7954691 -0.5804144 -0.007771849 0.8175898 -0.5757489 -0.1217524 0.8128577 -0.5695952 -0.2705995 0.7734899 -0.5731399 -0.5220644 0.6556079 -0.545552 -0.6413406 0.5160776 -0.5677553 -0.6200793 0.5241774 -0.5837293 -0.5820684 0.5777853 -0.5721544 -0.5489509 0.6083183 -0.573238 -0.8049464 -0.1297789 -0.5789809 -0.795439 -0.2000694 -0.5720571 -0.7509803 -0.345576 -0.5626773 -0.6856264 -0.4498066 -0.5723552 -0.4870283 -0.6630966 -0.5684246 -0.3758295 -0.7324765 -0.5676533 -0.2670133 -0.769407 -0.5802732 -0.1920672 -0.7816833 -0.5933645 -0.1225301 -0.8142067 -0.567498 0.007818341 -0.8192971 -0.5733159 0.1564341 -0.8091144 -0.5664471 -0.7827973 0.249021 -0.570278 0.2992076 -0.7779935 -0.5524499 0.227899 -0.802075 -0.5520306 0.03311872 -0.8212488 -0.5696083 -0.1205166 -0.8139926 -0.5682358 -0.3763979 -0.7322791 -0.5675315 0.8240737 0.0590052 -0.5634014 0.838561 -0.1217837 -0.5310218 -0.6766293 -0.7363178 -0.002999007 -0.5145568 -0.8574513 -0.002955615 -0.1347276 -0.9908786 -0.002854645 0.06751894 -0.9977141 -0.002814352 0.2669789 -0.9636982 -0.002868413 0.4554784 -0.8902424 -0.002814114 0.6253757 -0.7803194 -0.002648532 0.7696553 -0.6384547 -0.002527475 0.9964306 -0.08438032 -0.00243771 0.948941 0.3154454 -0.002314746 0.866021 0.5000027 -0.002253413 0.4251739 0.9051094 -0.002061903 0.2342626 0.9721714 -0.002005815 0.03377407 0.9994277 -0.001930356 -0.1681032 0.9857683 -0.001525223 -0.3630923 0.9317458 -0.003740429 -0.4999709 0.8660412 0.001411437 -0.3724198 0.9280625 -0.001881897 -0.3851602 -0.9228447 0.003068745 0.8853539 0.4649116 0.002406656 0.6280934 0.7781347 0.002273142 -0.1618178 0.9867679 0.0102086 -0.2790639 0.9602725 3.42071e-4 -0.7729333 0.6343976 0.01066887 -0.9254808 0.378781 -0.003209471 -0.9827888 0.1847035 -0.003313958 -0.9759842 -0.2178196 -0.003116548 -0.9121608 -0.4098201 -0.003194034 -0.8457291 -0.533603 0.003206491 -0.9682002 0.2501545 0.003354668 -0.9880283 -0.1542382 0.003271758 -0.7009359 0.7132071 -0.004961907 0.2363507 0.1361675 -0.9620795 0.5532872 0.3277087 -0.7658201 -0.2835287 -0.1639308 0.9448482 0.1848754 -0.3534733 0.9169939 0.01975566 0.01219952 0.9997304 0.1005637 0.279874 0.9547553 -0.409032 0.507973 0.7580609 0.8348135 0.4965865 0.2376728 0.3219805 0.9467453 0.001437783 0.05713146 0.9965735 0.05981236 -0.6044828 -0.5089353 0.6128504 -0.8221541 -0.05536234 0.5665668 -0.8091681 -0.3327323 0.4842896 0.6666677 0.7154552 0.2089928 0.4943267 0.869275 0.001464068 -0.1384199 0.9900256 0.02625143 -0.1558015 0.9876044 0.01906281 6.79402e-4 -0.008941948 0.9999599 -0.6120845 -0.07573699 0.7871572 -0.8476591 0.5144765 0.1295685 0.2115586 0.9772832 0.0126689 0.5319325 0.8392036 -0.1130717 -0.2586302 0.7706745 0.5823842 0.0713306 -0.4593353 0.8853943 0.06043708 -0.9980908 -0.01273691 -0.3787707 -0.9247781 0.036309 -0.6954041 -0.3924767 0.601976 -0.5070974 -0.2802854 0.8150414 -0.858621 -0.5100885 0.05079144 -0.8746015 -0.47987 -0.06926077 -0.8654813 -0.5004819 -0.02145075 -0.03276395 -0.9952028 0.09218466 -0.5066042 -0.8613673 -0.03740054 -0.6161654 -0.7870185 0.03069645 -0.415332 -0.8960168 -0.1570135 0.07195675 -0.9641774 0.255312 0.65074 0.737888 -0.1790501 -0.8133485 0.554173 -0.1770776 0.9806098 0.09698569 0.1702888 -0.238031 -0.9380844 -0.251672 -0.2148232 -0.9761242 0.03213411 -0.9950177 -0.0974816 -0.02091205 -0.02608287 0.9953258 0.09298574 -0.7214245 -0.6794067 0.1339898 -0.6026254 -0.7733337 0.1969716 -0.7347487 0.678085 0.01857692 0.8006064 -0.5811415 0.1459593 0.5166819 0.8242423 0.2316558 0.9380978 -0.3216162 0.1285907 0.02142739 -0.7592808 0.6504104 -0.9205703 0.3282372 0.2116852 0.74605 0.6588435 0.09661704 -0.608962 0.7765204 -0.1618066 0.6973401 -0.7163458 -0.0237801 -0.8557778 0.0217477 -0.5168862 -0.6060442 -0.7521904 0.2586892 0.3048502 0.927255 0.2174045 -0.9493489 -0.2626979 -0.1724142 0.4996944 -0.8659948 0.01894235 -0.9667207 -0.2382689 -0.09316188 0.4183845 0.6993108 0.5795851 0.603144 0.6463292 0.4674142 0.6766228 0.461427 0.5738176 -9.98336e-4 -6.33387e-4 -0.9999994 -3.05316e-6 -1.72879e-6 -1 0 2.02953e-6 -1 -8.60927e-6 -5.38493e-6 -1 -1.18695e-4 -3.95066e-5 -1 -6.94459e-4 -4.04139e-4 -0.9999997 -0.01200902 -0.02279102 -0.9996682 0.03155004 -0.02561444 -0.999174 0.02155798 -0.2850652 -0.9582657 1.18399e-5 0.001767456 -0.9999985 -2.17906e-4 -3.8399e-4 -1 -4.68435e-4 -4.0229e-4 -0.9999999 -0.5396437 -0.5134761 0.6671784 5.3037e-6 -1.56018e-6 -1 1.83173e-5 1.03361e-5 -1 7.84839e-6 5.38415e-6 -1 4.41216e-4 2.43957e-4 -0.9999999 -0.005074977 0.003103256 -0.9999824 -0.06515163 0.02316153 -0.9976066 2.37346e-4 2.32147e-5 -1 -0.00101906 -0.001371383 -0.9999986 0.005565643 -0.004130363 -0.999976 -4.348e-5 3.70411e-5 -1 0.03507506 -0.9959338 0.08298057 -0.5342538 0.7538729 -0.3824246 -0.9174024 -0.3910754 -0.07370918 0.7073829 0.7006993 -0.09289693 -0.3076464 0.9465401 0.09703379 -0.9428768 0.3268456 0.06446284 -0.6950433 -0.5013368 -0.5153409 2.57751e-4 -0.001591742 -0.9999987 0.00171715 -0.001487493 -0.9999974 -0.002609133 -0.002837061 -0.9999926 -6.09029e-5 -4.42436e-4 -1 -0.004115521 0.006424367 -0.9999709 0.917397 0.3910844 -0.0737279 -0.8776237 0.4372953 -0.1963402 -0.7074205 -0.7006735 -0.09280562 0.695051 0.5013287 -0.5153385 -0.03510254 0.9959343 0.08296173 -0.00144875 -0.001006543 -0.9999985 -0.001969873 6.21337e-4 -0.9999979 -0.001303672 8.60234e-4 -0.9999988 0.8642621 0.5028463 -0.01403111 0.8650879 0.5011662 -0.02134096 -0.1050328 -0.9944308 0.008693218 -0.4814401 -0.8676426 0.1241446 -0.9876446 -0.155605 0.01857924 -0.9889271 -0.1451653 -0.03082585 -0.04134446 -0.9768334 0.2099699 0.07671254 -0.9954339 0.05680412 1.37287e-4 1.27106e-4 1 2.36661e-5 -2.49261e-5 1 -2.06744e-5 -5.91974e-5 1 0.001901268 -1.11267e-4 0.9999983 0.006168901 -0.005541265 0.9999656 -0.02156895 0.06949776 0.997349 -0.01954936 0.04544365 0.9987757 0.02082782 0.0438497 0.998821 0.002304792 0.008385539 0.9999622 -0.004603981 0.001937747 0.9999876 0.03655666 0.01166367 0.9992635 0.03912496 0.01565808 0.9991117 4.10596e-4 -0.001752555 0.9999984 0.002643167 0.01572889 0.9998728 -0.01475822 -0.004582643 0.9998806 0.001336872 -0.01989758 0.9998012 1.85835e-4 5.14399e-4 1 1.92746e-5 8.57886e-6 1 -0.02297013 -0.02152836 0.9995043 5.35253e-4 4.02516e-4 0.9999998 1.02463e-4 1.59489e-4 1 -4.54969e-7 1.14127e-4 1 -0.9942831 -0.1036543 0.02563071 -0.7435696 0.6654747 -0.06517487 0.6738173 -0.7387924 0.01249921 -0.302689 -0.9525902 0.0308451 -0.9070607 -0.4169949 -0.05793309 0.2048045 0.9777126 -0.04618513 0.332838 -0.9389845 -0.08675867 -0.9525743 0.3027436 0.03080075 0.9793399 0.1944352 0.05557245 0.3017678 -0.9529327 -0.02924644 -0.7387863 -0.6738245 0.01247179 -0.4168488 0.9071303 -0.05789375 0.9776713 -0.2050015 -0.04618549 0.2261611 -0.9740894 0.001101732 -0.6123779 -0.3535565 0.7071005 -0.8680959 -0.4928632 -0.05912297 -0.8660251 -0.5000008 -1.70424e-5 0.8608786 0.5053638 -0.05912333 0.8660251 0.5000007 9.28183e-6 0.6123399 0.3535306 0.7071464 0.02994406 0.01728862 -0.9994021 -0.6123731 -0.3535537 0.7071061 -0.6123707 -0.353552 0.7071089 -0.612365 -0.3535482 0.7071159 -0.6123728 -0.3535538 0.7071063 -0.6128987 -0.3537611 0.7065467 -0.6123507 -0.3535446 0.70713 -0.6124852 -0.3535975 0.7069871 -0.6123855 -0.3535574 0.7070936 -0.6123797 -0.3535544 0.7071 -0.612368 -0.3535612 0.7071067 0.6121767 0.3534358 -0.707335 0.6124405 0.3536002 -0.7070244 -0.6123653 -0.3535481 0.7071156 0.6123712 0.3535522 -0.7071085 0.6887509 0.3273172 -0.6469047 0.5783647 0.4121646 -0.7039991 0.5783635 0.412162 -0.7040016 0.5783726 0.4121577 -0.7039967 0.6606693 0.3814395 -0.6465448 0.5783737 0.4121552 -0.7039972 0.6606678 0.3814384 -0.6465469 0.5783709 0.412155 -0.7039995 0.6606701 0.3814369 -0.6465454 0.6606606 0.3814328 -0.6465576 0.6607977 0.3813776 -0.6464501 0.5783642 0.4121628 -0.7040005 -0.6123716 -0.3535534 -0.7071076 -0.6123505 -0.3535859 -0.7071096 -0.6124571 -0.353588 -0.7070162 -0.646125 -0.2947964 -0.7040011 -0.6461243 -0.2947977 -0.7040012 -0.6606696 -0.3814362 -0.6465463 -0.6606677 -0.38144 -0.646546 -0.6461263 -0.294795 -0.7040005 -0.6606679 -0.3814445 -0.6465432 -0.6606709 -0.3814435 -0.6465407 -0.6606672 -0.381441 -0.646546 -0.6461229 -0.2947905 -0.7040056 -0.6606684 -0.3814458 -0.6465419 -0.6461185 -0.2947862 -0.7040115 -0.6606665 -0.3814414 -0.6465466 -0.6606685 -0.381436 -0.6465476 -0.01564449 -0.007818639 -0.9998471 0.002867221 -0.004966259 -0.9999836 0.005156278 -8.56199e-4 -0.9999864 -0.3192136 -0.1177619 0.9403376 -0.2918324 -0.3388524 0.8944345 0.7212072 0.3272356 -0.6105548 -0.4867377 -0.4137478 0.7693499 -0.4520497 -0.8468695 0.2801132 -0.6592916 -0.7323929 0.170104 -0.06305199 -0.3470832 0.9357125 0.1524999 -0.348263 0.924909 0.3420733 -0.2249621 0.9123476 0.2570281 -0.205896 0.9442158 0.3760843 -0.1157365 0.9193291 0.0326575 -0.3794701 0.9246274 -0.2471833 -0.3957274 0.8844774 0.600134 0.04017996 0.7988898 -0.2105423 -0.9722534 0.1019586 0 0 1 -0.5105633 0.8591221 0.03513497 -0.510375 0.8592479 0.03479295 0.03587907 0.5171775 0.8551258 0.0370897 0.9986859 0.03536707 0.4245189 0.2838141 0.8597869 0.7724148 0.4173828 0.4787141 0.8653786 0.5002518 0.02946609 0.8618328 0.5060217 0.03444486 0.9978797 0.01604998 0.06307649 0.9128937 -0.4070822 0.03015214 0.08321315 -0.2053011 0.9751549 0.5105733 -0.8591151 0.03516018 0.51037 -0.8592506 0.03479927 -0.03709644 -0.998685 0.03538691 -0.0412684 -0.9985839 0.03357619 -0.4470909 -0.2597054 0.8559573 -0.8654719 -0.5000911 0.02945035 -0.8620532 -0.505649 0.03440052 -0.4124547 0.745641 0.5233553 -0.5009442 0.864777 0.03486931 0.1352557 0.1999047 0.970435 0.4176394 0.2550864 0.8720713 -0.001017451 0.002544045 0.9999963 -1.25962e-4 8.70405e-5 1 0.005052268 -0.004414319 0.9999776 0.03704714 0.998687 0.03538006 0.04119914 0.9985864 0.03358262 0.2279216 0.0393694 0.9728833 0.5104358 -0.8591969 0.03515928 0.5103693 -0.8592411 0.03504246 -0.04832631 -0.9983661 0.0304929 -0.8618171 -0.505992 0.03526085 0.4997339 -0.8654729 0.03497195 0.4997295 -0.8654757 0.03495877 -0.03705763 -0.9986873 0.03536176 -0.3729574 -0.2216525 0.9009845 -0.2799326 -0.1869606 0.9416388 -0.8656097 -0.4998522 0.02945864 -0.8618146 -0.5060196 0.03492796 -0.08840525 0.1904318 0.9777118 -0.2146815 0.3757962 0.9014927 0.03588318 0.5171963 0.8551144 0.3899107 0.3095765 0.8672555 0.8660737 0.4990496 0.02942645 0.8618208 0.5059858 0.03526192 0.8837369 -0.4666381 0.03546911 -0.4250004 -0.2841227 0.859447 -1.49392e-4 1.36185e-4 1 -0.0192272 0.0369293 0.9991329 -0.04122191 -0.9985659 0.03416121 -0.99788 -0.01600629 0.06308293 -0.9042258 0.4255419 0.03591489 -0.5105677 0.8591189 0.03514951 -0.5103736 0.8592489 0.03479093 0.8660832 0.4990322 0.0294395 0.9129809 -0.4068925 0.03007382 0.1320764 -0.194219 0.9720261 0.3741687 -0.6547126 0.6567719 -0.04265207 -0.7177491 0.6949943 -0.4234859 -0.2831102 0.860528 0.01960074 -0.03622889 0.9991513 -2.34377e-4 2.1366e-4 1 -0.0192269 0.03692853 0.9991329 -0.07514494 -0.9963868 0.03958123 -0.08983159 -0.9953755 0.03403139 -0.8618465 -0.5059983 0.03444576 -0.9126292 0.4076789 0.03009819 -0.5105641 0.85912 0.03517633 -0.5103557 0.859259 0.03479999 0.03706365 0.9986861 0.03538745 0.8618053 0.5060112 0.03527879 0.9128435 -0.4072012 0.03006428 0.1320801 -0.1942254 0.9720245 0.3741692 -0.6547127 0.6567715 0.5076023 -0.8608832 0.03492891 -0.4234812 -0.283105 0.8605319 0.01960039 -0.03622806 0.9991514 -2.34377e-4 2.13659e-4 1 -1.49367e-4 1.36176e-4 1 -0.08982843 -0.9953756 0.03403377 -0.861837 -0.5060138 0.03445315 -0.9127923 0.4073125 0.03011393 -0.08443194 0.2017891 0.975783 0.04122877 0.9985854 0.03357923 0.3891959 0.3100837 0.8673955 0.8660817 0.4990352 0.02943211 0.9064725 -0.4207856 0.03531426 0.1320843 -0.1942306 0.9720227 0.5076014 -0.8608838 0.03492897 -0.08219158 -0.5013754 0.8613171 -0.7726109 -0.4170901 0.4786525 0.0196011 -0.03622919 0.9991513 -0.01922994 0.03693455 0.9991327 -0.07514357 -0.9963869 0.03958195 -0.9978793 -0.01596564 0.06310248 -0.9126294 0.4076788 0.0300973 -0.08443164 0.2017893 0.9757831 -0.5105563 0.859125 0.03516525 -0.5103546 0.8592598 0.03479933 0.035856 0.5171185 0.8551625 0.03706592 0.998686 0.03539031 0.04123353 0.9985854 0.03357416 0.8660801 0.4990382 0.02943229 0.1320805 -0.1942236 0.9720247 -0.04265171 -0.7177638 0.6949792 -0.08219945 -0.5014011 0.8613016 -0.4234864 -0.2831087 0.8605283 0.0196011 -0.03622895 0.9991513 -2.34433e-4 2.13703e-4 1 -1.49385e-4 1.36183e-4 1 -0.08982783 -0.9953756 0.03403592 -0.8654009 -0.5002129 0.02946835 -0.8618369 -0.5060143 0.0344516 -0.08443301 0.2017908 0.9757826 -0.5105636 0.8591215 0.03514665 -0.5103728 0.8592491 0.03479683 0.03585076 0.5171146 0.8551651 0.04118084 0.9985868 0.03359371 0.8660805 0.4990371 0.029437 0.9064932 -0.4207538 0.03516113 0.5076034 -0.8608831 0.03491598 -0.7726141 -0.4171014 0.4786378 -0.01922053 0.03691607 0.9991336 -0.07514691 -0.9963868 0.03957778 -0.8654017 -0.5002113 0.02947187 -0.9127373 0.4074367 0.03010189 -0.5105654 0.8591203 0.03514951 0.04123997 0.9985846 0.03358459 0.3891646 0.3100651 0.8674162 0.1320731 -0.1942121 0.972028 0.3741782 -0.6547251 0.656754 -0.4250118 -0.284131 0.8594385 -0.01922124 0.03691738 0.9991335 -0.8618378 -0.5060136 0.03443837 -0.9978789 -0.01598584 0.06310564 0.03706055 0.9986876 0.03535336 0.9064865 -0.420754 0.0353353 0.9129044 -0.407064 0.0300768 0.3741847 -0.6547405 0.6567349 0.5102967 -0.859064 0.04008024 2.05345e-4 -1.7944e-4 1 2.61322e-5 -4.83997e-5 1 0.4998166 -0.8654185 0.03513282 -0.04184693 -0.9985593 0.0335896 -0.8656107 -0.4998505 0.02945864 -0.5105038 0.8591614 0.03503715 -0.5103704 0.8592505 0.03479325 0.03585559 0.5170783 0.8551868 0.8837386 -0.4666344 0.03547638 0.8927084 -0.4497837 0.02768617 -0.07558798 -0.9963826 0.03883665 -0.09314715 -0.9951002 0.03315848 -0.00887835 0.01094895 0.9999006 -0.8653327 -0.4999543 0.03528541 -0.8655533 -0.4995931 0.03499227 -0.9062455 0.4212307 0.03583347 -0.91275 0.4074068 0.03012287 -0.08439844 0.2018486 0.9757736 -0.5105668 0.8591194 0.03515034 -0.5103703 0.8592506 0.03479588 0.03709566 0.998685 0.03538817 0.04127562 0.9985833 0.03358048 0.3896151 0.3089159 0.8676239 0.8664423 0.4979122 0.03689634 0.9067416 -0.4202042 0.03532862 0.9199895 -0.3911303 0.02522629 0.3747967 -0.6545241 0.6566016 -0.6353229 -0.4398927 0.6347121 -0.5967101 -0.4754729 0.6464229 0.6354552 -0.3553543 0.6855072 -0.4986736 -0.2879055 0.8175789 -0.4903996 -0.2831375 0.8242219 -0.2882392 -0.01612615 0.9574227 -0.5089105 -0.2662183 0.8186196 -0.5574347 -0.177141 0.8111028 -0.5472831 -0.3081068 0.7781719 -0.5215492 -0.3012863 0.7982562 -0.5098584 -0.2914361 0.8093884 -0.4984918 -0.2877427 0.8177469 -0.6246674 -0.3499574 0.6980835 -0.5433343 -0.1072767 0.8326342 -0.4440011 -0.2466742 0.861403 -0.3721732 -0.2266503 0.900065 -0.4238216 -0.2522238 0.8699187 -0.5566968 -0.4475138 0.6998715 -0.5328944 -0.3660216 0.7629233 -0.5226435 -0.3593065 0.7731382 -0.2580783 -0.2555793 0.9317054 -0.5276765 -0.3008955 0.7943673 -0.1581092 -0.1612913 0.9741595 -0.4913856 -0.3071572 0.8149814 -0.5046777 -0.258514 0.8236936 -0.5169958 -0.250707 0.8184507 0.5997111 0.537302 -0.5930035 0.02320134 0.007902204 0.9996997 0.8004906 0.2630409 0.5385394 0.9304876 -0.3649115 0.03213018 0.9053438 -0.4232144 0.03524541 0.8969649 -0.4410652 0.03025895 0.4337447 -0.7850571 0.4422116 0.4565345 -0.7721812 0.4419419 -0.6364607 0.2870534 0.7159037 -0.3936524 0.6674048 0.6321461 0.02103763 0.7634707 0.6454999 0.01375406 -0.009667336 -0.9998587 0.002493023 0.001114308 -0.9999963 -0.4411421 -0.1109534 0.8905522 -0.3678374 -0.07158625 0.9271306 -0.5599207 -0.03453487 0.8278263 -0.3591502 0.1228088 0.9251644 0.1874929 0.2533001 0.9490446 0.3310481 0.1254696 0.9352351 0.02093273 -0.3550093 0.9346284 0.501492 -0.1618837 0.849882 0.8025889 0.02063792 0.5961755 0.3447511 0.355542 0.8687559 0.1564655 0.7144547 0.6819627 -0.4912424 0.3183334 0.810768 -0.3959205 0.125949 0.9096064 -0.621809 0.07700377 0.7793741 -0.9516559 0.3027433 -0.05193781 -0.6019185 0.7969949 0.04993385 -0.09297829 0.9920819 0.0844314 0.4549566 0.8824886 0.1192825 0.9070447 0.4209131 0.01011705 0.9188564 0.3945883 -0.001811027 -0.3617673 0.9308795 -0.05087196 -0.1531955 0.9869346 -0.04991286 0.03076112 0.9982208 -0.0510798 0.2136405 0.9755311 -0.05193287 0.3893048 0.9198133 -0.04884135 0.5540609 0.8297183 -0.06770628 0.6017277 0.7987014 -5.25848e-5 0.529936 0.8480372 9.34663e-4 0.213903 0.9767255 0.01590287 0.06820619 0.9974963 -0.01869058 -0.4635913 0.884362 0.05465346 -0.4822422 0.8323937 0.273063 -0.7067981 0.6418675 -0.297393 -0.952856 0.3031447 0.01299554 -0.9996268 -0.02731841 -2.68469e-4 -0.9980899 -0.06156295 0.005172789 -0.9681723 -0.2502849 0 0.03078627 0.9990444 0.03102737 -0.9923838 0.1228823 0.008626103 -0.9697943 -0.2439215 0.001167476 -0.9860779 -0.166284 -4.06084e-4 -0.9958845 -0.0614196 -0.06664592 0.8167313 0.5770183 -1.46634e-4 -0.7992599 -0.5985606 0.0539335 2.38092e-4 -7.8325e-5 1 3.81137e-4 8.52262e-5 1 3.9606e-4 6.70202e-6 1 0.007149457 -0.007271945 0.999948 0.007066905 -0.01358622 0.9998828 5.46149e-4 -8.54329e-5 0.9999999 0.009011685 -0.01247662 0.9998816 0.004175662 -0.01071631 0.999934 1.3306e-5 5.54799e-5 1 3.32671e-4 7.08587e-4 0.9999998 3.83729e-4 5.14003e-4 0.9999999 5.74774e-5 3.31798e-5 1 6.40831e-5 2.11646e-5 1 2.01265e-4 2.39678e-5 1 1.77628e-4 -1.50486e-5 1 3.57281e-4 -4.46528e-4 0.9999999 1.57287e-4 -3.23515e-6 1 8.88589e-5 2.77674e-5 1 2.21496e-4 -4.31674e-4 0.9999999 1.47791e-4 -5.34026e-4 0.9999999 -6.68027e-5 -4.90926e-4 1 -2.95054e-4 -4.91423e-4 0.9999998 -1.48176e-4 -1.07139e-4 1 8.46203e-5 -9.16482e-4 0.9999996 -2.64361e-4 -4.65949e-4 0.9999999 0.0608133 -0.1369927 -0.9887036 -0.8349931 -0.5502604 -4.50649e-4 -0.8305614 -0.5569269 -5.47365e-4 -0.8277925 -0.5610345 -5.35695e-5 -0.8028716 -0.5961049 -0.007503569 -0.8455091 -0.533961 7.74897e-5 -0.837177 -0.5469254 -0.002692103 -0.861557 -0.5076232 0.006201565 -0.8696483 -0.4936352 0.006004154 -0.8775113 -0.4795245 0.005498886 -0.885138 -0.465306 0.004585266 -0.8925255 -0.4509871 0.003004848 -0.8996657 -0.4365797 1.98315e-4 -0.8832866 -0.4687887 -0.006472945 -0.8315722 -0.5554161 7.93529e-4 -0.8237212 -0.56685 -0.01282662 0.9028492 0.429754 -0.01322436 0.9028789 0.429673 -0.01381385 0.9190266 0.3941203 -0.007709026 0.9243607 0.3814889 -0.00486046 0.8834108 0.468541 -0.007393956 0.8748816 0.4842774 -0.007596313 0.8660601 0.4998832 -0.007519781 0.8282874 0.5602933 -0.003388345 0.8703921 0.4923202 0.006209492 0.8540361 0.5201849 0.005484938 0.6168743 0.002754211 0.7870569 0.5486725 0.1963225 0.8126599 0.7724388 0.2243061 0.5941592 0.7547215 0.1183695 0.6452783 0.8231298 0.1636151 0.5437714 -0.451124 -0.2192701 -0.8651057 -0.4507117 -0.2712544 -0.8504588 -0.4014523 -0.2543039 -0.8798669 -0.4428108 -0.2568578 -0.859036 -0.433768 -0.2567189 -0.8636787 -0.4344103 -0.2489898 -0.8656164 -0.4285875 -0.2525205 -0.8674943 -0.4399174 -0.2439833 -0.8642597 -0.4376048 -0.2370028 -0.8673706 -0.4617964 -0.2565005 -0.8490888 -0.4221944 -0.2121285 -0.8813362 -0.4455128 -0.2342002 -0.8641 -0.1115862 -0.062231 -0.9918043 -0.4433704 -0.22492 -0.86766 -0.4447569 -0.2234268 -0.8673361 -0.4167072 -0.2075323 -0.8850342 -0.4542139 -0.219213 -0.8635019 -0.4502589 -0.2110173 -0.8676051 0.04254579 0.995779 0.08132678 0.8739399 0.484703 0.03594583 0.8689806 0.493617 0.0348587 0.8646385 0.5011782 0.03493893 0.8597616 0.5094922 0.03504014 0.8595778 0.5097795 0.03537195 0.02326744 0.9937833 0.1088732 -0.5809502 0.8138428 0.01252585 0.8549469 0.5175256 0.03511834 0.8343004 -0.5448139 0.08438336 0.8501783 0.5252973 0.03549224 0.85052 0.5247786 0.03497654 0.2729983 0.9574595 0.09350627 0.8453706 0.5330117 0.03531485 -1.20187e-7 0 -1 1.80582e-7 0 -1 6.5374e-7 0 -1 -3.60618e-7 0 -1 0 0 -1 -2.32935e-5 -1.7722e-5 -1 2.34102e-6 1.74804e-6 -1 -1.12046e-6 -1.0747e-6 -1 -1.88891e-4 -8.06224e-5 -1 7.45903e-4 3.99364e-4 -0.9999997 -0.03023815 0.004883229 -0.9995308 -0.002321958 -0.001441776 -0.9999963 -0.01059508 -0.01470297 -0.9998358 0.003061115 0.001767337 -0.9999938 9.96509e-4 7.41908e-4 -0.9999992 -0.03850573 -0.02961581 -0.9988194 -0.03565269 -0.025801 -0.9990312 0.002456307 0.001525282 -0.9999959 -0.09334075 -0.04533952 -0.9946014 1.2103e-6 0 -1 -0.007816016 -0.004512608 -0.9999594 -0.007816731 -0.004512965 -0.9999593 0.005836427 0.003624498 -0.9999764 0.0100637 0.005810201 -0.9999325 -0.007814168 -0.00451225 -0.9999593 -0.007815062 -0.004511833 -0.9999593 0.001348614 7.72255e-4 -0.9999989 -0.05640107 -0.02966898 -0.9979674 0.005706965 0.003276348 -0.9999784 -3.06502e-4 1.452e-4 -1 0.003868579 0.002230048 -0.9999901 9.73277e-4 0.001173198 -0.9999989 -0.02894562 -0.03780889 -0.9988657 -0.0711348 -0.05388814 -0.99601 -0.03011143 -0.01243185 -0.9994692 -0.4367229 -0.8988179 0.03741317 -0.04931485 -0.9944337 0.09311157 -0.8617142 -0.5061608 0.03535425 -0.8570482 -0.5140244 0.03531837 -0.8524146 -0.5216535 0.03559476 -0.852473 -0.5215643 0.03550571 0.3532257 -0.9351959 0.02530533 -0.8474643 -0.5296794 0.03527152 -0.9710128 0.2237297 0.08413767 -0.9209591 0.3851634 0.0590226 -0.8425579 -0.537415 0.03579974 -0.8407176 -0.540125 0.03819704 0.1866913 -0.9810554 0.05173641 0.5716567 0.2443997 0.783248 0.831421 0.5432428 -0.1167325 0.5414305 0.8025952 -0.2503876 0.1491543 0.9272475 -0.3434606 -0.2715306 0.8869134 -0.3737056 0.5595508 0.7924934 -0.2426048 -0.2489703 0.8943055 -0.3717951 -0.1498014 0.6091102 -0.7788096 0.174179 0.687341 -0.7051411 0.5181947 0.6625385 -0.5408485 0.6139121 0.6273085 -0.4791617 0.8361423 0.5019788 -0.221096 0.9323363 0.3606237 -0.02645319 0.92941 0.3671274 -0.03761094 0.9360806 0.3506097 -0.02874338 0.9352348 0.3532243 -0.02384608 0.9377791 0.3461114 -0.02788156 -0.8776012 0.334442 -0.3434598 -0.9657829 -0.06759059 -0.2503897 -0.8818497 -0.4578356 -0.1128178 -0.8790118 -0.4640303 -0.1096093 -0.8924664 0.3019905 -0.3351205 -0.8396064 -0.508555 -0.190874 -0.68241 0.1927393 -0.7051016 -0.4526042 0.4342926 -0.7788063 -0.7245209 0.1127082 -0.6799753 -0.4538528 0.8137104 -0.3631711 -0.3213927 0.5566704 -0.766045 -0.5455787 0.229744 -0.805954 -0.2571334 -0.966367 -0.004182994 -0.6210589 -0.7837639 1.70406e-4 3.44168e-6 -3.6146e-5 -1 5.38329e-5 -2.28972e-5 -1 -0.002193033 6.51783e-5 -0.9999976 -1.2928e-4 -0.001016438 -0.9999995 -2.87801e-6 0 -1 0.002010762 0.001529514 -0.9999969 3.14936e-7 0 -1 -2.26549e-4 -4.30689e-5 -1 -0.3207771 0.5574588 -0.7657296 -0.3213952 0.5566871 -0.7660318 -0.3207472 0.5574577 -0.7657428 -0.03663504 0.4831809 -0.8747538 0.269594 0.6626251 -0.6987468 -0.3207619 0.5574393 -0.7657502 0.8660257 0.4999997 0 0.6123701 0.3535532 0.7071089 0.612372 0.3535532 0.7071074 0.6123904 0.3535605 0.7070877 0.6123629 0.3535505 0.7071165 0.6123731 0.3535546 0.7071057 0.6123977 0.353565 0.7070791 -0.612846 -0.3537766 -0.7065847 0.6123767 0.3535559 0.7071019 -0.6114547 -0.3529865 -0.7081834 0.61224 0.3534284 0.707284 0.6123699 0.3535529 0.7071093 0.6123416 0.3535154 0.7071526 0.6123679 0.3535562 0.7071093 0.6123737 0.3535547 0.7071052 0.612374 0.3535537 0.7071053 0.6123808 0.3535565 0.7070981 0.6606693 0.3814376 -0.6465459 0.4897443 -0.8699795 0.05732733 1.45229e-4 -4.22317e-5 1 -2.58566e-4 -0.002402186 0.9999971 2.39814e-4 -9.90072e-5 1 8.26696e-5 2.67339e-4 1 -4.40705e-5 -1.42742e-4 1 1.14156e-4 -2.54215e-5 1 0.01042276 -0.01377391 0.9998509 -0.7637917 0.3922767 -0.5125832 -0.685366 0.2717459 -0.6755943 -0.5830101 0.523665 -0.6211878 -0.7154505 0.4639459 -0.5223838 -0.845698 0.501769 -0.1817221 -0.6151044 0.2463006 -0.7489877 -0.3564763 0.146803 -0.922699 -0.2008166 -0.03344637 -0.9790578 0.02945029 -0.1146517 -0.9929692 0.1505638 -0.2745559 0.9497103 -0.8871164 0.4563542 0.06903213 -0.0488494 -0.8061739 -0.5896588 -0.8764817 -0.3061448 0.3715581 -0.4567925 0.8660944 -0.2030305 -0.3760238 0.8623096 -0.3391584 -0.24907 0.8736963 -0.4178745 -0.3985351 0.9148542 0.06489783 -0.6134056 0.7641642 0.1994658 -0.2724665 0.9483169 0.1626569 0.06432771 0.8043626 0.5906462 -0.02238637 0.6013822 -0.7986479 0.6070559 0.4003782 0.6864258 0.2088832 -0.03902769 0.9771615 0.1819235 -0.8480755 -0.4976664 -0.1811121 0.9178391 -0.3532279 -0.9829351 -0.001008629 0.1839503 0.7780076 -0.6137053 -0.1344245 0.927519 -0.2331741 -0.2921275 -0.4248878 0.4234386 0.8001064 0.534129 -0.499097 0.682355 0.7029752 -0.3388429 -0.6253091 -0.7805359 0.569292 -0.2582066 -0.8295579 0.556962 -0.04033863 -0.9994333 -0.03333181 -0.004703044 -0.9972106 0.07450717 0.004429459 -0.951843 0.3065824 0.001508951 -0.7860813 0.6181228 6.75003e-4 -0.7610971 0.6481065 -0.02625668 -0.6816742 0.7316451 0.003964841 -0.6980516 0.715639 0.02418327 -0.7008442 0.7132557 -0.009157121 -0.6876542 0.7260326 -0.002896606 -0.6220291 0.7829817 0.004410982 -0.9897272 0.1429037 -0.004320323 -0.9034391 0.4280151 0.02451443 -0.773117 0.634177 0.01047194 -0.808373 0.587877 -0.03055965 -0.6207034 0.7840288 0.005128026 -0.4763467 0.8792239 -0.007696032 -0.4580983 0.8888966 0.003003835 -0.3374 0.9412946 0.0112127 -0.3342175 0.9423059 -0.01893115 -0.5792661 0.8151385 2.38889e-4 -0.271501 0.9623795 0.01062566 0.1583923 0.9873735 0.002342998 0.3013567 0.9535034 0.003922402 0.3643316 0.9312627 -0.003510355 0.4330619 0.9013573 0.003536403 0.5361316 0.8441292 0.002988517 0.9185707 0.3794615 0.110621 0.09866493 0.9940367 0.04643607 -0.08471488 0.9964028 -0.002264261 0.1567525 0.9876337 0.002923429 0.1357897 0.9907378 1.01888e-4 0.07402187 0.9968817 -0.02734529 -0.07664066 0.9968835 0.01869815 -0.9002439 0.4350659 -0.01669061 -0.3217837 0.9467884 -0.006857752 -0.7798969 0.6250134 -0.03345245 -0.1802823 0.7648877 -0.6184216 0.4392384 0.5584909 -0.7036744 0.03922134 0.4995586 -0.8653919 0.2939656 0.4677206 -0.8335596 -0.5829005 0.7484999 -0.3161879 -0.6916165 0.6083749 -0.3892899 0.01797807 0.1643295 -0.9862418 -0.4966382 0.8601227 -0.1163588 0.009818911 -0.2405686 0.9705826 0.1279965 -0.04955184 0.990536 2.83932e-7 0 1 -1.56396e-7 0 1 1.91239e-7 0 1 1.43148e-7 0 1 0.04660218 -0.1853403 0.9815688 0 0 1 0 0 1 -4.10849e-7 0 1 1.78817e-7 0 1 -2.02276e-5 -1.95307e-5 1 -6.63097e-5 5.6841e-6 1 -4.05648e-5 1.10342e-5 1 -5.19567e-7 0 1 1.74295e-7 0 1 -0.5604593 -0.4507061 0.6948017 0.4025461 0.6294735 0.66462 0.4024549 0.6294719 0.6646769 0.6706019 0.2598585 0.6948142 -0.009531259 -0.73269 0.6804957 -0.6408695 -0.3403228 0.6880892 0.3535524 -0.6123697 0.7071098 0.3535543 -0.6123741 0.707105 0.4081727 -0.4809522 0.7759383 0.6012409 -0.3367834 0.7246285 0.7792296 -0.124275 0.6142941 0.701105 -0.3379251 0.6279001 0.3367031 -0.9415915 -0.0060485 -0.007587611 -0.9998111 -0.01789259 -0.7292286 -0.6837054 -0.02779531 0.339652 -0.9405311 -0.006149947 -0.7735173 -0.6333265 -0.02384716 -0.7685958 -0.6391256 -0.02791064 -0.7827592 -0.6211816 -0.0377025 0.9569668 0.2888531 -0.02790468 0.8723692 -0.4885273 -0.01769649 0.987174 -0.1573444 -0.02702152 0.1148863 -0.9931792 0.01990646 0.2055274 -0.9784489 -0.01990747 0.8734276 -0.4861435 0.02808254 0.4949817 0.8686754 -0.01990777 -0.4337158 0.9008299 -0.01990759 0.8826318 -0.4696434 0.01990777 0.9170925 0.3969879 0.03663527 0.4783821 0.8777027 -0.02808159 -0.3492324 0.9368247 0.01990765 -1.0285e-4 4.94407e-4 -0.9999999 0.05772727 0.03034353 -0.9978712 -0.01650089 0.02165603 -0.9996293 -0.0152781 -0.004642188 -0.9998725 2.84608e-4 3.01289e-4 -1 0.01017302 0.001592993 -0.999947 -0.006717801 0.01395416 -0.9998801 -0.2544304 -0.9666833 -0.02808248 -0.3773087 -0.9256616 0.02808415 0.2724838 -0.9614627 -0.03663563 0.9875854 0.1546643 -0.02746415 0.5877482 0.8082868 -0.03499442 0.5625011 -0.8248723 0.05637603 0.9968295 -0.07467824 0.02746474 0.8312998 0.5547218 0.03499341 0.1260702 0.9913218 0.03724843 -0.9900851 0.1360403 0.0349937 2.68231e-4 2.2218e-4 -1 1.98548e-4 4.86228e-4 -1 -3.0231e-4 -3.58679e-4 -1 -5.03149e-4 0.008749485 -0.9999616 0.04609245 -0.001791357 -0.9989356 -0.005362451 -0.007447242 -0.9999579 1.49883e-4 -8.42236e-5 -1 0.01017075 0.001592934 -0.9999471 -0.001009345 0.02927029 -0.9995711 -0.01358139 0.01008373 -0.999857 -0.9650027 0.2588282 0.04216444 0.8501722 -0.5257558 0.02807271 0.1099525 -0.9936921 0.02205508 -0.7497425 -0.6614255 0.02006202 -0.03446793 0.9987341 -0.03663492 0.5878735 0.8084653 0.02808302 0.6005498 -0.7991716 -0.02578198 0.09607267 -0.9949782 0.02808254 -0.03048813 -0.08987927 0.995486 -0.02281951 -0.03266316 0.999206 -0.969801 0.2412168 0.03606307 -0.4462631 0.894124 0.03730481 0.1853258 0.9825245 0.01732212 0.04723107 -0.9985016 0.02763777 -0.7510537 -0.6578298 0.05637764 -0.9216095 -0.3863852 -0.03663742 0.03458654 0.9987719 -0.03547936 0.8419855 0.5391329 -0.01990813 0.9207182 -0.3861345 -0.05637598 -0.3772397 -0.9254544 -0.03499215 -0.1180017 -0.2183552 0.9687088 0.07812583 0.01347517 0.9968525 -0.0088889 -0.007785558 0.9999302 -0.9688973 0.2446438 0.03724801 -0.7743474 0.6322352 -0.02578383 -0.3492079 0.9367598 0.02312731 0.9170902 0.3969931 0.03663557 0.8826314 -0.4696441 0.01990777 0.1148867 -0.9931791 0.01990747 -0.3398903 0.9400711 0.02722114 0.4949921 0.8686696 -0.01990306 0.2055274 -0.9784489 -0.01990747 -0.6884929 -0.7249698 -0.0199089 -0.002527534 0.01253879 0.9999182 0.00233221 -0.01450771 0.9998921 -0.01122599 -0.008389115 0.9999019 2.34998e-4 -6.30288e-4 0.9999998 -3.68917e-4 -6.76951e-4 0.9999998 0.008450686 0.003658056 0.9999576 0.0174809 -0.009301543 0.999804 -0.9881725 0.1520642 -0.01979017 -0.9903432 0.1360751 -0.02653449 0.1260717 0.9913216 0.03724962 0.886665 0.4589632 0.05637502 0.9289603 -0.3691127 -0.02808272 0.5046527 -0.8625448 0.03663748 -0.2543751 -0.9664724 0.03499197 -0.7958534 -0.6052529 0.01692008 0.08044147 0.9965201 0.02183938 0.5877484 0.8082868 -0.03499227 0.873425 -0.4861487 0.02808159 -0.005219817 0.008411884 0.9999511 0.03641057 0.04299688 0.9984116 0.05767369 -0.06547528 0.9961862 -0.009741246 -0.006901383 0.9999288 0.01512235 -0.006008744 0.9998677 0.2603869 -0.4750339 0.8405603 0.3973619 0.7357732 0.5483989 -0.561808 -0.1450695 0.8144487 -0.6875063 -0.5105673 0.5163878 0.4587994 -0.2083662 0.8637632 -0.9990672 0.0431627 -0.001352131 -0.9621217 0.2719177 0.01956158 0.9673526 0.2532045 -0.01079791 -0.2662588 0.9637383 -0.01774358 -0.3078578 0.9512904 0.01643848 -0.07141023 0.997447 -4.61659e-4 0.546188 0.8376483 0.004905939 0.8005778 0.5991706 0.008361876 0.2597815 -0.9654922 0.01840043 -0.8433629 -0.5373427 -0.001350343 0.9771177 0.2125715 -0.007387757 0.4643145 -0.8856693 -0.001450717 -0.5369545 -0.8436103 -0.001359045 -0.9990673 0.04315835 -0.001351714 -0.9693423 0.2449333 -0.01957935 -0.706741 -0.7071655 -0.02083772 -0.2662711 0.9637349 -0.01774334 -0.4647123 0.8854607 0.001348614 -0.3078579 0.9512904 0.01643818 0.3422676 0.9395538 -0.009576261 0.5461687 0.8376609 0.004905343 0.8005733 0.5991767 0.008362233 0.7750849 0.6318492 0.003160417 0.9665631 -0.2562637 0.009210467 0.259787 -0.9654907 0.01839977 -0.7068974 -0.7070781 0.01835036 -0.843368 -0.5373348 -0.001349568 0.9771323 0.2125044 -0.00738728 0.4643132 -0.88567 -0.001450955 0.04507982 -0.9989825 -0.001350522 -0.5369389 -0.8436201 -0.001358747 -0.1136711 -0.9928552 0.03629881 -0.1293481 -0.9910557 0.03282892 -0.8615792 -0.5064294 0.03479516 0.1079569 0.9933835 0.03917634 0.07456499 0.9962939 0.04288011 0.1329695 0.9905732 0.03292304 0.6640337 0.7462401 0.046745 -0.1229408 -0.9920517 0.02681434 -0.4288003 -0.9015727 0.05741918 -0.8656295 -0.4997696 0.03026807 -0.5523377 -0.8328779 0.03517776 -0.3490431 -0.9356285 0.05261403 -0.8656195 -0.4997763 0.03044056 -0.8616998 -0.5062435 0.03450936 -0.9780557 -0.2019199 0.05133557 -0.08481889 -0.9957985 0.03451234 -0.09940022 -0.9942939 0.0387212 -0.3405435 -0.9387478 0.05275136 -0.8655984 -0.4998127 0.0304417 -0.9938089 -0.1086224 0.02334922 0.08285683 0.9958581 0.03743577 0.664023 0.7461004 0.04906964 0.865632 0.4997708 0.03017252 0.8615553 0.5064868 0.03454613 0.9781333 0.2020027 0.04950183 -0.8971809 0.4397398 0.04117679 -0.9004791 0.4326049 0.04461264 0.09158778 0.9951767 0.03514552 0.8656018 0.4998189 0.03024435 0.8616324 0.5063411 0.03476238 0.1018063 0.9941096 0.0371713 0.6640195 0.7461242 0.0487523 0.8656287 0.4997735 0.03022652 0.9780415 0.2019268 0.05158042 0.9943499 0.08766412 0.05986124 0.5042858 -0.8620417 0.05079472 -0.8877973 0.4586051 0.03869575 0.8657275 0.4993137 0.03466665 0.9140005 -0.4040336 0.03687888 0.05400276 0.9974753 0.04611599 0.8778708 0.4775885 0.03538566 0.8866248 0.4611356 0.03536295 0.8992651 -0.4351555 0.04429364 0.8183218 0.5723716 0.05234843 0.9322595 0.3557912 0.06561297 0.897822 -0.4387716 0.03735303 0.9022369 -0.4289218 0.04466378 -0.4884994 0.8724143 0.01618182 -0.5099774 0.8585779 0.05260503 0.1050849 0.9943481 0.01513314 0.04134267 0.9983274 0.04041391 -0.8836274 0.4659852 0.04539388 -0.8795552 -0.4745149 0.03490495 0.3849455 0.919089 0.08421683 0.03283762 0.9976226 0.06058704 0.8657341 0.499829 0.02599465 0.9942362 -0.08384174 0.06682091 0.5261524 -0.8493984 0.04106277 0.9947541 0.065521 0.07855767 -0.925232 0.3777294 0.03558647 -0.3822724 -0.9201856 0.08441811 -0.8657369 -0.4998235 0.02600133 -0.8602101 -0.508792 0.03419733 -0.6335661 0.7727375 0.03835201 0.03338909 0.9987097 0.0382651 0.07622617 0.9957792 0.05112087 -0.9237821 0.381496 0.03297829 -0.9145007 0.4026951 0.03905671 0.8400104 0.5410774 0.04022347 -0.1001374 -0.5601951 0.8222858 -0.6005896 -0.3456821 0.7209689 0.1614956 -0.2127846 0.9636607 0.8461347 0.2647192 0.4625794 -0.1540453 -0.07395845 0.985292 -0.5107384 0.03374189 0.8590739 -0.3869754 -0.7460525 0.5419003 -0.1263019 -0.01744115 0.9918385 0.1471244 0.1009423 0.9839538 -0.5433982 0.7968814 0.2640047 -0.6262273 -0.4073671 0.6647492 -0.8653087 -0.5002946 0.03076207 -0.8616701 -0.5062742 0.03479814 -0.2374595 0.6121879 0.7542142 0.6667168 -0.6521769 0.3607689 0.648036 0.4697359 0.5994978 -0.0663498 -0.09916925 0.9928562 -0.3916617 0.3115562 0.8657563 -0.865119 -0.4994702 0.04581046 0.08592498 -0.2489895 0.9646871 -0.5812179 -0.333061 0.7424663 -0.3871192 -0.2124362 0.8972234 -0.4405767 -0.2401143 0.865007 -0.723639 0.6755444 0.1413736 -0.9183016 0.3931965 0.04603219 0.07813644 0.3578314 0.9305114 0.2173094 -0.7533593 0.6206661 0.6760041 0.3593792 0.6433236 0.1104205 0.1267137 0.9857743 -0.2137472 0.9438356 0.2519654 -0.4584542 -0.2668365 0.8477135 0.2709594 -0.2811728 0.9206101 -0.2814692 -0.475557 0.8334392 -0.6106587 -0.3593358 0.7056726 -0.2805507 -0.4769729 0.8329395 0.996124 0.01530748 0.08661878 -0.6380593 -0.5093353 0.5774582 -0.5972734 -0.8003873 0.05142599 0.5591961 0.2843195 0.7787568 -0.2270237 0.03629088 0.9732129 -0.5733935 -0.3658443 0.7330607 0.886044 -0.4557155 0.08514434 0.8012946 -0.5949423 0.06301379 0.6113934 0.3630307 0.7031407 -0.4812414 0.6785685 0.554934 -0.3100093 -0.1689557 0.9356005 -0.5252419 -0.2532142 0.812406 0.6783767 -0.6209996 0.3926379 0.9146494 -0.4017589 0.04479074 0.4289647 0.2483831 0.8685016 0.4235666 0.2445854 0.8722209 -0.07175111 -0.9964064 0.04501283 0.9162623 -0.3960652 0.05996644 0.2444915 -0.2880042 0.9258929 0.0858882 0.0688973 0.9939197 0.9368191 -0.3481513 0.03406834 0.9193323 -0.3908942 0.04505354 0.6540856 0.01171821 0.7563298 -0.7161287 0.5958009 0.3635672 -0.5724589 0.5466929 0.6110792 0.6294342 -0.292839 0.7197624 0.4627668 0.2690452 0.8446666 0.697326 0.3921967 0.5999318 -0.4063823 0.8213418 0.4003141 0.1100009 -0.3297726 0.93763 -0.1652234 0.3226861 0.9319738 -0.5397468 0.203112 0.8169571 -0.7964323 -0.1112233 0.5944116 -0.9248886 0.3788499 0.03246253 -0.9136488 0.4046891 0.03837752 -0.942489 0.1974531 0.2696793 -0.4230788 -0.2442642 0.8725476 0.1667219 -0.1428146 0.9756065 -0.0331363 -0.592268 0.8050594 0.6169845 -0.5266091 0.5848188 0.07566046 0.01351219 0.9970421 -0.542948 0.3162369 0.7779473 0.04577147 0.9982314 0.03793776 -0.5122127 -0.5327334 0.6736716 0.1120283 0.05085039 0.9924032 0.09186357 0.03688323 0.9950883 -0.7259987 0.1568189 0.6695773 -0.2939133 -0.2730587 0.9159989 -0.915216 0.4014149 0.03529572 0.0881868 0.3117066 0.9460773 -0.3812972 -0.2387944 0.8930789 0.6599195 -0.1852437 -0.7281423 -0.5275365 -0.4237511 0.7363017 0.6112344 -0.6055899 0.5095621 -0.3314808 -0.2089164 0.9200406 0.6524966 0.2967629 0.697266 0.06735306 0.9969456 0.03953492 -0.9955632 0.0588625 0.07341003 -0.9860284 0.1442439 0.08331632 -0.06430876 -0.6003515 0.7971465 0.689798 0.3714625 0.6214454 -0.6064304 -0.3571416 0.7104169 -0.5847324 -0.3376126 0.7376353 0.04030019 0.8299313 0.5564081 0.6098505 0.352114 0.7099987 0.5280948 -0.1917552 0.827252 -0.3658167 0.8707156 0.3286829 0.4307419 0.2570772 0.8650854 0.5277143 0.8485111 0.0393297 -0.1791585 -0.1580914 0.9710352 0.4289675 0.2482704 0.8685325 -0.03247773 0.1566725 0.9871165 0.2401508 0.1461367 0.9596728 -0.7078163 -0.376117 0.5979399 -0.003613948 -0.999351 0.03584259 -0.04911857 -0.9977107 0.04648482 0.9205295 -0.3859444 0.06059962 0.1842351 0.6035172 0.7757734 0.59126 0.3427657 0.730016 -0.5770264 0.7380071 0.3498373 0.3330265 0.7063574 0.6246219 -0.6323326 -0.4081368 0.6584678 0.6749146 0.2416615 0.6972016 0.912072 -0.4074591 0.04584574 0.9228749 -0.05663979 0.3809122 0.4317954 0.2488021 0.8669776 0.4368 0.2522296 0.8634733 0.3890101 0.8103685 0.4381485 0.03777551 0.1734425 0.9841193 0.5244326 -0.3098948 0.7930547 0.1207964 -0.8305548 0.5436793 -0.03039258 -0.9988707 0.03652155 -0.0642516 -0.9968907 0.04561501 0.9873048 -0.1339476 0.08536732 0.9101943 -0.4100743 0.05818641 0.5167022 0.03950899 0.8552532 0.219171 0.4377334 0.8719826 0.994141 -0.08493262 0.06686031 0.4920315 0.3744019 0.785957 0.218557 0.09572756 0.9711174 -0.1405689 -0.0998001 0.9850281 -0.6218462 -0.4583483 0.6349994 -0.6811046 -0.2669893 -0.6817721 0.548802 0.3197172 0.7723972 0.8005553 0.2183498 -0.5580633 0.912482 -0.4073412 0.03807806 -0.02685016 0.1466559 0.9888232 -0.4991011 -0.2882019 0.8172134 0.1162127 -0.1540864 0.9811993 0.1384772 -0.6007806 0.787329 -0.03019458 0.09620082 0.9949039 0.07807397 0.9959769 0.04398339 -0.8029218 0.5899098 0.08557492 0.990871 0.06344366 0.1189526 0.8980591 0.2353774 -0.371601 -0.3220191 0.5333854 0.7821788 0.01973056 0.08277678 0.9963728 0.4565573 -0.375118 0.8067477 0.3182959 0.7445949 0.5867419 0.8652351 0.5001237 0.03528076 0.8654981 0.499695 0.0349009 0.1843518 0.08165878 0.9794623 -0.6805299 -0.4071363 0.6091955 -0.2294949 -0.2047325 0.9515339 0.6816038 -0.6963567 0.2247304 -0.2613269 0.1773151 0.9488244 0.2176916 -0.3164986 0.9232763 0.9147079 -0.402512 0.03596889 0.9316955 -0.3601923 0.04695904 -9.33935e-4 -0.7141229 0.7000197 -0.5798537 -0.3575159 0.7320876 0.003761887 0.7454386 0.6665638 0.02775144 0.6733523 0.7388008 0.6180995 -0.3229098 0.7167164 0.3305697 -0.5376111 0.7756919 0.418195 -0.745682 0.518721 -0.03253781 -0.7568949 0.6527262 -0.5872481 -0.3397758 0.7346374 -0.6305832 0.2916282 0.7192482 -0.3885071 0.6589587 0.6440774 0.6018655 0.3538348 0.7159323 0.5874163 0.3398197 0.7344827 0.5546301 -0.2881851 0.7805992 0.3281626 -0.5331453 0.7797856 0.4176535 -0.7457985 0.5189896 0.003029584 -9.04996e-4 0.9999951 -0.03136539 -0.7570721 0.6525782 -0.6026663 -0.3538246 0.7152633 -0.02013319 0.6907832 0.7227817 0.5880447 0.3404273 0.7336979 0.6412442 -0.2893153 0.7107057 -0.1078677 -0.2692354 0.9570146 -0.3885188 0.6589769 0.6440518 0.01976108 0.7129338 0.7009529 0.6680722 -0.3724441 0.6441778 0.2609893 -0.4486383 0.8547564 -0.001456856 -0.7121005 0.7020761 -0.6020629 -0.3532662 0.7160471 -0.5933945 -0.3448261 0.7273088 -0.7153358 0.3189133 0.6217629 -0.3695418 0.6272263 0.6855844 0.02432322 0.7644919 0.6441744 -0.004453957 0.6944189 0.7195572 0.2981479 -0.5305157 0.7935119 -0.06424695 -0.7041432 0.7071454 -0.05786299 -0.7221558 0.6893062 -0.6044049 -0.3555071 0.7129583 -0.651616 0.3615595 0.666837 0.5929661 0.3444638 0.7278296 0.6421926 -0.2833821 0.7122383 -0.6019723 -0.3535866 0.715965 -0.5958696 -0.3476315 0.7239419 -0.6420808 0.2841011 0.7120527 -0.4380538 0.7238379 0.5330738 -0.2695744 0.4913872 0.8281717 0.03119295 0.7529489 0.6573394 0.6020405 0.353306 0.7160462 0.6244594 -0.2996227 0.7213022 0.6395218 -0.2996978 0.70795 0.3806192 -0.6505897 0.6571621 -0.06424862 -0.7041172 0.7071712 -0.604184 -0.3553761 0.7132107 -0.6019601 0.304624 0.7381385 -0.6522833 0.3612272 0.6663643 -0.2656975 0.488938 0.8308698 0.6020516 0.3533158 0.7160321 0.5929213 0.3444277 0.7278832 0.5853971 -0.2828159 0.7598193 -0.06590479 -0.6993458 0.7117387 -0.5910127 -0.3429126 0.7301472 -0.6346109 0.282801 0.7192307 -0.6423432 0.2823818 0.7124997 0.01456809 0.7278754 0.6855548 0.6042879 0.3549044 0.7133576 0.597323 0.3481611 0.7224882 0.380631 -0.650612 0.6571334 -0.06596374 -0.698081 0.7129738 -0.6019676 -0.3535761 0.7159742 -0.6346573 0.2828225 0.7191812 -0.3885676 0.6589292 0.6440711 0.01870203 0.7295808 0.6836389 0.5854157 -0.2828221 0.7598028 0.6422221 -0.2833861 0.7122101 0.4176385 -0.745766 0.5190483 -0.03137326 -0.7570697 0.6525804 -0.008835554 -0.711935 0.7021899 -0.6044723 -0.355226 0.7130412 -0.5931547 -0.3442931 0.7277567 -0.3389512 0.571515 0.747317 0.02142274 0.7953272 0.6058018 0.6018756 0.353847 0.7159176 0.5880247 0.3404031 0.7337252 -0.6346567 0.2828277 0.7191797 -0.3504779 0.5740633 0.7400113 -0.3885052 0.6589596 0.6440777 0.01975744 0.7129443 0.7009422 0.5973367 0.3481245 0.7224945 0.5857751 -0.332156 0.7392833 0.6964456 -0.3450506 0.6292088 -0.8631929 -0.5000076 0.06993204 -0.05581229 -0.9977431 0.03733432 0.3619677 0.9277589 0.09079098 0.3724417 0.9236496 0.09032565 0.8673655 -0.4964972 0.03416955 0.9043001 -0.4235841 0.05308383 -0.3653596 -0.9264423 0.09064799 0.882752 0.4684644 0.03591841 0.8866588 0.4601894 0.04540932 -0.2149397 0.9745681 0.06338882 -0.4235381 -0.9034107 0.06681805 0.9416649 -0.3240061 0.09103411 0.9922127 -0.1121755 0.05413693 0.8908981 0.452844 0.03511577 0.4074261 0.9117799 0.05159044 -0.007611811 0.9925699 0.1214379 -0.005378425 -0.998398 0.05632519 0.4999998 -0.8660256 -4.05445e-7 -0.9071316 0.417696 0.05140292 -0.1001963 0.9914503 0.08358895 0.2975864 -0.9538651 0.03979557 -0.950758 0.2972728 0.08768159 -0.9860301 0.1538116 0.06392854 -0.8838697 -0.4654908 0.04574728 0.3629011 0.927397 0.090761 0.0316016 0.997756 0.0590291 0.8651139 0.4994941 0.04564869 0.8651121 0.4994966 0.04565405 -0.8763557 -0.4795433 0.04515486 0.8651248 0.4994763 0.04563724 0.8651126 0.4994958 0.04565513 -0.3492826 -0.9320315 0.0965346 -0.06702625 -0.9961284 0.05688422 -0.4285424 0.9026983 0.03856557 -0.9567921 0.2603703 0.1294464 -0.8806661 -0.4716004 0.04494869 -0.1103762 -0.9934301 0.03022933 -0.8651252 -0.4994746 0.04564487 -0.865117 -0.4994878 0.04565614 0.8951807 -0.4431879 0.04728686 0.9104968 -0.4100367 0.05353134 -0.09734767 -0.9946159 0.03553533 -0.8654981 -0.4996939 0.03491508 -0.8584882 -0.5108674 0.04486262 -0.9539915 0.297391 0.03819721 -0.8947054 0.4436433 0.05179691 -0.7644836 -0.6415034 0.06354767 0.5309084 -0.8325464 -0.1581235 0.9735749 -0.2060464 -0.09847277 -0.6640394 0.7455996 -0.05597293 -0.9376073 0.3394117 -0.07544797 -0.7803896 0.6202122 0.07955616 -0.1904266 0.9793663 0.06767261 0.7657607 0.6425493 0.027224 -0.04996383 0.402453 0.9140762 0.1598585 0.2857831 0.9448668 0.3601422 -0.09281939 0.9282684 0.08322024 -0.2373456 0.9678541 -0.4628848 -0.2659133 0.8455932 0.06029969 0.896516 0.4388887 0.09823626 0.4432278 0.8910099 0.5474836 0.1574605 0.8218685 0.49576 -0.06389188 0.8661062 0.2731134 -0.6090577 0.7446193 -0.3061085 -0.4489509 0.8394884 -0.1247384 0.08434879 0.9885979 -0.3609672 0.363775 0.8587028 2.31205e-7 0 -1 0 1.05092e-6 -1 -4.72879e-7 0 -1 0 -4.03588e-7 -1 -1.76574e-6 4.25787e-7 -1 0.8651982 -0.4995296 -0.04361462 0.8651999 -0.4995276 -0.04360586 -0.8652051 0.4995163 -0.04363125 0.4995296 0.8651969 -0.04364132 -0.4995303 -0.8651982 -0.04360914 -0.4995233 -0.8652023 -0.04360663 0 0 -1 -0.4807852 0.2797755 0.8310062 0.9083393 0.4153101 0.04936933 0.8524678 -0.5216425 0.03446251 0.03114986 -0.006614625 0.9994929 0.0945245 -0.9911103 0.09362512 -0.9066871 -0.4188804 0.04957586 -0.904068 -0.4250591 0.04456436 0.02141857 -0.01693797 0.9996271 -0.01935935 0.03422302 0.9992267 0.9762158 0.2140235 0.03459328 -0.06514197 0.9968534 0.04516381 -0.4300954 0.226095 -0.8740132 -0.454588 0.2179446 -0.863626 -0.4954577 0.2951925 -0.8169352 -0.4391635 0.2663604 -0.8580138 -0.4371196 0.2754775 -0.8561767 -0.4286023 0.2525296 -0.8674842 -0.1189644 0.07006585 -0.9904233 -0.4575411 0.2452914 -0.8546862 -0.1169359 0.05660009 -0.9915254 -0.4416809 0.2342674 -0.8660467 -0.4208163 0.2146522 -0.8813843 -0.4543935 0.2242161 -0.8621217 -0.3933345 0.2020303 -0.8969236 -0.4423076 0.211322 -0.8716118 -0.45867 0.2213639 -0.8605929 -0.4346258 0.2375058 -0.8687299 -0.4385406 0.2452819 -0.8645918 -0.4347326 0.2557055 -0.8634943 -0.4381369 0.2556762 -0.8617805 -0.4370304 0.265631 -0.859328 -0.003076255 -0.003942489 -0.9999875 0.001470029 -0.001368165 -0.999998 -0.03723001 0.02113068 -0.9990833 -9.7371e-4 0.007110834 -0.9999743 -0.06321424 0.0268827 -0.9976379 0.09772008 -0.03639233 -0.9945484 -0.1538727 0.09963726 -0.9830542 -5.69826e-4 -9.78811e-4 -0.9999994 0.006572604 -0.004081249 -0.9999701 -0.05076158 0.04580301 -0.99766 -0.05700337 0.03213196 -0.9978569 0.002968192 -0.001588761 -0.9999943 0.007033288 -0.004060566 -0.999967 8.59944e-4 -6.16242e-5 -0.9999997 -0.09450286 0.05691295 -0.9938964 1.21218e-6 0 -1 -0.03602355 0.00849694 -0.9993149 -0.09672844 0.06140768 -0.9934147 0.001251041 -7.77098e-4 -0.9999989 -0.03199034 0.0300861 -0.9990352 6.97147e-4 -4.06325e-4 -0.9999998 1.51296e-7 0 -1 -0.002322375 0.001442074 -0.9999963 -1.80311e-7 0 -1 -9.71587e-7 1.29607e-6 -1 -7.73352e-6 3.23354e-6 -1 0.8660256 -0.4999996 -1.54453e-4 0.8660258 -0.4999995 0 0.3222683 0.5611202 -0.7624221 0.3313133 0.5491287 -0.767261 -0.1983582 -0.6417126 0.7408502 0.5996638 -0.3576824 0.7158678 0.7357531 -0.4120655 0.5374659 0.9078902 0.4182918 0.02770394 0.5178191 -0.2907192 0.8045782 0.3886395 -0.2447618 0.8882855 0.05136036 -0.8676898 -0.4944459 -0.2908982 -0.4750413 0.8304902 -0.3583588 -0.6133297 0.7038508 -0.1764724 0.1538048 0.9722148 -0.03673368 0.5578836 0.8291059 0.2498842 0.4199746 0.8724558 0.9067206 0.4094937 -0.1008601 0.4884018 0.8710252 0.05271416 0.8689581 -0.4932749 0.03989595 0.005111455 -0.004284977 0.9999778 0.006018161 -0.003751158 0.9999749 0.1148825 -0.01289981 0.9932953 -0.3863188 -0.5332368 0.7526064 -0.8636212 0.5034337 0.02670246 0.005542695 -0.003641784 0.9999781 -0.6271967 -0.2310478 0.7438018 0.3540574 0.5433089 0.761222 -0.03382664 0.6318229 0.7743744 -0.06374555 0.5398973 0.8393137 -0.9121936 -0.4082642 0.03497761 -0.9096953 -0.4135981 0.03729993 0.6967319 -0.5057216 0.5087341 0.7555902 -0.4585054 0.4678208 -0.8155997 0.4083117 0.409974 -0.7170092 0.3355027 0.6110122 0.6232534 0.2497097 0.7410805 0.7799205 0.3968562 0.4839723 0.8969393 0.4406594 0.03632384 0.8632757 -0.5033925 0.03675985 0.8654812 -0.4994464 0.03867489 0.4148565 -0.9087196 0.04607558 -0.02341097 0.02389979 0.9994403 0.3359658 0.4330422 -0.8364218 0.05109381 0.1261787 -0.9906908 0.8343846 -0.5497741 0.03938138 0.8349179 -0.5488851 0.04046571 -0.003874242 -0.9979199 0.06435054 0.001086592 -8.98208e-4 -0.9999991 -0.9796219 -0.1897023 0.06598562 -0.9742416 -0.2143922 0.06992429 0.005390465 0.02590018 -0.9996501 7.79329e-5 0.006078422 -0.9999815 0.3234236 0.557952 -0.7642557 0.3173771 0.5572133 -0.7673234 -0.958563 -0.1400398 0.2480846 -0.2786891 0.9519649 0.1268669 0.9802626 -0.1381234 0.1414467 0.172622 0.9831218 -0.0606091 0.7387743 0.6739528 -3.3387e-4 -0.2228784 0.9735867 0.04953885 0.9375981 0.310408 0.1567065 0.5655601 -0.8074607 -0.1677769 0.5002682 0.865868 -0.002105116 0.4999976 0.8660261 -0.001113474 -0.9285371 -0.03917425 0.369167 -0.8650615 0.4998109 -0.04309976 -0.8651992 0.4995251 -0.04364567 -0.8652019 0.4995233 -0.0436154 0.8653203 -0.4992978 -0.04384589 0.8651996 -0.4995275 -0.04361069 -1.67286e-5 9.76012e-6 -1 4.50561e-6 9.16715e-7 -1 6.819e-6 -9.93213e-7 -1 3.86334e-7 -8.11069e-7 -1 -0.9283092 0.3649774 -0.07094812 -0.03757536 -0.9440407 -0.3276818 -0.04235273 -0.9434446 -0.3288139 -0.4656504 -0.8064841 -0.3643529 -0.9717227 -0.06436449 -0.2271835 6.69409e-5 -2.61516e-4 -1 -1.12625e-4 -8.35864e-5 -1 -1.08263e-4 -1.71757e-5 -1 1.34146e-5 9.82099e-6 -1 -1.46032e-6 0 -1 -1.95561e-6 0 -1 -3.2608e-7 0 -1 1.16192e-6 0 -1 -1.33434e-6 0 -1 1.50061e-6 0 -1 -0.8660253 0.5000001 4.93006e-7 0.8752478 0.4836705 0.002022922 0.8459969 0.4962961 0.1948837 0.2981194 0.7071156 -0.6411805 -0.06382274 -0.9978696 0.01352852 0.6124389 -0.7902955 -0.01875263 -0.7246236 -0.6155651 -0.309839 0.01363307 -0.905785 -0.4235184 0.8660162 -0.500016 -7.08307e-6 0.8660036 -0.5000379 -3.77085e-6 0.8789105 -0.4769816 0.002233922 0.8660265 -0.4999983 -2.91068e-5 0 0 -1 0 0 -1 3.61602e-5 -0.001492321 -0.9999989 2.52332e-7 0 -1 -0.4999995 -0.8660258 0 -0.8287292 0.4538145 -0.3275063 0.2145159 0.9614639 -0.1719599 -0.7903077 -0.6124531 -0.01775151 -0.8881654 0.3755344 -0.2648325 -0.571464 0.8206236 0.002410948 -0.1655774 0.986196 0.001268208 0.3069977 0.9517103 0 -0.7071075 0.7070948 -0.004001677 -0.2588273 0.9659188 -0.003068685 0.4999933 0.8660293 0 0.4999998 0.8660256 8.29388e-7 0.4999866 0.8660333 0 0.232207 0.3474597 -0.9084887 0.129409 0.2241431 -0.9659262 0.5093767 0.8455433 -0.1599755 0.1024814 0.2650399 -0.958776 0.3976178 0.6083566 -0.6868787 0.8660261 -0.4999989 0 -0.8756329 0.4828336 -0.01178556 -0.5000141 0.8660173 1.9169e-6 0.9999905 0.003469586 -0.002638041 1 -9.94297e-5 7.44944e-5 0.564594 -0.7832121 0.2604083 -0.433085 -0.8999585 0.05012208 -0.30452 -0.04677563 0.9513568 -0.2429131 -0.9667885 0.07945698 0.4243324 -0.9054768 -0.007339596 -0.1838473 -0.5319142 0.8265999 -0.5231581 0.2313522 0.8202329 -0.4246513 0.254514 0.8688463 -0.3401472 0.1916959 0.9206262 -0.4969326 0.2868823 0.8189974 -0.2894154 0.1517229 0.9451027 -0.3187454 0.2357973 0.918042 -0.4980382 0.2874521 0.8181254 -0.503636 0.2906416 0.8135591 -0.4981926 0.2875816 0.8179859 -0.5021924 0.2900342 0.8146674 -0.5009822 0.2886158 0.8159153 -0.4968666 0.2868644 0.8190436 -0.4396291 0.2625485 0.8589498 -0.4965363 0.2866687 0.8193123 -0.614446 0.3483129 0.7079084 -0.4967373 0.286789 0.8191485 -0.4961661 0.2864473 0.8196141 -0.454804 0.2601313 0.8517541 -0.5011613 0.2825918 0.8179116 -0.4599199 0.2820894 0.8419616 -0.502779 0.290153 0.8142632 -0.4395976 0.2611975 0.8593776 -0.5449411 0.1138499 0.830709 -0.5483636 0.1238883 0.8270121 -0.5084109 0.3062529 0.8048153 -0.430505 0.2966589 0.8524429 -0.2355906 0.1760252 0.9557783 -0.6004202 0.2452685 0.7611432 -0.5248412 0.123842 0.8421431 -0.5351033 0.273327 0.7993478 -0.5019651 0.2889232 0.8152021 -0.7716056 0.5576673 0.3059935 -0.1058975 0.1150171 0.9877029 0.2147298 -0.0685684 0.9742636 0.6540079 -0.3858283 0.6506997 -0.6069433 0.792091 -0.06489723 0.8599053 -0.5103916 0.007964849 0.8675326 -0.495764 0.04006779 -0.4301071 0.2564602 0.8655844 0.4718651 -0.1810647 0.8628783 -0.7556424 0.4012298 0.5177057 -0.6063274 0.3501372 0.7139826 0.03178799 -0.06833779 0.9971557 0 0 1 -0.003548383 -0.005176842 0.9999804 -0.016182 -0.002191305 0.9998667 2.87493e-4 -2.14234e-4 1 -0.003448784 0.001899003 0.9999923 -0.003397524 0.001879215 0.9999926 -0.006931662 0.003791451 0.9999689 -0.003365576 0.001919627 0.9999925 -0.004932999 0.002504467 0.9999848 -0.004862606 0.002834975 0.9999842 3.17996e-4 -1.7571e-4 1 0.01747548 8.41614e-4 0.9998469 -0.01471257 0.009653329 0.9998453 2.25094e-4 9.31355e-5 1 -0.00442624 0.003352582 0.9999847 -5.00654e-4 2.18879e-5 0.9999999 0.002790272 5.82553e-4 0.999996 0.003360211 -0.001864075 0.9999927 8.924e-4 -4.96376e-4 0.9999996 -0.1624437 0.07210904 0.9840795 8.71742e-4 -7.52095e-4 0.9999994 3.64917e-4 -3.16607e-4 1 4.88934e-4 -4.11022e-5 1 0.001511216 -8.52432e-4 0.9999986 0.001519024 -8.85997e-4 0.9999985 3.18123e-4 -1.89463e-4 1 0.001057922 -7.41009e-4 0.9999992 5.10516e-4 -3.07632e-4 0.9999998 3.0783e-4 -1.90229e-4 1 -0.2196399 0.1377728 0.9658038 0.002559304 -8.48636e-4 0.9999964 0.01747971 8.40698e-4 0.9998469 0.003449499 -0.001948416 0.9999922 -0.01425904 0.06889313 0.9975222 5.34716e-4 -3.01458e-4 0.9999998 -0.04114025 0.01664358 0.9990149 -0.04594409 0.02701574 0.9985787 -0.0393356 0.02679371 0.9988668 0.06865566 -0.07615542 0.9947295 0.06914192 0.1276908 0.9894011 -2.93674e-4 9.83295e-5 1 -0.001822352 7.34179e-4 0.9999982 -4.9589e-4 -4.09207e-5 1 -0.001766443 -0.03010797 0.9995451 0.3437291 -0.09426128 0.9343261 -0.00200349 7.93071e-4 0.9999977 -0.001847565 0.001112878 0.9999977 -0.002019047 0.001259088 0.9999972 0.02082252 -0.2115073 0.9771547 -0.00182414 0.001287043 0.9999975 -0.002923607 0.001674711 0.9999943 0.1278273 -0.1218679 0.9842807 0.1705369 -0.07111597 0.9827816 4.47346e-5 -5.20701e-4 1 8.20326e-6 -3.37087e-5 1 -8.18662e-5 -5.57901e-5 1 2.66981e-4 -9.94049e-4 0.9999995 -5.54586e-4 -4.62971e-4 0.9999998 0.001053333 0.001461744 0.9999985 -0.00236833 3.68994e-4 0.9999972 2.3594e-4 -9.73703e-4 0.9999995 -4.41619e-4 -5.3613e-4 0.9999998 3.56619e-4 4.04039e-4 0.9999999 0.003285467 -0.1478797 0.989 -0.007317721 0.004332065 0.9999639 -0.001648366 6.29169e-4 0.9999985 0.01265454 -0.002597391 0.9999166 0.03353983 -0.01898252 0.9992572 7.25266e-4 5.04188e-4 0.9999997 -0.001134455 5.59926e-4 0.9999992 4.6795e-4 1.06437e-4 0.9999999 0.03378999 -0.01941996 0.9992403 0.003025293 -0.001764595 0.9999939 -0.00218141 0.001254439 0.9999969 4.3536e-4 -3.7785e-4 0.9999999 -2.48522e-4 -1.55312e-4 1 -1.82525e-4 -3.11866e-5 1 0.001182496 3.37929e-4 0.9999994 5.96487e-4 -3.86679e-4 0.9999998 -2.73028e-4 -1.89781e-4 1 4.49458e-4 6.94316e-5 1 9.66193e-5 -1.69313e-5 1 -0.00217545 0.00125122 0.9999969 0.005774676 0.01089948 0.999924 0.001616358 1.89007e-4 0.9999988 -0.001903891 0.001435697 0.9999973 2.51613e-4 4.0437e-4 0.9999999 -0.002510666 0.001329898 0.999996 -1.53167e-5 1.33143e-4 1 -2.65522e-4 9.15042e-5 1 -0.002823889 -0.008733391 0.9999579 0.8914081 0.3693135 0.262677 0.8660254 -0.5000001 8.12328e-6 0.8660258 -0.4999997 -8.93175e-5 0.6077597 -0.3697227 0.702804 -0.8635463 0.4952021 0.09519916 -0.8635854 0.4952171 0.09476536 -0.8652019 0.4995231 -0.04361945 -0.8652036 0.4995198 -0.04362243 -0.8652008 0.4995244 -0.04362231 -0.8652002 0.499526 -0.0436182 -0.8652018 0.4995228 -0.04362034 -0.865202 0.4995226 -0.04362159 -0.8652036 0.4995204 -0.04361605 -0.8651983 0.4995298 -0.04361146 -0.865204 0.4995189 -0.04362344 -0.8652023 0.4995231 -0.04361015 -0.8652037 0.4995198 -0.04361921 -0.8651995 0.4995275 -0.04361426 -0.8652005 0.4995265 -0.0436061 -0.8652012 0.4995244 -0.04361432 -0.865192 0.4995411 -0.04360699 0.8652031 -0.4995205 -0.04362148 0.8652024 -0.4995218 -0.04362064 0.8652 -0.4995259 -0.04362326 0.8652011 -0.4995241 -0.04362171 0.8652024 -0.4995217 -0.04362368 0.8652009 -0.4995244 -0.04362142 0.8652019 -0.4995229 -0.04361754 0.8652015 -0.4995233 -0.04362165 0.865204 -0.4995192 -0.04361855 0.8652058 -0.4995167 -0.04361283 0.8652009 -0.4995242 -0.04362452 0.8651973 -0.4995304 -0.04362446 0.8651994 -0.4995273 -0.04361754 0.8652005 -0.4995242 -0.04363214 0.8652085 -0.4995119 -0.0436154 0.8652058 -0.4995168 -0.04361069 0.8652062 -0.4995146 -0.04362809 0.8651999 -0.4995235 -0.04365164 0.8652077 -0.4995136 -0.04361081 -0.8651989 0.499527 -0.04363048 0.865207 -0.4995149 -0.04361093 0.8652005 -0.499524 -0.04363441 -0.4995211 -0.8652034 -0.04361027 0.4995121 0.8652074 -0.04363584 0.4995233 0.865202 -0.04361546 1.09929e-6 0 -1 -0.499526 -0.8651993 -0.04363369 0.4995238 0.8652021 -0.04360258 -0.5007371 -0.8645036 -0.04354184 -0.4994859 -0.8651352 -0.04533088 -0.4995228 -0.8652023 -0.04361325 0.001858353 -0.001072764 -0.9999977 8.81371e-4 0.001526653 -0.9999985 0.4995353 0.8651939 -0.04363542 0.499521 0.8652037 -0.04360616 0.4995256 0.8652009 -0.04360967 0.05087435 0.01915144 -0.9985214 0.02177387 0.03771454 -0.9990514 -0.4995256 -0.8651998 -0.04362851 -0.4995067 -0.8652121 -0.04360359 -0.4995102 -0.8652089 -0.04362273 0.4995325 0.8651961 -0.04362434 0.4995315 0.8651977 -0.04360365 0.4995133 0.8652073 -0.04362213 0.05087471 0.01915138 -0.9985214 -0.02994495 0.01728826 -0.9994021 0.4995356 0.8651943 -0.04362499 -0.02994477 0.01728826 -0.9994021 0.02177447 0.03771406 -0.9990513 -0.4995263 -0.8651991 -0.04363465 0.4995272 0.8651989 -0.04362964 0.4995215 0.8652017 -0.04364007 -0.4995076 -0.86521 -0.04363542 -0.4995227 -0.865202 -0.04361933 0.4995266 0.8651998 -0.04361897 0.4995226 0.8652026 -0.04360949 0.4995284 0.8651992 -0.04360842 -0.4995286 -0.8651995 -0.04360324 -2.17893e-7 0 -1 0.4995312 0.8651972 -0.04361933 0.4995197 0.8652042 -0.04361116 0.05087471 0.01915156 -0.9985215 -0.4995071 -0.8652111 -0.04361951 -2.179e-7 0 -1 0.4995224 0.8652022 -0.04362028 0.05087471 0.01915127 -0.9985215 -0.4995253 -0.8652005 -0.04361951 -0.4995235 -0.8652015 -0.04361778 0.4995259 0.8652 -0.04362446 0.4995227 0.8652022 -0.04361557 0.4995242 0.8652009 -0.04362452 0.05087453 0.0191515 -0.9985215 -0.4995231 -0.8652017 -0.043621 0.4995213 0.8652026 -0.04362457 0.499522 0.8652026 -0.04361563 -0.02994483 0.01728838 -0.9994021 0.02177476 0.03771477 -0.9990513 -0.4995205 -0.8652031 -0.04362171 -0.4995232 -0.8652018 -0.04361921 0.4995219 0.8652026 -0.04361659 0.4995216 0.8652025 -0.04362338 0.4995243 0.865201 -0.04362189 0.4995233 0.865202 -0.04361271 0.05087482 0.01915132 -0.9985215 0.02177464 0.0377146 -0.9990514 -0.4995206 -0.865203 -0.04362434 -0.4995235 -0.8652019 -0.04361182 0.4995196 0.865204 -0.04361671 0.4995205 0.865203 -0.04362326 0.4995253 0.8652002 -0.04362499 0.05087465 0.01915144 -0.9985214 -0.02994483 0.01728856 -0.9994021 -0.4995259 -0.8652001 -0.04361921 -0.4995222 -0.8652023 -0.04361933 -0.4995241 -0.8652014 -0.04361641 0.08489412 -0.07277798 -0.9937286 5.40959e-7 0 -1 4.43122e-5 2.98556e-5 -1 0.4995224 0.865202 -0.04362446 0.4995233 0.8652014 -0.0436235 -0.4995226 -0.8652021 -0.04361921 0.02994471 -0.0172885 -0.9994021 -0.02994471 0.01728856 -0.9994021 -0.02994441 0.01728844 -0.9994021 -0.8002439 0.4620233 -0.382288 -0.8002172 0.4619953 -0.3823778 -0.8002423 0.4620198 -0.3822958 -0.8002799 0.4620448 -0.3821869 -0.8002523 0.4620289 -0.3822638 -0.8001954 0.4619986 -0.3824194 -0.8002476 0.462023 -0.3822806 -0.8002504 0.4620247 -0.3822728 -0.8002488 0.4620218 -0.3822795 -0.800277 0.4620366 -0.3822027 -0.8002461 0.462023 -0.3822842 -0.8002468 0.4620233 -0.3822823 0.8002243 -0.4620147 -0.3823399 0.8002423 -0.4620194 -0.3822962 0.8002215 -0.4620111 -0.3823498 0.8003039 -0.4620611 -0.3821169 0.8002613 -0.4620335 -0.3822395 0.8002396 -0.4620196 -0.3823013 0.8002544 -0.4620257 -0.3822636 0.8002426 -0.4620206 -0.3822939 0.8002447 -0.4620233 -0.3822863 0.800248 -0.4620221 -0.3822808 0.4995337 0.8651964 -0.04360389 0.4995231 0.8652013 -0.04362773 0.4995189 0.8652047 -0.04360985 0.01419931 0.002962291 -0.9998948 0.04102283 -0.005831241 -0.9991413 0.2493874 0.7818177 -0.5714605 0.2475619 0.7820117 -0.5719886 0.2085561 0.7928168 -0.5726658 0.1192163 0.810971 -0.5728121 -0.2077252 0.7909383 -0.5755579 -0.3661988 0.7318378 -0.5747277 -0.2473616 0.7831007 -0.5705837 -0.516018 0.632574 -0.5775602 -0.5889626 0.5726935 -0.5702152 -0.7262135 0.374031 -0.5768144 -0.5940355 0.5691393 -0.5685089 -0.8216958 0.05392116 -0.5673699 -0.8185882 0.02687913 -0.5737516 -0.8165498 -0.08152377 -0.5714895 -0.8178432 -0.1012774 -0.5664587 -0.7760061 -0.2468394 -0.580418 -0.6128069 -0.5347409 -0.5818248 -0.4003782 -0.6934345 -0.5990375 -0.3067404 -0.7799188 -0.5455613 -0.1166549 -0.8121516 -0.5716655 -0.1439383 -0.7990981 -0.5837157 -0.2092378 -0.7929842 -0.5721851 -0.5765046 -0.58468 -0.5707818 0.03572851 -0.8170052 -0.5755225 0.2065462 -0.7903135 -0.576839 0.5148962 -0.6321951 -0.5789745 0.7201948 -0.3869196 -0.5758584 0.7326924 -0.3687216 -0.5720195 0.7901646 -0.2328602 -0.5669357 0.7959368 -0.1926005 -0.5739248 0.7729825 0.2245321 -0.5933662 0.6328321 0.5198123 -0.5738631 0.3206351 -0.7574845 -0.5686919 0.4546313 -0.6861109 -0.5679457 0.698823 0.4307621 -0.5710433 0.1575331 0.8086988 -0.5667359 0.7652022 0.3026186 -0.5682321 0.8379808 0.1171419 -0.5329784 0.8251701 -0.06141859 -0.5615356 0.802642 0.1753934 -0.5700903 0.8223741 0.04018157 -0.5675266 -0.3815883 0.7270935 -0.5707237 -0.3138043 0.7871048 -0.5310301 0.9610376 -0.2763996 0.003154873 0.9759847 -0.2178184 -0.002997756 0.9971153 -0.07583844 0.003112375 0.9998533 -0.01687377 -0.002956688 0.9827896 0.1847057 -0.002909898 0.9254694 0.3788118 -0.002856433 0.7011133 0.7130442 -0.002866566 -0.03377461 0.9994263 -0.002553403 -0.2342637 0.9721699 -0.002497017 -0.4251627 0.9051138 -0.002436995 -0.8660272 0.4999917 -0.002258896 -0.996434 -0.08435195 -0.002058327 -0.8824142 -0.4704695 -0.001927614 -0.6253471 -0.7803379 -0.003730118 0.9917868 0.1278659 0.003064692 0.9452565 0.3263142 0.003023147 0.7376897 0.6751335 0.002931535 0.5856489 0.8105597 0.002896487 0.2164087 0.976299 0.002756297 -0.1894503 0.9818868 0.002647578 -0.3845707 0.923092 0.002589046 -0.563709 0.8259696 0.00253117 -0.8452959 0.5342931 0.002402961 -0.9361855 0.3514987 0.002345025 -0.9988139 -0.04863888 0.002219021 -0.9681933 -0.2501942 0.002142846 -0.7825842 -0.6225408 0.002249419 -0.4555016 -0.8902173 -0.005624413 -0.3723765 -0.9280775 0.002821922 -0.1629313 -0.9865796 0.01068222 -0.06751525 -0.997713 -0.003247022 0.06613969 -0.9978047 0.003369688 0.1346942 -0.990882 -0.00321263 0.3314249 -0.9434759 -0.00331372 0.5145597 -0.8574488 -0.003169298 0.6766224 -0.7363237 -0.003116071 0.810981 -0.5850639 -0.00319302 0.8849697 -0.4656378 0.003207981 0.4565912 -0.8896704 0.003327667 0.77269 -0.6347753 0.003248155 0.8591681 -0.4960353 -0.125615 0.818384 -0.4744253 -0.3242968 -0.625776 0.3482045 -0.6979671 0.2833703 -0.1643725 0.944819 -0.1406815 -0.2550376 0.9566423 0.357252 -0.1284941 0.9251272 -0.1305521 0.01654016 0.9913035 -0.04541438 0.03808832 0.9982419 0.4631049 -0.3612287 0.8093502 -0.2415285 -0.7440012 0.6229978 -0.9270746 0.3655079 0.08328723 -0.7020146 -0.6380219 0.3163915 -0.7173092 0.362153 0.5952418 -0.9163456 -0.4001419 -0.01404649 -0.689369 0.400529 0.6036115 -0.8727916 -0.1706755 0.4572798 0.7692858 0.04616045 0.6372351 -0.992163 0.1232235 -0.02070504 -0.8475953 -0.5299166 0.02775967 -0.2275831 0.1005028 0.9685583 0.02220505 0.0689308 0.9973743 0.01777017 -0.01887148 0.9996641 -0.04624915 -0.5374436 0.8420305 -0.9638696 -0.2562055 0.07289999 0.1156451 0.4107894 0.9043663 0.8036323 0.5875271 0.09480112 0.6047291 0.4735522 0.6403523 0.9497246 -0.3021023 0.08220404 0.9885607 0.1461403 0.0372945 0.3899863 -0.210276 0.8964903 0.8682528 -0.4959723 -0.01219654 0.8653524 -0.5006996 -0.02157324 0.7042973 0.7093066 0.02914881 0.9950568 -0.07146471 -0.06895518 0.983638 0.08829843 -0.1570344 0.08635205 0.9845623 -0.1522519 -0.9472056 -0.2942702 0.1273061 0.2856705 -0.9401991 0.1855208 0.8084306 0.5718515 0.1393771 -0.7108739 -0.7013592 -0.05247479 0.9903877 0.1278817 -0.05271345 0.972848 0.2204155 0.07059651 0.6558987 -0.7538036 -0.03971338 -0.7622788 0.4813778 -0.4326736 -0.7979143 -0.4886828 0.3528769 -0.1717376 0.9373058 0.3032558 0.9835409 0.09032261 0.1564902 -0.9853692 0.1549366 0.07100963 0.1365845 0.9864486 -0.09090697 -0.6263636 -0.7759445 -0.07469242 -0.9092315 -0.4136536 0.04678475 -0.6655728 0.7455676 -0.03379243 0.7886143 -0.5424652 -0.2895151 0.8022428 0.4944508 0.3345519 -0.3648713 -0.9183464 -0.1533256 0.3480505 0.9334862 -0.08639764 0.1446893 -0.9876224 -0.06055498 0.5010995 -0.857214 -0.1186746 -0.8841161 -0.2625729 0.3865156 -0.3085383 0.9486761 -0.06941127 0.7021462 -0.6908424 -0.1724166 0.5000924 0.8657654 0.01892352 0.6896834 -0.7180913 -0.09317523 -0.801461 -0.5857974 -0.1204231 -0.8039245 -0.01643311 0.5945043 -0.721244 -0.3662919 0.5879094 -0.4759477 0.6696286 0.5701503 -0.4772039 0.6645755 0.5749921 -1.35514e-6 -8.27524e-7 -1 -2.18627e-4 1.88033e-4 -1 1.53438e-4 4.45336e-5 -1 1.28253e-5 -4.94801e-6 -1 1.46081e-4 -1.10157e-4 -1 6.89019e-4 -3.96344e-4 -0.9999997 0.006438672 0.04006212 -0.9991765 0.1254476 -0.464451 -0.8766688 0.03627485 0.03771448 -0.9986301 -0.0233798 6.79121e-4 -0.9997265 -0.0096547 0.05235815 -0.9985818 -2.38993e-4 4.75379e-4 -1 0.8186712 -0.03837603 0.5729789 0.8742895 -0.2786214 0.397477 0.7572295 0.2996734 0.5803443 0.7297561 0.3553911 0.5840831 0.7298964 0.3543714 0.5845273 -9.58569e-6 1.04593e-5 -1 -3.54916e-5 1.07869e-5 -1 -0.001163959 0.001014351 -0.9999988 0 4.1673e-7 -1 -1.47519e-4 1.10169e-4 -1 -6.94565e-4 3.99881e-4 -0.9999998 -0.05027979 -0.04772305 -0.9975944 -0.1626086 -0.1172823 -0.9796956 0.01252877 -0.06802082 -0.9976053 -2.11006e-4 2.09117e-4 -1 7.97173e-4 0.006875395 -0.9999761 -0.00444591 0.001630425 -0.9999888 0.09639525 -0.0119692 -0.9952712 0.8627747 0.452696 0.2251365 0.4523288 0.8672146 -0.2081769 -0.4557197 0.8144835 -0.3590769 0.4225804 -0.7671226 -0.4826475 -0.8585668 0.3218322 0.3991079 5.85491e-4 -0.002811908 -0.9999959 0.007565677 7.80634e-4 -0.9999711 -4.71991e-4 1.72486e-4 -0.9999999 0.002504706 0.004805326 -0.9999854 -6.27942e-4 0.001500725 -0.9999988 0.00210464 0.00436145 -0.9999884 0.3815603 -0.8212708 -0.424177 0.8585421 -0.3218358 0.3991581 0.6651231 0.7318251 0.1484702 -0.1872459 0.9801369 0.06535208 -0.8830127 -0.4634196 0.07437044 -0.04047983 -0.9593303 0.2793684 2.13626e-4 -0.002728462 -0.9999963 0.007218956 0.00105077 -0.9999735 0.002418637 0.004867792 -0.9999853 -0.006689965 -0.00519818 -0.9999642 -0.8678236 0.4961727 0.02636116 -0.5385017 0.5331257 0.6525281 0.8894938 -0.4495028 -0.08214688 0.8999522 0.3875877 0.1996543 9.72257e-6 3.25367e-5 1 6.188e-5 1.15726e-5 1 -2.12427e-4 5.48942e-4 0.9999998 -0.002551853 -0.003098487 0.999992 -0.03416639 -0.04986643 0.9981714 -0.0295825 -0.03965079 0.9987756 -0.04838883 -0.003887236 0.998821 -0.003053784 0.003051221 0.9999908 -0.001572251 8.84889e-4 0.9999984 -7.25529e-7 -9.69417e-7 1 -2.30294e-6 -7.36816e-7 1 1.05382e-4 0.001903653 0.9999983 6.71003e-4 0.001616537 0.9999985 -0.01494342 -0.005576193 0.9998728 0.01893693 0.0011276 0.9998201 -3.63657e-4 1.19863e-4 1 -4.16766e-5 1.37301e-5 1 -2.79374e-5 2.13657e-5 1 -0.002198636 0.01642167 0.9998628 0.03992784 0.01928216 0.9990166 -6.15059e-4 2.62498e-4 0.9999998 -1.90603e-4 9.27449e-6 1 -9.91854e-5 -5.72509e-5 1 -1.03429e-5 -4.39798e-5 1 -0.9533217 -0.3019569 -1.19701e-4 0.4073984 0.9130981 0.01668691 0.9759947 -0.2148903 0.03544849 -0.9501469 -0.3117833 -0.003474354 0.6472681 0.7582784 -0.07783383 0.1037044 -0.994469 0.01664298 -0.9533213 -0.3019581 -1.57792e-4 0.4074769 0.9130647 0.01659917 -0.9501813 -0.3116787 -0.003469944 0.5774726 0.8149713 -0.04844981 0.5560455 -0.3152456 0.7690473 0.6123785 -0.353556 0.7071002 0.8660249 -0.5000009 2.32046e-5 0.8660262 -0.4999988 8.52121e-6 -0.8660262 0.4999987 2.78456e-5 -0.8660252 0.5000004 1.70424e-5 -0.6123113 0.3535237 0.7071745 -0.6123854 0.3535599 0.7070923 0.02177441 0.03771436 -0.9990514 -0.4995245 -0.8652011 -0.04361623 0.6123837 -0.3535577 0.7070949 -0.6116899 0.3531012 -0.7079231 0.6123332 -0.3535265 0.7071542 0.6126204 -0.3537386 0.7067993 0.6123634 -0.3535464 0.7071181 0.6123164 -0.3535112 0.7071765 0.612377 -0.3535571 0.7071011 0.6123499 -0.3535338 0.7071361 0.6123689 -0.3535476 0.7071128 0.6113394 -0.3562505 0.7066469 0.6123667 -0.3535507 0.7071132 -0.6134935 0.3540809 -0.70587 0.6123746 -0.3535545 0.7071044 0.6123571 -0.3535458 0.7071238 -0.6057007 0.3570463 -0.7110869 -0.628705 0.3635057 -0.6874545 -0.6606708 0.3814378 -0.6465441 -0.6606712 0.3814338 -0.6465461 -0.6606696 0.3814347 -0.6465471 -0.6461246 0.294803 -0.7039988 -0.6461281 0.2947986 -0.7039974 -0.6461231 0.2947971 -0.7040026 -0.6606678 0.3814421 -0.6465446 -0.6606677 0.3814523 -0.6465387 -0.646123 0.2947905 -0.7040055 -0.6241248 0.4383372 -0.6467834 -0.6606599 0.3814309 -0.6465594 -0.6606635 0.3814513 -0.6465436 0.6123739 -0.3535529 -0.7071058 0.6123831 -0.3535156 -0.7071164 0.5708528 -0.2856083 -0.769776 0.660669 -0.3814367 -0.6465467 0.5783653 -0.4121611 -0.7040007 0.6606718 -0.3814329 -0.646546 0.5783599 -0.4121606 -0.7040053 0.5783633 -0.4121615 -0.7040019 0.660675 -0.3814347 -0.6465417 0.5783661 -0.4121688 -0.7039955 0.5783593 -0.4121618 -0.7040051 0.5783666 -0.4121567 -0.7040021 0.5783535 -0.4121577 -0.7040122 0.6606684 -0.3814362 -0.6465476 0.5783657 -0.4121632 -0.7039991 0.5783655 -0.4121633 -0.7039992 0.660667 -0.3814372 -0.6465485 -2.1789e-7 0 -1 -0.5186337 0.4421316 0.7318052 0.6056051 -0.2290577 0.7620861 0.9757862 -0.02807039 0.2169179 0.7826715 -0.07964974 0.6173179 0.9331997 0.04258686 0.3568261 0.9134135 -0.2791815 0.2961985 0.9948118 -0.09365457 -0.03972834 0.2655205 0.2095991 0.9410458 0.2333204 0.3337686 0.9133237 0.04180401 0.3598456 0.9320749 0.274267 0.2118079 0.9380378 0.5080912 -0.8425279 -0.1788585 0.3116686 -0.2747316 0.9096073 0.4928798 -0.3590815 0.7925465 0.1668015 -0.4460176 0.8793439 -0.01313561 -0.02953642 0.9994774 6.54416e-7 1.42411e-4 1 -0.8368649 -0.4015842 -0.3720046 -0.8834083 -0.4672661 0.03538966 -0.7476723 0.4602363 0.4787159 0.4887282 0.8717274 0.03516012 0.4889466 0.8716195 0.0347979 0.4606825 0.2268532 0.8580846 0.8834363 0.467213 0.03538757 0.8689304 -0.4937373 0.03440099 -0.1152753 -0.2489625 0.9616285 -0.4395244 -0.7300313 0.5233284 -0.4996899 -0.865587 0.03269994 -0.7611218 -0.4475003 0.4695075 -0.0016945 -0.002153158 0.9999963 0.001296818 0.006582736 0.9999775 -0.8834105 -0.4672626 0.03537881 -0.8854027 -0.4636105 0.03358012 -0.1480602 0.1777055 0.9728818 -0.0880801 0.9954634 0.03598135 -0.1039142 0.9941293 0.03014773 0.8854178 0.4635814 0.03358215 0.2405835 -0.04301995 0.9696746 0.1154798 0.2571269 0.9594532 0.02273511 0.03722113 0.9990485 5.81195e-5 2.65399e-4 1 0.4997434 0.8654673 0.0349701 0.4996572 0.8655116 0.03510493 0.8691292 -0.4933509 0.0349217 0.05352753 -0.8468391 -0.5291487 0.08981639 -0.9953331 0.03528779 0.1035094 -0.9941725 0.03011506 -0.4888046 -0.87169 0.0350266 -0.8834283 -0.4672297 0.03537172 -0.8853962 -0.4636217 0.03359532 -0.8652258 0.5005181 0.02942895 0.6429419 0.3219471 0.6949647 0.02157437 0.03508836 0.9991514 -4.70562e-5 -2.75769e-4 1 0.9004653 0.4331153 0.03966772 0.9071363 0.4194579 0.03404021 0.8658958 -0.4993562 0.02946376 0.5127922 -0.856192 0.06308346 -0.4887279 -0.8717284 0.03513932 -0.4889445 -0.8716224 0.03475362 -0.8834112 -0.4672595 0.03540074 -0.865216 0.5005344 0.02944093 -0.8691225 0.4933372 0.03527629 -0.1037694 0.9941469 0.0300647 0.1021613 0.2114886 0.9720267 0.3799134 0.6513871 0.6567806 0.6429525 0.321945 0.6949558 0.4753284 0.1795031 0.8613022 0.02157366 0.03508728 0.9991515 -4.70465e-5 -2.75798e-4 1 -3.83894e-5 -1.99862e-4 1 0.9004758 0.4331017 0.03957897 0.9069282 0.4199079 0.03403842 0.8658919 -0.4993627 0.02946734 0.8691281 -0.4933868 0.0344367 0.5127766 -0.8562002 0.06310039 -0.4231552 -0.6826611 0.5957462 -0.488729 -0.8717269 0.03516161 -0.8368632 -0.4015766 -0.3720168 -0.8854106 -0.4635948 0.03358697 -0.3978747 0.1400629 0.9066853 -0.8652117 0.5005424 0.02942782 -0.8691234 0.4933354 0.03528022 0.4917482 0.8700369 0.03492337 0.4753271 0.1795102 0.8613015 0.4569001 -0.2251846 0.860543 0.7475124 -0.4605573 0.4786567 -0.02167916 -0.04313004 0.9988343 0.9069329 0.4198979 0.03403657 0.5127547 -0.8562152 0.06307387 -0.4889771 -0.8716039 0.03475713 -0.836865 -0.4015641 -0.3720263 -0.8834133 -0.4672555 0.03540199 -0.8854079 -0.4635998 0.03358775 -0.3978692 0.1400545 0.9066889 -0.86522 0.5005279 0.02943426 -0.08882004 0.9954213 0.03532022 -0.1037729 0.9941467 0.03006201 0.1021558 0.2114818 0.9720287 0.6429604 0.3219601 0.6949415 0.4569414 -0.2252051 0.8605157 -4.70514e-5 -2.75778e-4 1 -3.83959e-5 -1.9987e-4 1 0.9004582 0.433138 0.03958106 0.9069266 0.4199121 0.03403204 0.8691228 -0.4933971 0.03442478 0.5127564 -0.8562127 0.06309366 0.08362066 -0.9958535 0.03582656 -0.4887299 -0.8717269 0.03514766 -0.8834106 -0.4672605 0.0354039 0.642956 0.3219603 0.6949455 0.456947 -0.2252052 0.8605127 0.7475566 -0.4605802 0.4785655 0.0215739 0.03508794 0.9991514 -0.02167838 -0.04312825 0.9988344 0.9004559 0.4331428 0.03958094 0.9069288 0.4199075 0.03402954 0.8691287 -0.4933853 0.0344448 -0.4231452 -0.6826431 0.595774 -0.836888 -0.4015942 -0.3719417 -0.8652126 0.5005409 0.0294283 0.3799316 0.6514267 0.6567307 0.4917498 0.8700361 0.03492105 0.4999445 0.8658139 0.02054059 0.7475458 -0.4605728 0.4785895 -0.0216884 -0.04314815 0.9988333 0.900474 0.4331043 0.03958749 0.865891 -0.499364 0.02946931 0.8691279 -0.4933868 0.03444463 -0.488729 -0.8717283 0.03512936 -0.8368903 -0.4015863 -0.371945 -0.8854265 -0.4635645 0.0335856 -0.3978367 0.1400408 0.9067053 -0.8691163 0.4933486 0.03527343 -0.08887088 0.9954176 0.03529763 0.3799175 0.6513989 0.6567665 0.6416773 0.3242681 0.6950542 0.4720041 0.1784722 0.8633423 0.02157354 0.03508704 0.9991514 -4.70713e-5 -2.7587e-4 1 0.08358645 -0.9958581 0.0357784 0.1034725 -0.9941762 0.03011989 -0.4231769 -0.682701 0.595685 -0.4887319 -0.8717246 0.03517955 -0.4889677 -0.8716086 0.03477245 -0.8834032 -0.4672735 0.03541588 -0.8691133 0.4933539 0.03527253 -0.0888611 0.9954177 0.03531897 0.3799344 0.6514317 0.6567241 0.4888212 0.8714622 0.04009634 0.1154547 0.2570727 0.9594706 1.83091e-6 8.37284e-6 1 0.8827874 0.4683816 0.03612834 0.3783958 -0.2121284 0.9010096 0.0535137 -0.8468109 -0.5291952 0.1035043 -0.9941729 0.0301184 -0.1207094 -0.171769 0.977714 -0.4888044 -0.87169 0.03502815 -0.4889368 -0.8716246 0.03480547 -0.4658786 -0.2275383 0.8550928 -0.8834245 -0.4672358 0.03538244 -0.4630676 0.1828929 0.8672478 -0.865221 0.5005262 0.02943247 -0.8690986 0.493381 0.0352568 -0.03776359 0.9986569 0.03547203 -0.05676877 0.9980028 0.02770829 0.900341 0.4337561 0.03523814 0.4302687 -0.235511 0.8714376 0.01199209 0.01411062 0.9998286 -0.4232096 -0.6826938 0.5956701 -0.8644132 0.5014265 0.03689658 0.6973482 -0.3293012 0.6366053 0.7393558 -0.3060539 0.5997368 0.3239614 0.1339364 0.9365416 -0.09566593 -0.4599234 0.8827903 0.4917625 -0.2989184 0.8178128 0.4937043 -0.2847436 0.8216917 0.4670931 -0.2485715 0.8485496 0.5362734 -0.2594563 0.8031771 0.4959289 -0.3482277 0.7954823 0.4969462 -0.2869338 0.818971 0.4962983 -0.2865206 0.8195084 0.4309775 -0.2528621 0.8662097 0.4666142 -0.2549316 0.8469245 0.4985066 -0.2879425 0.8176676 0.4975662 -0.345264 0.7957516 0.4532465 -0.2639909 0.8513967 0.4572358 -0.4853663 0.7452214 0.377773 -0.4530611 0.8074795 0.6436187 -0.3387585 0.6862928 0.4340707 -0.2596399 0.8626528 0.4542055 -0.2656161 0.8503797 0.4079251 -0.2542623 0.8768967 0.4303484 -0.2409284 0.869916 0.5179541 -0.1359611 0.8445344 0.5133726 -0.5435371 0.6640904 0.3865163 -0.2204292 0.8955535 0.4968551 -0.2868803 0.8190451 0.4962691 -0.286552 0.8195151 0.5093901 -0.3169053 0.800058 0.4895876 -0.2502776 0.8352636 0.4879381 -0.2469353 0.8372213 0.296455 -0.2914524 0.9094889 0.4556453 -0.2671754 0.8491199 0.2016667 -0.09912526 0.9744254 0.5721046 -0.277561 0.7717878 0.2337749 0.04118412 0.9714181 0.4903637 -0.2977281 0.8190857 0.4733376 -0.3124895 0.8235908 -0.2853434 0.9579232 0.03102254 -0.02015459 0.9991807 0.03509747 0.6370976 -0.2980664 0.7108187 0.6044456 0.5747647 0.5516258 0.3785907 0.5928121 0.7108045 -0.3230117 -0.5922227 0.7381976 -0.3763511 -0.665954 0.6441004 0.01641428 -0.3317166 0.9432363 -0.33029 0.001246869 0.9438787 -0.2471549 0.1986532 0.9483942 -0.1348105 0.3842023 0.9133537 0.3498338 0.1322513 0.9274298 0.40186 -0.1737123 0.8990733 0.6916366 0.04242563 0.7209986 0.3637199 0.1603467 0.9176039 -0.04089277 0.4396848 0.8972208 -0.2990743 0.5786725 0.7587442 -0.3680998 0.2458102 0.896705 -0.6453096 0.2969121 0.7038599 -0.4513937 -0.05590182 0.8905723 -0.4594631 -0.1461528 0.8760897 -0.07747197 -0.6385205 0.7656955 0.1296554 -0.620671 0.7732769 0.3893409 -0.9198015 -0.04877382 0.1518267 -0.9846954 0.08557915 -0.3892755 -0.9197683 0.04990917 -0.6019225 -0.7969897 0.04996824 -0.8126592 -0.5765957 0.08439546 -0.9917435 -0.04724669 0.1192168 -0.9680699 0.2506806 0 0.030757 -0.9982203 -0.05109202 -0.1531962 -0.986938 -0.04984354 -0.3617661 -0.9308763 -0.05093854 -0.6253037 -0.7787201 -0.05089473 -0.8798531 -0.4724885 -0.05112129 -0.9912357 -0.1227351 -0.04886531 -0.9996016 -0.02680128 -0.008864283 -0.9797306 -0.200085 -0.009700655 -0.9528068 -0.3030799 0.0173735 -0.7689856 -0.6385365 0.03053557 -0.6813153 -0.710991 -0.1740733 -0.2533409 -0.9583919 -0.1315429 0.2011107 -0.9793282 0.02170127 0.529832 -0.8481022 9.2114e-4 0.7012063 -0.7129584 0 -0.9980897 0.06156492 0.005173265 0.3897854 -0.9208589 0.009285271 0.6961343 -0.7179107 0.00117129 0.5523657 -0.8335968 0.002952575 -0.6986595 0.7068995 0.1103084 5.15497e-4 -3.7163e-4 0.9999998 8.22896e-4 -8.94706e-4 0.9999993 5.77502e-4 -9.6252e-4 0.9999994 7.24465e-6 -5.39495e-5 1 -3.73972e-6 -6.04806e-5 1 0.005110144 0.009987473 0.9999371 0.004524767 0.009475529 0.9999449 4.41888e-4 -3.60244e-4 1 0.005449235 0.006800889 0.9999621 3.34691e-4 9.85286e-5 1 3.23589e-4 2.74525e-5 1 1.17574e-4 -1.39086e-5 1 -3.57771e-4 4.77334e-4 0.9999998 -1.893e-4 4.03217e-4 1 -2.26466e-5 6.77862e-4 0.9999998 1.77028e-4 -5.55668e-5 1 -1.13953e-4 2.16344e-4 1 3.04802e-4 4.71395e-4 0.9999999 4.71111e-4 3.16684e-4 0.9999999 4.6518e-4 -1.03867e-4 0.9999999 4.26064e-4 -1.91599e-4 0.9999999 0.1954948 0.4959342 -0.846068 0.8782356 -0.4781889 0.006135165 0.8623254 -0.5063191 0.005999565 0.8540361 -0.5201848 0.005497694 0.8455362 -0.5338985 0.004585266 0.8368299 -0.547455 0.002997219 0.8279218 -0.5608437 1.72925e-4 0.8282831 -0.5602998 -0.003395199 0.8569748 -0.5153086 -0.007170796 0.9009952 -0.4338279 0.001075446 -0.8315801 0.5554045 7.95753e-4 -0.8261396 0.5634649 8.55585e-4 -0.8232769 0.5676172 -0.005081355 -0.837868 0.5458273 -0.00705868 -0.8474733 0.5307865 -0.007398366 -0.8659428 0.5000866 -0.007523953 -0.8747664 0.484492 -0.007163703 -0.8915048 0.4529805 -0.005293667 -0.8447438 0.5351415 0.005606174 -0.8615567 0.5076234 0.006209492 -0.8775116 0.4795243 0.005487918 -0.4498779 0.4119123 0.7924255 -0.6074219 0.7931023 0.04502636 -0.4810188 0.6112501 0.6284859 0.4635132 -0.2523777 -0.8493887 0.4147565 -0.2805752 -0.865595 0.03192704 -0.007286727 -0.9994637 0.4256299 -0.2257564 -0.8762838 0.4363676 -0.2492704 -0.8645505 0.4328395 -0.2517135 -0.8656156 0.4447611 -0.2614499 -0.8566397 0.4479341 -0.2617456 -0.8548943 0.4329838 -0.2449084 -0.8674936 0.4308179 -0.2554652 -0.8655251 0.4313214 -0.2589851 -0.8642272 0.4197402 -0.2593553 -0.8698006 0.4280041 -0.2606935 -0.8653619 0.4507858 -0.2796136 -0.8477078 0.4256618 -0.2697892 -0.8637279 0.4164748 -0.2715122 -0.8676578 0.4133904 -0.2704408 -0.8694654 0.4444234 -0.3084834 -0.8410267 0.4169538 -0.2837552 -0.8635002 0.4078768 -0.2844296 -0.8676038 0.4186007 -0.2457833 -0.8742793 0.4316092 -0.226043 -0.8732801 -0.8569645 0.5141574 0.03541076 0.9360825 -0.3165307 -0.153486 -0.8723191 -0.47666 0.1088793 -0.414408 -0.9100049 0.01253366 -0.8756568 0.4816553 0.03511935 -0.8799538 0.4737378 0.03541117 -0.8797191 0.4742051 0.0349825 0.146938 0.9861141 0.07738405 0.005270719 -0.001815557 -0.9999845 0 0 -1 6.21439e-7 0 -1 -6.01952e-7 0 -1 3.60598e-7 0 -1 0 0 -1 2.70247e-5 -1.15013e-5 -1 -2.82878e-6 1.13451e-6 -1 2.0413e-6 -1.09475e-6 -1 -9.77206e-6 -1.68952e-4 -1 0.005251646 0.001216888 -0.9999855 0.06791239 -0.06524097 -0.995556 -1.51529e-7 0 -1 0.01803022 -0.001823842 -0.9998358 -0.001259267 7.81923e-4 -0.999999 0.02138274 -0.02775186 -0.9993861 -0.002545952 0.001362919 -0.9999958 0.04230862 -0.01612687 -0.9989745 0.007814586 -0.004511654 -0.9999593 -0.006056725 0.003242313 -0.9999765 0.1070985 -0.04926151 -0.9930273 -0.006379306 0.003682792 -0.9999729 0.05337584 -0.02392554 -0.9982879 0.001166343 -0.002279877 -0.9999968 0.007815361 -0.00451225 -0.9999594 0.007816731 -0.004513204 -0.9999593 -0.001340091 7.80189e-4 -0.9999988 4.12474e-4 8.94003e-4 -0.9999995 0.05119007 -0.04112571 -0.9978419 -0.005846738 0.003630816 -0.9999764 2.66719e-5 -3.36977e-4 -1 0.09846317 -0.05389666 -0.9936802 0.007859766 -0.004543542 -0.9999588 -0.003870844 0.002238094 -0.9999901 1.23408e-4 -0.001106858 -0.9999995 0.04765295 -0.01384812 -0.998768 7.57541e-7 0 -1 0.08203476 -0.03769218 -0.9959166 0.0311855 -0.02442348 -0.9992153 0.07912349 -0.07491105 -0.9940462 0.8642953 -0.5017496 0.03522765 -0.1923639 -0.9797347 0.05582237 -0.627781 -0.7716231 0.1024155 0.8690537 -0.4934757 0.03503483 0.8779242 -0.4774814 0.03550583 0.1193878 -0.9911887 0.05737227 0.8883488 -0.4575474 0.03856027 0.8881366 -0.4579895 0.03819817 0.8908469 -0.4529188 0.0354461 -0.02803099 -0.9947308 0.09861552 -0.4975902 0.3661007 0.7863678 -0.8790163 0.4640206 -0.1096141 -0.9657834 0.06761574 -0.2503811 -0.6337846 -0.6773275 -0.3735567 -0.9660946 0.08834052 -0.2426052 -0.8924677 -0.301985 -0.3351215 -0.6500068 -0.6627689 -0.371791 -0.6823421 -0.1928299 -0.7051424 -0.7784739 0.6271218 -0.02639842 -0.7826464 0.6213293 -0.03761112 -0.7685953 0.6391262 -0.02791064 -0.270222 -0.8873562 -0.373603 0.1491569 -0.9272463 -0.3434625 0.5414308 -0.8025947 -0.2503885 0.8374197 -0.5347896 -0.1128199 -0.2489684 -0.8943072 -0.3717922 0.1847065 -0.9238936 -0.3351179 0.5595547 -0.7924914 -0.2426027 0.8602203 -0.4728488 -0.1908798 0.8376259 -0.5002824 -0.2193183 0.5201991 -0.6620584 -0.5395105 -0.1497999 -0.609112 -0.7788085 0.2646657 -0.6838027 -0.679975 -0.4666975 -0.8080793 -0.3594459 -0.02609324 -0.4111741 -0.9111834 -0.3207478 -0.5574559 -0.765744 0.6413055 0.7672857 0 0.7072039 0.707002 -0.003322541 3.6876e-4 -1.15434e-5 -1 5.71832e-7 0 -1 -6.43378e-7 0 -1 0 0 -1 1.44505e-6 0 -1 0.001479923 -0.00149095 -0.9999979 0.00102514 3.48998e-4 -0.9999995 -2.87806e-6 0 -1 0 0 -1 1.49086e-4 -1.74895e-4 -1 7.7391e-5 -1.58511e-4 -1 -0.322385 -0.5565311 -0.7657292 -0.3213961 -0.5566639 -0.7660482 -0.322399 -0.5565031 -0.7657436 -0.3925591 -0.2712573 -0.8788156 -0.8660259 0.4999992 -2.10089e-5 -0.6123753 0.3535569 0.7071025 -0.6123742 0.3535535 0.7071052 -0.612369 0.3535494 0.7071118 -0.6123856 0.3535623 0.707091 0.61259 -0.3537084 -0.7068409 0.6124005 -0.3535879 -0.7070652 -0.6125491 0.3536418 0.7069097 -0.6125739 0.3536299 0.706894 -0.612339 0.3535388 0.7071431 -0.6123738 0.3535475 0.7071086 -0.6123437 0.3535404 0.7071381 -0.6123915 0.3535591 0.7070874 -0.6139672 0.3516482 0.7066739 -0.6123734 0.3535501 0.7071076 -0.6461255 0.2947947 -0.7040014 -0.6606695 0.3814409 -0.6465438 0.0312398 0.009823262 -0.9994637 0.4913181 0.8698354 0.04464203 0.5050748 0.862365 0.03501713 0.4158064 -0.8954722 0.1588549 -0.3489528 0.5605883 0.7509812 0.001889109 0.01998531 0.9997985 0.001906692 0.009713828 0.999951 0.002201437 9.7491e-4 0.9999972 -2.91647e-5 2.60705e-4 1 1.81051e-4 5.42859e-5 1 1.82718e-4 2.83101e-5 1 0.06574773 8.36811e-4 0.9978359 0.03765153 -0.003174066 0.9992859 -4.7739e-4 -3.17592e-4 0.9999998 0.01844048 -0.7709777 -0.636595 0.4919093 -0.7118026 -0.5013605 -0.01149338 -0.983278 -0.1817483 0.2578782 -0.6324508 -0.7304142 0.1112244 -0.6525185 -0.7495658 0.05109608 -0.3821513 -0.9226861 0.4700555 0.1798025 -0.8641291 0.2412167 -0.03913307 -0.969682 0.1625787 0.2677935 0.9496604 -0.3690093 -0.6812833 0.6322066 0.04827219 -0.9964447 0.06905096 0.7225723 0.3607895 -0.5896781 0.7029186 -0.6065941 0.3714151 -0.9909561 -0.06330901 -0.118314 -0.7504967 -0.2307704 0.6192736 -0.8446676 -0.5352158 -0.008991241 -0.6627407 -0.4851821 -0.570415 0.6434891 0.5815609 -0.4977034 -0.7108717 -0.6699672 0.2140219 -0.3953177 -0.804183 -0.4438622 0.1425243 0.9806187 -0.1344392 -0.1277877 0.08226209 -0.9883843 -0.3794919 -0.8284677 -0.4118585 -0.1542484 -0.5796612 0.8001253 0.1651666 0.7120648 0.6824103 -0.2722337 -0.9594604 0.07296991 -0.5334648 -0.8376124 0.1175619 0.5285677 -0.8488782 -0.004701852 0.2328532 -0.9725108 -0.00145775 -0.1422683 -0.9898279 6.82002e-4 -0.2707331 -0.9623504 0.02419227 -0.2849633 -0.9585341 -0.002897083 -0.3670079 -0.9302074 0.004406929 0.08104062 -0.9964091 0.02452254 -0.1626379 -0.9866304 0.01045942 -0.1049348 -0.9940094 -0.03056114 -0.3685967 -0.9295753 0.005123257 -0.5232749 -0.8521292 -0.007702171 -0.6868659 -0.7267751 0.003646135 -0.6490063 -0.7606779 -0.01264619 -0.4397574 -0.8977953 -0.02402096 -0.4163068 -0.9092242 2.57256e-4 -0.6979252 -0.7160676 0.01215279 0.2807626 0.9554526 0.09100949 -0.8371268 -0.5467925 0.01538473 -0.9886586 -0.1501392 -0.003507316 -0.9999085 -0.01272779 -0.004610955 -0.7879464 0.6057296 0.1105994 -0.9101809 -0.411601 0.04642742 -0.8205514 -0.5715684 -0.00225383 -0.9336777 -0.3581024 0.002926349 -0.9259011 -0.3777661 1.05523e-4 -0.869971 -0.4911949 0.04333609 -0.7776485 -0.6283576 -0.02072703 0.0733354 -0.9971683 -0.016658 -0.5343599 -0.845092 0.01670843 -0.1513261 -0.9879177 -0.03345131 0.6435317 0.7584592 -0.1029889 -0.6109781 -0.482618 -0.6275234 -0.705056 -0.2247647 -0.6725897 -0.6106899 -0.09750914 -0.7858434 -0.4773347 0.07046169 -0.875892 -0.4752729 0.09956973 -0.8741863 -0.3026914 -0.06994223 -0.9505189 -0.1260501 0.4287403 -0.894591 0.3695673 -0.618333 0.6936025 0.4098834 -0.631844 0.6578516 0.4111549 -0.6318398 0.6570619 -0.4992782 -0.866441 0.001192629 -2.26599e-4 5.87237e-4 0.9999998 3.12602e-5 5.74741e-5 1 3.56967e-7 0 1 -3.11648e-7 0 1 0 0 1 2.03173e-7 0 1 1.24929e-7 0 1 -5.80205e-7 0 1 -2.4938e-7 0 1 2.46453e-6 -4.90713e-7 1 -7.26657e-6 -5.8564e-7 1 -5.34898e-6 2.7448e-6 1 0 0 1 0 0 1 4.73751e-5 6.62665e-4 0.9999999 -2.80497e-7 0 1 -3.76327e-7 0 1 0.6705534 -0.2599969 0.6948093 -0.7529297 0.0397697 0.6568984 -0.7529311 0.03977316 0.6568965 -0.721403 0.01184988 0.6924142 -0.5604572 0.4507033 0.6948052 0.3534503 0.612229 0.7072825 -0.4589667 0.5322606 0.7113707 0.2568479 0.7182093 0.6466875 0.001814663 0.6765735 0.7363729 -0.008955061 0.6890799 0.7246301 -0.281987 0.7369683 0.6142972 0.6470953 0.7623852 -0.006048679 0.8696547 0.4933362 -0.01789224 0.8723677 0.48853 -0.01769596 0.9806631 -0.192758 -0.03382533 0.9318029 -0.3613224 -0.03448873 -0.3538777 0.9348967 -0.02718329 -0.7286354 0.6843377 -0.02779281 -0.01310604 0.9997575 -0.01769655 0.7445888 0.6672266 -0.01990896 -0.1260729 0.9913214 -0.03724956 -0.886666 0.4589611 -0.05637413 -0.5049156 -0.8630028 -0.0169211 0.3598286 -0.932806 -0.01990747 0.03449159 0.9992617 0.01692116 0.272725 -0.9618861 0.01990753 -3.76828e-4 -3.37143e-4 -1 4.62359e-4 -8.35942e-5 -0.9999999 0.002965092 0.009452819 -0.999951 1.03918e-4 -0.007635295 -0.9999709 -2.39367e-5 1.86845e-4 -1 -0.009249091 0.004786908 -0.9999458 -0.02667552 -0.01059907 -0.999588 -1.65358e-4 4.30884e-4 -1 0.7435551 0.6662939 -0.05637681 -0.1259655 0.9904314 -0.05637574 -0.8962469 0.4426659 -0.02808296 -0.9460595 -0.3219153 0.03663438 0.2727164 -0.9618886 0.01990771 4.59984e-4 -8.61265e-5 -0.9999999 -0.004530727 -0.005873084 -0.9999725 -0.05514609 0.0348283 -0.9978708 -0.01050192 -0.02512288 -0.9996293 0.01165741 -0.01091086 -0.9998726 -4.07506e-4 9.76158e-5 -1 -2.30159e-5 1.84617e-4 -1 -0.007930159 0.005291104 -0.9999546 -0.008720815 -0.0127933 -0.9998802 -1.66254e-4 4.32918e-4 -0.9999999 -0.2016741 -0.9792469 0.02007657 -0.8776569 -0.4792818 0.002716839 -0.9889835 0.1470167 0.01726001 0.3292818 0.943785 -0.02904355 0.7517298 -0.6584185 -0.03724879 -0.9944754 0.1049392 0.002561151 -0.08044284 0.9964258 -0.02578294 0.9680271 0.2444291 -0.05637413 0.09454435 0.1511046 0.9839863 0.2651856 -0.9624645 0.05778211 -0.114722 -0.9917876 -0.05653685 0.9701157 0.2419261 -0.01863557 0.9212046 -0.3873792 0.03632885 -0.8814007 -0.4689934 -0.0563746 -0.1259635 0.9904317 -0.05637598 0.990301 0.1360703 0.02808362 -0.09776288 0.11868 0.988108 -0.1153002 -0.2360267 0.9648821 0.2564045 -0.01138001 0.9665027 -0.8734242 -0.4861497 -0.02808272 -0.5877466 0.808288 0.03499418 0.8022705 0.5957977 0.03724819 0.7954245 -0.6049444 -0.03663742 -0.9304088 -0.3653065 0.02984517 -0.1260723 0.9913214 -0.03725057 0.6967726 0.7170925 -0.0169211 0.004063248 -0.009968161 0.9999421 -0.02960157 -0.01613461 0.9994316 0.01139843 0.009273171 0.9998921 0.01287686 -0.005525648 0.9999019 0.0111013 -0.003776013 0.9999313 6.43228e-4 0.01863378 0.9998262 0.01285749 0.009548604 0.9998719 0.3773113 -0.9256607 -0.02808183 -0.9215472 -0.3864754 0.03724873 -0.5046498 -0.8625466 -0.03663408 -0.9032397 -0.4285802 0.02184188 -0.9938708 0.1048635 -0.03499352 -0.6277292 0.7779472 -0.02746492 0.004061877 -0.009965002 0.9999421 -0.006574511 -0.003381013 0.9999728 1.98549e-4 7.00374e-4 0.9999998 3.08623e-4 4.16485e-4 0.9999999 -0.004675745 -0.008724808 0.999951 -0.03977549 -0.005829393 0.9991917 0.01084107 -0.004979431 0.9999288 0.01042211 -0.004369616 0.9999362 -0.008350074 0.004124045 0.9999567 0.008988142 0.01866841 0.9997854 0.6689034 -0.1241473 0.7329092 -0.2772259 -0.4433619 0.8523944 0.2455736 -0.9691805 0.0195623 0.2725542 -0.9619413 -0.01957929 0.7050195 0.7088761 -0.02102798 -0.7029505 0.7111568 -0.01079756 -0.5344732 -0.8451843 0.001348614 -0.669911 -0.7422594 0.01643896 -0.9191904 0.3937249 0.008362293 -0.2613279 0.9652062 0.009210169 0.7062601 0.7077134 0.01840174 0.9657926 -0.2586659 0.01834988 0.842625 0.5384992 -0.00135076 0.9990656 -0.04319846 -0.001359343 0.4621664 -0.8867923 -0.001351475 0.2455638 -0.969183 0.01956385 0.04397648 -0.9990317 0.001336812 0.9657943 -0.2584713 -0.02083742 -0.7015141 -0.7124347 -0.01774334 -0.6699316 -0.7422409 0.0164383 -0.8281223 -0.5605472 -4.62853e-4 -0.9848082 -0.1733816 -0.009577512 -0.9347282 0.3553496 0.003162503 -0.261319 0.9652087 0.009208858 0.9657961 -0.2586527 0.01834952 0.8870355 -0.4616993 -0.00134927 -0.07249253 0.9973682 -0.001289248 0.8426109 0.5385212 -0.001350581 0.8656595 -0.4997193 0.03023576 0.8693686 -0.4929376 0.03479909 -0.9000846 -0.4335994 0.04288667 -0.599003 0.7990216 0.05253583 0.8693729 -0.4929479 0.03454464 0.6639171 -0.746166 0.04950273 0.9781812 -0.2019923 0.04858887 0.6639304 -0.7460302 0.05133789 0.9790903 -0.2021961 0.02234274 0.8656512 -0.4997213 0.03044164 0.8692566 -0.4931369 0.03477382 -0.86941 0.4928821 0.03454655 -0.6640458 0.7460515 0.04950249 0.06778103 -0.9968501 0.0411787 -0.9858558 -0.1442285 0.08536213 -0.8739539 -0.4823607 0.05943614 -0.8657333 0.4998305 0.0259881 -0.8707389 0.4905557 0.03419095 -0.9106993 -0.411307 0.03812438 -0.8693225 0.4930212 0.03476232 -0.9118358 -0.4088691 0.03717273 -0.6639481 0.7459977 0.05157941 -0.5731047 0.8172931 0.05986005 0.2584381 0.9631019 0.07513034 -0.5555793 0.8293499 0.05924749 0.8990718 0.4361281 0.0382409 0.04673665 -0.9981573 0.03870117 0.06617951 -0.9966141 0.04879248 -0.865494 0.4997022 0.03489625 -0.8652728 0.5001013 0.03466308 -0.6639541 0.7461221 0.04966747 -0.1282969 0.991209 0.03231972 -0.1070891 0.9935655 0.03687256 -0.8523939 0.5216864 0.03560918 -0.8426501 0.5372547 0.0360316 -0.8307695 0.555318 0.0380004 -0.06924784 0.9968908 0.03759759 0.0390554 -0.9979614 0.05047649 0.1049325 -0.9940462 0.02934944 -0.4883245 -0.8710745 0.05261719 -0.8616293 0.5066738 0.0296055 0.03825294 -0.9982365 0.04539614 0.06536418 -0.9970064 0.04130434 0.07533288 -0.9959746 0.04857856 0.03736144 -0.9986267 0.03672575 -0.8707339 0.4905644 0.03419232 0.4724656 0.8803921 0.04106301 0.8662852 0.4983184 0.03505772 0.6639956 -0.7460486 0.05021494 0.1358683 -0.9900855 0.03564453 0.8657296 -0.4998365 0.02599495 0.8707363 -0.4905598 0.03419649 0.4283725 -0.9011391 0.06667321 -0.4419442 -0.8959435 0.04439318 0.5506837 -0.8310996 0.07759493 -0.8955216 -0.441612 0.05495393 0.4132777 -0.9053475 0.09771186 -0.3496502 -0.9360827 0.03865373 -0.8786917 -0.4760025 0.03636568 -0.9004596 -0.431927 0.05110287 0.1167578 -0.9924357 0.03793692 0.09898388 -0.994504 0.03411942 -0.8858629 0.461324 0.04926526 -0.8940935 0.4466832 0.03272628 0.6135028 -0.3519286 0.7069376 0.5960652 -0.3452045 0.7249415 0.1870888 0.1604821 0.9691457 0.4994069 -0.05021637 0.864911 0.4866309 -0.3675204 0.7925398 0.4321674 0.8680697 0.2443083 0.1617923 -0.1142539 0.9801885 -0.6332778 0.3322622 0.6989715 -0.2046954 0.0350725 0.9781973 -0.5307181 -0.8075333 0.2573488 0.3596193 -0.221895 0.9063315 0.8693873 -0.492895 0.03493487 -0.4311329 -0.5091344 0.7449207 0.7061856 -0.3507736 0.6150283 0.4226351 -0.2421954 0.8733391 0.8651216 -0.4994646 0.04582393 0.8439745 0.5338839 0.05172085 -0.02826493 0.402742 0.9148771 0.5747217 -0.3342928 0.746956 0.2384904 0.8959655 0.3746578 0.05033087 0.971155 -0.2330772 -0.6758764 0.3741531 0.6349809 -0.2231444 -0.9644665 0.1414602 0.1186015 -0.9918742 0.04603749 -0.1368752 -0.3969684 0.9075689 -0.1649134 0.03225135 0.9857807 -0.7097241 -0.6582847 0.2509043 0.6351488 0.6375849 0.435972 0.1267364 -0.04394793 0.9909625 -0.7307536 0.4182134 0.5395339 -0.6599597 0.3505762 0.6644919 -0.8376986 -0.4923279 0.2363772 0.8974322 0.4399403 0.03268057 -0.8814007 -0.06194758 0.46829 -0.1608574 -0.889712 0.4272441 0.1813528 0.6196384 0.7636489 -0.0711463 0.6181087 0.7828665 0.1186219 0.9911937 0.05885732 -0.2171126 0.6061183 0.7651685 -0.3470575 -0.7559751 0.5550251 0.481894 -0.3282549 0.8124205 -0.4235041 0.2444681 0.8722841 -0.8798227 -0.01457774 0.4750787 -0.1414824 -0.8203212 0.5541265 -0.09021991 0.109556 0.9898778 0.6194462 -0.4603005 0.6359323 0.5516209 0.7225326 0.4167267 -0.3725082 0.924075 0.08557611 -0.1150523 0.9915466 0.05998659 -0.7052711 -0.1661833 0.6891849 -0.6168227 0.349293 0.705354 0.1256533 0.3559769 0.9260085 -0.5042119 -0.7082499 -0.4941179 -0.1616376 0.98636 0.0311039 -0.3371833 0.5606521 0.7562914 -0.1872546 -0.7690932 0.6110904 0.08712702 -0.08786791 0.9923146 0.6258614 -0.3179826 0.7121691 -0.06112343 0.691492 0.7197937 0.4193553 0.8823925 -0.213365 -0.6179473 0.3250405 0.7158839 -0.9034072 -0.04887342 0.4259894 -0.1740916 -0.2819864 0.9434913 -0.1817791 -0.1294386 0.9747831 0.4294809 -0.2472457 0.8685712 0.4236511 -0.2445462 0.8721908 0.2138572 0.9342818 0.2852768 -0.5449344 -0.7484853 0.3779104 0.3843477 -0.919256 0.08511978 0.1245078 -0.9903713 0.06051909 0.5861831 -0.3395228 0.7356044 -0.3312344 -0.433498 0.8380712 -0.006775259 0.03485304 0.9993695 0.214412 -0.9761199 0.03488987 -0.04321324 -0.1656095 0.9852442 0.4234913 -0.2444566 0.8722937 0.05881446 0.1277841 0.9900567 -0.1479513 0.1157914 0.9821928 -0.1590818 0.1251372 0.9793027 0.03060859 -0.6765424 0.7357674 -0.8873813 -0.4594737 0.03792828 -0.8989624 -0.4356156 0.04588896 0.3745694 -0.9232493 0.08549141 0.06742155 0.4411653 0.8948898 0.579193 -0.3361288 0.7426661 -0.1858645 -0.2983409 0.9361876 0.8438494 0.2176423 0.4904593 -0.404321 0.6522461 -0.6411705 0.2112918 -0.6381071 0.7403885 0.1099568 -0.9933096 0.03529363 0.1210951 -0.9919034 0.03825801 -0.3110085 -0.08550351 0.9465532 0.6161579 -0.3815338 0.6890438 0.5680616 -0.2814806 0.7733529 -0.1254137 0.07657951 0.9891446 -0.5619462 0.457468 0.6891585 -0.8970556 -0.440146 0.03953289 -0.5759728 -0.8164946 0.03990006 0.2338198 0.8737961 0.4263904 0.5520793 0.2444573 0.7971507 0.07433569 3.4342e-4 0.9972332 -0.6665841 0.4116455 0.6214609 0.5218546 -0.5417986 0.6588795 0.2815673 -0.6728681 0.6840822 -0.3086615 0.725784 0.6147893 0.5749804 -0.3358573 0.7460546 0.5853478 -0.3390472 0.7364883 -0.03062164 -0.4376132 0.8986418 0.1069071 -0.9934821 0.03955262 -0.7389165 -0.3800823 0.5563632 0.2023401 0.2538534 0.9458419 -0.09796094 0.5532029 0.8272668 -0.5711677 -0.7521442 0.3287044 0.6371227 -0.3608258 0.6810869 0.6543938 -0.3776948 0.655069 0.6500759 0.6104122 0.4525465 -0.9986919 0.03267192 0.03933382 0.2265471 -0.07615661 0.9710183 -0.4295173 0.2473747 0.8685165 -0.423466 0.2444506 0.8723077 -0.1194629 -0.1064463 0.987116 -0.2466389 0.1349071 0.9596716 0.6796741 -0.4249455 0.5978834 -0.3862523 0.918466 0.08502709 -0.6185176 0.349055 0.7039863 0.08162891 0.3613899 0.9288349 -0.7782378 -0.06473934 0.6246238 -0.5922997 0.289934 0.7517443 0.8292526 0.5214311 0.201122 -0.5467576 0.463661 0.6971905 -0.1031289 0.9936108 0.0458486 -0.4124198 0.8275614 0.3808569 -0.4313788 0.2495509 0.8669699 -0.4368371 0.252166 0.8634731 -0.1701586 -0.05285829 0.983998 0.006184875 0.6091315 0.7930453 0.8802312 0.4731379 0.03652 -0.3776527 0.9220032 0.08537292 -0.2925781 0.4277002 0.8552606 -0.4886707 -0.02905386 0.8719844 0.04597932 -0.9907642 0.127563 0.06207233 -0.0721541 0.9954602 0.07887762 0.5991812 0.7967184 0.3637911 0.6033143 0.7096957 -0.7614191 0.200204 0.6165707 -0.4235442 0.9034047 0.06686061 -0.2975875 0.9531757 0.05383276 -0.8725307 0.03755372 0.487114 0.1585564 -0.07700163 0.9843428 0.5699923 -0.4599732 -0.680833 -0.0927658 0.9950995 0.03423058 -0.113586 -0.09658396 0.9888224 0.4392254 -0.2585925 0.8603552 0.864224 0.02529412 0.5024712 -0.05735707 0.2349128 0.9703227 0.4422589 0.4117399 0.7967919 -0.04107904 -0.04869198 0.9979687 -0.9029815 -0.4274469 0.04374533 0.1142581 -0.9916206 0.06028014 -0.550392 0.8263942 0.1189177 -0.3009223 -0.5455691 0.7821767 0.6299301 0.5547155 0.5435796 -0.1797091 0.7748344 0.6060827 -0.6916595 0.3993268 0.6017851 -0.8039937 -0.09664261 0.586732 -0.8657383 0.4992519 0.03528076 -0.8654975 0.499696 0.03490096 -0.9610956 -0.272403 0.04573756 0.6886581 -0.3580026 0.6305428 0.2617737 0.9358457 0.2359396 -0.02291983 -0.3149632 0.9488271 -0.6017068 0.3419857 0.7217997 0.1614536 0.3473218 0.9237427 0.6916069 0.3617804 0.6251359 0.002416372 -0.683381 0.730058 -0.6553361 -0.3613055 0.6633197 -0.02940249 0.6967429 0.7167182 0.3002984 0.5550891 0.7756915 0.4366863 0.735013 0.5187109 0.671751 0.350273 0.6527323 0.6035094 0.3456591 0.7185375 0.08187389 -0.7208904 0.6881961 -0.7146545 -0.3819965 0.5859588 -0.6073654 0.344314 0.7159296 -0.5879997 0.3388078 0.7344833 -0.02774065 0.6244135 0.7806013 0.437053 0.7346 0.5189872 -7.30597e-4 0.003076195 0.9999951 0.6713237 0.351365 0.6525849 0.620962 0.3483171 0.7021976 0.5947742 -0.3413433 0.7278245 0.05820661 -0.7197566 0.6917821 0.05179595 -0.708574 0.703733 -0.7136042 -0.3814704 0.5875794 -0.5881602 -0.3628255 0.72279 -0.6073699 0.3443164 0.7159247 -0.07005864 0.6999833 0.7107145 0.08464014 0.2195799 0.9719161 0.287103 0.04120272 0.9570131 0.07239216 -0.6909876 0.7192326 0.07661533 -0.6974723 0.7125045 -0.3219046 -0.5905414 0.7400259 -0.3764261 -0.6659464 0.6440644 -0.6000672 0.3437048 0.7223479 -0.03908026 0.682998 0.7293741 -0.01595729 0.7484697 0.662977 0.6071661 -0.3445176 0.7160007 0.08148473 -0.7789744 0.6217389 0.04256021 -0.7101259 0.7027872 -0.588073 0.3387318 0.7344597 0.3537464 0.6221835 0.6983919 0.3103529 0.5234373 0.7935329 0.6100288 -0.345653 0.713014 0.06351643 -0.8143362 0.5769074 0.003851711 -0.6825773 0.7308033 -0.409331 -0.7397253 0.5340923 -0.3046575 -0.5015425 0.8097155 -0.07567042 0.6978607 0.712225 0.3351268 0.590449 0.734207 0.4207296 0.5553694 -0.7173225 0.02054196 -0.5980088 0.8012263 -0.4077977 -0.7412182 0.5331948 0.373097 0.6548832 0.6572113 0.6376953 0.2915698 0.7129739 0.004444241 -0.6840333 0.7294374 -0.4093434 -0.7397553 0.5340414 -0.6676867 -0.3494712 0.657316 0.3061804 0.5058639 0.8064461 0.6419417 0.2964484 0.7071275 0.6071309 -0.3445112 0.7160336 0.07238656 -0.6909801 0.7192404 -0.376403 -0.6659082 0.6441174 -0.6376292 -0.3513093 0.6855733 -0.6002026 0.3432198 0.7224661 -0.06939131 0.8241415 0.5621172 0.3731136 0.654927 0.6571583 0.3142946 0.5227725 0.7924191 0.6071339 -0.3445107 0.7160312 0.07238388 -0.6910022 0.7192195 0.07661563 -0.6974807 0.7124962 -0.3763303 -0.6659188 0.6441488 -0.6777897 -0.3641985 0.638718 -0.6069447 0.3447671 0.7160683 -0.04775005 0.6483608 0.7598345 -0.07567256 0.6978644 0.7122212 0.2976788 0.5508203 0.7797337 -7.31719e-4 0.003075361 0.999995 0.6713302 0.3513768 0.652572 0.6209989 0.3483323 0.7021574 0.5947344 -0.341512 0.7277778 -0.330008 -0.6136563 0.717301 -0.07003337 0.6999604 0.7107396 -0.02697795 0.02302521 0.9993708 0.6069309 -0.3447004 0.7161121 0.07661676 -0.6974751 0.7125015 -0.3219007 -0.590535 0.7400328 -0.3764066 -0.6659196 0.6441034 -0.6376382 -0.3512911 0.6855742 -0.04383409 0.7668868 0.6402838 0.8901063 0.4543712 0.03546029 -0.9844582 -0.1503324 0.09078717 -0.00367707 0.9994095 0.03416544 -0.08492136 0.9949776 0.05299156 0.9849972 0.1468521 0.09063762 0.8839066 0.4638142 0.05987954 -0.2897736 0.9506587 0.1108127 -0.8472691 0.5292071 0.0455513 -0.8469873 0.5296152 0.04604768 -0.9860901 -0.1566743 0.05549228 -0.3990053 0.9153493 0.05413395 -0.8376245 0.545117 0.03511279 -0.8321554 0.5525114 0.04742074 -0.85579 -0.5029119 0.1212566 0.4999991 0.8660259 1.61676e-5 0.4999998 0.8660255 4.86534e-6 0.07843106 -0.996009 0.04260081 0.09182649 -0.9944475 0.05140316 -0.8148063 -0.5739583 0.08162564 -0.8721566 -0.4853181 0.0617178 -0.8589559 0.5097177 0.0488128 0.8577175 0.5056532 0.09292811 0.677134 0.7347853 0.03975188 -0.3172374 -0.941304 0.1153575 0.3906766 -0.9198368 0.03566789 0.8447694 -0.5331243 0.04629695 0.844865 -0.5329877 0.04612255 -0.8651226 0.4994801 0.04563713 -0.8651334 0.49946 0.04565167 -0.8651316 0.4994631 0.04565197 0.007953763 -0.9993214 0.03596788 0.859569 -0.5098429 0.03466284 0.9111057 0.4083514 0.05599778 0.3640113 0.9211306 0.1378925 0.8549902 -0.5174442 0.03526216 -0.8876428 -0.4584786 0.04344856 0.9112866 0.4099897 0.03828006 0.8530521 0.5190329 0.05391669 0.8651211 -0.4994827 0.04563564 -0.02028197 0.9991151 0.0368486 -0.06377589 0.9968435 0.04728317 -0.0527184 0.9979251 0.0369637 0.2156866 -0.9758079 0.03575408 0.9378026 -0.3413043 0.06354498 0.9974708 0.04405146 -0.05578172 0.9837203 0.1138623 -0.1390322 -0.3137139 -0.9478664 -0.05597293 0.4601785 -0.8850792 0.0697894 -0.1469181 -0.9859416 0.07958853 -0.7529662 -0.6545684 0.06769067 -0.9959495 -0.065629 0.06146126 -0.9393504 0.3418778 0.02721273 -0.7658458 0.642632 0.02245765 -0.4416789 0.8965002 0.0347445 0.190009 0.9771263 0.09550428 -0.1256022 -0.5824944 0.8030718 -0.3286935 -0.00495094 0.9444237 -0.4096165 0.1739229 0.895525 -0.09970414 0.3583578 0.9282451 0.3149269 0.1073423 0.9430264 0.3889327 0.02611881 0.9208959 0.2653511 -0.3371565 0.9032798 0.2808293 -0.371701 0.8848578 0.325104 -0.8106679 0.4869549 -0.6034682 0.1673192 0.7796348 -0.1925554 0.4613084 0.866093 -0.1099308 0.5674974 0.8160036 0.4403226 0.2656308 0.8576458 0.3270031 0.1077795 0.9388571 0.4216726 0.05347007 0.9051703 0.6341584 -0.1775559 0.7525405 0.7292052 -0.4851803 0.4825555 -0.009032189 -0.174164 0.9846752 -0.134467 -0.4943706 0.8587877 0.4034513 0.5334196 0.7434318 2.28356e-7 0 -1 5.32309e-7 0 -1 -3.01023e-6 9.82876e-7 -1 6.86813e-6 0 -1 0.5219663 -0.190186 0.831493 -0.8224065 -0.5667577 0.04933017 -0.498139 0.1864697 0.8468096 -0.9354912 0.3516225 0.03489917 -0.9384528 0.342279 0.04638475 -0.2657604 0.9595077 0.09336251 0.816167 0.5760847 0.04469817 0.3951784 -0.1341798 -0.9087518 0.02454775 -0.0160796 -0.9995694 -0.7316383 -0.6748554 0.09631061 0.247922 -0.9674047 0.05160415 0.4628219 -0.1479746 -0.8740134 0.4647278 -0.1403728 -0.874256 0.4835333 -0.1340121 -0.8650066 0.1304997 -0.05014079 -0.9901797 0.4717712 -0.1753938 -0.8641001 0.1293458 -0.04834705 -0.9904203 0.1244055 -0.0353589 -0.9916014 0.4834787 -0.146677 -0.8629798 0.4660857 -0.1446889 -0.8728283 0.4919195 -0.1445343 -0.8585599 0.4224414 -0.1306585 -0.8969234 0.4722778 -0.1313045 -0.8716152 0.4901418 -0.1383543 -0.8605924 0.4841837 -0.1421998 -0.8633339 0.4817742 -0.1408275 -0.8649053 0.4867575 -0.1468734 -0.8611014 0.48448 -0.1615445 -0.8597573 0.4744473 -0.1654258 -0.8646005 0.4706721 -0.1681349 -0.86614 0.4732423 -0.1680231 -0.8647602 0.4709556 -0.1675179 -0.8661054 0.4591557 -0.1852451 -0.868827 0.4765092 -0.1857067 -0.8593324 1.79019e-5 -3.55075e-6 -1 4.81584e-7 0 -1 -0.01029801 0.00374788 -0.99994 0.04027652 -0.01435059 -0.9990856 -0.001202821 4.41471e-4 -0.9999992 -0.001576721 5.09796e-4 -0.9999986 0.03247135 -0.03215837 -0.9989553 -5.81017e-7 0 -1 4.14204e-7 0 -1 0.09538638 -0.02255523 -0.9951848 3.93649e-4 0.00106126 -0.9999994 -0.007175326 0.002875566 -0.9999701 0.05794215 -0.03629142 -0.9976601 0.001031398 -7.70852e-4 -0.9999992 0.06172055 -0.02174603 -0.9978566 9.63228e-7 0 -1 -0.003192543 0.001047015 -0.9999944 -0.00763297 0.002778112 -0.9999671 0.05964761 -0.01503878 -0.9981063 -8.68012e-4 -8.4139e-5 -0.9999997 1.77039e-4 -7.0356e-4 -0.9999998 -0.004274189 0.001187741 -0.9999902 0.03695124 -0.002113103 -0.9993149 0.1059284 -0.04368209 -0.9934139 -1.16223e-6 0 -1 1.80303e-7 0 -1 -3.97261e-5 1.78476e-5 -1 0.01466095 0.004468083 -0.9998826 9.07677e-7 0 -1 -0.002440214 1.14263e-4 -0.9999971 3.11984e-5 -1.49314e-5 -1 -7.82629e-6 3.96788e-6 -1 1.19876e-6 -1.09311e-6 -1 4.30057e-6 -1.30715e-6 -1 -4.53858e-7 0 -1 -5.06273e-6 8.03413e-7 -1 0.09344661 -0.02404075 -0.995334 0.01074099 -0.01917415 -0.9997586 0.00123924 -4.28765e-4 -0.9999992 -0.2220932 -0.6037035 -0.7656478 -0.6367711 0.2419579 0.7321059 0.4986253 -0.260562 0.8267287 -0.8110386 -0.5814391 0.06438118 -0.8214644 -0.5695862 0.02770811 -0.9320915 -0.3621987 -0.004197895 0.00428313 -0.004117727 0.9999824 -0.4231406 0.1527593 0.8930939 -0.176696 0.1169376 0.9772943 -0.1138622 0.4730379 0.8736537 0.1789092 0.4730334 0.8626882 0.09511923 -0.5439906 0.8336827 -0.1880961 -0.5128103 0.8376429 -0.1801506 -0.4768282 0.8603376 -0.3300241 -0.943257 0.03674858 -0.9414161 0.3348848 0.03985089 -6.35447e-6 -4.92344e-6 1 -0.8508512 -0.4210566 0.3142665 -0.8542775 0.2627474 0.4485242 -0.9333614 0.2605103 0.2469229 0.09728091 -0.4913892 0.8654901 0.5616037 -0.2141442 0.7992145 0.6765786 -0.2355915 0.6976662 0.9379172 -0.3458302 0.02669924 -0.5922734 -0.8055835 -0.01573151 -0.007233798 -5.52195e-4 0.9999738 -0.4394141 0.1600185 0.8839171 0.594654 0.3272054 0.7343863 0.9417847 -0.3347607 0.03125888 0.9375684 -0.3458275 0.03699922 0.03977739 -0.01539456 0.99909 0.7522058 -0.2190561 0.6214507 -0.4465213 -0.1564255 0.8809936 -0.8196667 -0.5717437 0.0354368 -0.03649199 0.02843964 0.9989292 0.009844839 0.002842307 0.9999475 0.3120756 -0.9494371 0.03432244 0.2584835 -0.9653785 0.0350812 0.2590908 -0.9652107 0.03522008 -0.8957321 -0.4423609 0.04450905 0.00543636 -0.01041114 -0.9999311 0.962203 -0.2699132 0.03622531 -0.2601415 -0.9640859 0.05352431 0.7851175 0.6165202 0.05910748 -0.07741075 -0.06238746 0.9950455 -0.002314329 -0.00195384 -0.9999955 -0.003543257 -0.001317858 -0.9999929 -0.03638523 -0.1287158 -0.9910138 -0.1270394 -0.2431185 -0.9616416 -0.2063065 -0.5818064 -0.7867268 -0.2203688 -0.6036319 -0.7662026 -0.2161793 -0.603451 -0.7675373 0.906686 -0.1116907 0.4067505 -0.4106177 0.9113933 0.0274837 -0.1741126 0.9627454 -0.2068964 -0.9808986 0.1278312 0.1466192 0.5578391 0.8299227 -0.006640851 0.6922842 -0.719718 0.05242693 0.3878892 -0.921706 3.29473e-4 -0.3423096 -0.939585 -0.002105057 -0.3420225 -0.9396911 -0.001123785 0.422209 -0.9064981 9.46465e-4 0.938385 -0.3426994 -0.04461944 0.9387111 -0.3420017 -0.04308706 0.9387972 -0.3416965 -0.04362899 0.9387997 -0.3416917 -0.04361051 0.9387798 -0.3417415 -0.04365056 -0.9388797 0.3414396 -0.04386287 -0.9387801 0.3417488 -0.04358732 -0.9387982 0.3416954 -0.04361498 -0.9388316 0.3416186 -0.04349792 -3.75428e-6 -1.55336e-6 -1 0 -1.97337e-7 -1 -1.93202e-6 1.40791e-6 -1 -3.86349e-7 7.61119e-7 -1 4.97935e-6 -1.45303e-6 -1 -0.07564282 0.9376385 -0.339282 0.3184125 0.8751322 -0.3643589 0.3185353 0.8751008 -0.3643267 0.9457834 0.2321239 -0.2271833 0.8098411 0.5072509 -0.2947099 -1.0954e-4 2.45855e-4 -1 9.63541e-5 1.0186e-4 -1 1.04556e-4 3.6006e-5 -1 -1.34303e-5 -1.20697e-5 -1 7.90599e-7 0 -1 0.9397593 -0.3418372 -5.77234e-5 0.9396931 -0.3420191 0 -0.6289548 0.7758767 -0.0493077 -0.5863535 -0.8100498 -0.003028333 -0.1889272 -0.7733165 -0.6052175 0.3028563 0.44032 -0.8452197 0.01616394 0.9996264 -0.02204251 -0.1104119 0.9937939 0.01352709 -0.7403691 0.671939 -0.01875352 0.6067154 0.73205 -0.3098375 -0.9396765 0.3420646 -3.91156e-6 -0.9396927 0.3420199 2.54068e-7 1.81903e-7 0 -1 -2.52334e-7 0 -1 0.6719194 0.7403411 -0.02047991 0.6217253 0.7832355 0 0.7001051 -0.7140349 0.002673625 -0.1370698 -0.9905615 0 0.4226152 -0.9062988 -0.004359364 0.2736976 0.7722057 -0.5734004 0.2529523 0.7429592 -0.6196989 0.05560874 0.1789509 -0.9822853 -0.2172361 -0.6225237 -0.7518462 -0.2789096 -0.751904 -0.5973691 -0.3345546 -0.9191831 -0.2077878 -0.3420249 -0.9396909 0 -0.3420198 -0.9396929 2.97042e-6 -0.3420166 -0.9396939 -1.91113e-7 -0.3420081 -0.939697 0 -0.3548109 -0.9211496 -0.1599774 -0.054901 -0.2788102 -0.9587757 -0.2859394 -0.6681639 -0.6868739 0.6403051 -0.7681168 -0.002459704 0.6307162 -0.7760134 6.13208e-4 -0.9821097 -0.1883099 0 -0.9841957 -0.1770644 -0.002637207 0.08869731 0.5557601 0.8265976 0.4789324 0.8508123 0.2161996 0.5603746 -0.133753 0.8173681 0.5512641 -0.1612954 0.8185914 0.5142813 -0.1893997 0.8364465 0.40495 -0.2000425 0.8921875 0.5391986 -0.1962318 0.8189982 0.5388472 -0.1961243 0.8192552 0.579313 -0.08633494 0.81052 0.5403723 -0.1965976 0.8181365 0.5464473 -0.1987684 0.813564 0.5826177 -0.1524959 0.7983118 0.4108463 -0.1457883 0.8999728 0.4446294 -0.1672602 0.8799596 0.5391895 -0.1962486 0.8190001 0.5021062 -0.1807712 0.8457016 0.5387356 -0.1960742 0.8193407 0.4776055 -0.1659717 0.8627552 0.5340292 -0.196475 0.8223202 0.5389755 -0.1961711 0.8191596 0.5393792 -0.1963259 0.8188567 0.4674689 -0.206906 0.8594551 0.465633 -0.283455 0.8383551 0.6175753 -0.120742 0.7771887 0.5446973 -0.1999722 0.8144421 0.5455527 -0.1984445 0.8142433 0.504036 -0.1876602 0.8430489 0.5615397 -0.02677524 0.8270165 0.5508666 -0.1213232 0.825728 0.6513767 -0.238681 0.720236 0.5987449 -0.1369491 0.7891448 0.6075462 -0.2276907 0.7609499 0.1247797 -0.09255862 0.9878578 -0.7061479 0.2639278 0.6570369 -0.08197957 -0.7964137 0.5991699 0.7520216 -0.6527251 -0.09172666 0.3543511 0.9331101 0.06116282 0.7322701 -0.6547638 -0.1872562 0.4311368 -0.1739289 0.8853642 0.9821621 0.1830082 -0.04319411 0.004390358 0.002162814 0.9999881 0.02476143 -0.009882867 0.9996446 -9.87355e-4 6.49062e-4 0.9999994 0.003725767 -0.001271069 0.9999923 0.005292892 -0.001609921 0.9999847 0.005281984 -0.001947581 0.9999842 -0.003356158 0.001194834 0.9999938 -0.003632307 0.00125277 0.9999926 -0.002357244 0.00112611 0.9999967 -0.003017783 0.001132607 0.9999949 3.03558e-4 -8.47354e-5 1 -0.002644836 -0.001057922 0.999996 -0.003616929 0.001235604 0.9999927 -0.001792728 8.81124e-4 0.999998 -0.001634359 5.76306e-4 0.9999986 -6.06852e-4 2.95361e-4 0.9999998 -5.55615e-4 2.1423e-4 0.9999998 -3.35748e-4 1.33753e-4 1 1.83533e-4 2.5445e-4 1 0.2402449 -0.09754276 0.9657992 -0.00266534 3.91087e-4 0.9999964 -0.001521587 2.61606e-4 0.9999988 -0.003745794 0.001330196 0.9999922 0.2491126 -0.2613649 0.9325403 -0.1676009 -0.03969782 0.9850554 -0.02818167 -0.1516948 0.9880256 -5.27035e-4 -1.45083e-4 1 -1.82446e-5 7.04397e-5 1 0.002049863 -4.53267e-4 0.9999979 -0.003482758 0.02994257 0.9995456 -0.1559937 0.1607335 0.9745926 0.002569377 -5.28751e-4 0.9999967 0.002518296 -0.001002371 0.9999964 0.002013683 -7.75125e-4 0.9999977 -0.1352935 0.004774034 0.9907941 0.002355337 -0.001006603 0.9999968 -3.00396e-4 3.60374e-4 0.9999999 -0.1564368 -0.01965677 0.9874924 2.44484e-4 -7.67457e-5 1 -4.04638e-4 9.18916e-4 0.9999996 2.19628e-4 6.55797e-4 0.9999998 1.03787e-4 -1.10834e-4 1 6.87972e-4 -2.4317e-4 0.9999998 -4.36277e-4 9.32465e-4 0.9999995 4.65939e-4 5.52267e-4 0.9999998 -7.83813e-4 -0.001622557 0.9999985 -0.09964853 0.009612858 0.9949764 6.18302e-4 -2.34846e-4 0.9999999 0.008382797 -0.003333628 0.9999594 6.24347e-4 -2.07291e-4 0.9999998 -0.08603525 0.004740357 0.9962809 -0.06267613 0.02765053 0.9976508 6.8487e-4 -1.38558e-4 0.9999998 0.001733303 -3.3344e-4 0.9999985 -0.01291239 3.60149e-4 0.9999167 -0.02565717 0.01286506 0.999588 0.002192497 -8.86258e-4 0.9999972 0.001214802 -3.54456e-4 0.9999992 0.003430902 -0.001327574 0.9999932 0.009847402 -0.006205439 0.9999324 0.002151727 -8.28206e-4 0.9999974 -0.003286063 0.001212477 0.9999939 2.39695e-4 -6.60194e-5 1 5.88038e-4 -2.14395e-4 0.9999999 -4.93896e-4 2.96656e-4 0.9999999 2.18452e-4 1.96598e-4 1 -1.21395e-4 -3.92484e-5 1 -0.002220869 -0.001057922 0.999997 4.36545e-6 -6.26575e-5 1 -6.02605e-5 -3.88614e-5 1 2.35968e-4 2.34156e-4 1 2.31803e-4 2.36242e-4 1 0.002209663 -0.001113593 0.999997 2.46177e-4 -1.41136e-5 1 0.003136336 -0.001031041 0.9999946 -7.54602e-4 2.68434e-4 0.9999998 3.7908e-5 -1.28501e-4 1 -6.0251e-4 2.23588e-4 0.9999999 2.77062e-4 -4.38997e-5 1 0.1455042 -0.9712548 0.1883951 -0.9396929 0.3420195 -2.23293e-5 -0.9359465 0.3399694 0.09178811 -0.4084972 0.150575 0.9002541 0.8694612 -0.3240336 0.3728798 0.9364454 -0.3377321 0.09490567 0.938799 -0.341692 -0.0436238 0.9387977 -0.3416963 -0.04362028 0.9387988 -0.3416934 -0.04361945 0.9387983 -0.3416942 -0.04362165 0.938798 -0.3416954 -0.04362016 0.9387982 -0.3416943 -0.04362261 0.9387966 -0.3416988 -0.04362195 0.9387977 -0.3416963 -0.04361879 0.9387982 -0.3416951 -0.04361683 0.9387957 -0.3417023 -0.04361671 0.9387968 -0.3416981 -0.04362404 0.9387929 -0.3417096 -0.04361957 -0.9387952 0.3417034 -0.04361718 -0.938797 0.3416981 -0.04361891 -0.9387992 0.3416923 -0.04361844 -0.9387993 0.3416925 -0.04361635 -0.9387983 0.3416947 -0.04361796 -0.9387977 0.3416959 -0.04362201 -0.938799 0.3416925 -0.04361903 -0.9387984 0.3416945 -0.04361766 -0.9387972 0.3416977 -0.04361766 -0.9388034 0.3416809 -0.04361814 -0.9388011 0.3416869 -0.04361814 -0.9387997 0.3416905 -0.04361957 -0.9388036 0.3416805 -0.0436148 -0.9388025 0.3416835 -0.04361462 0.9387974 -0.3416979 -0.04361361 -0.9388027 0.3416833 -0.04361462 -0.9388038 0.3416799 -0.04361569 0.3416919 0.9388055 -0.0434845 -0.3416961 -0.9387975 -0.04362517 -0.3417002 -0.9387959 -0.04362773 0.3417054 0.9387941 -0.04362416 0.3416914 0.9387985 -0.04364055 -2.17898e-7 0 -1 -0.341697 -0.9387973 -0.04362189 -0.3416894 -0.9388005 -0.04361468 0.34169 0.9388006 -0.04360413 0.3416826 0.9388029 -0.04361385 0.3416915 0.938799 -0.04362839 -0.3416859 -0.9388017 -0.04361426 -0.341696 -0.9387969 -0.04363715 -0.3416896 -0.9388003 -0.0436142 -0.34169 -0.9388002 -0.04361581 -0.04677647 -0.0276947 -0.9985215 0.03249192 -0.01182591 -0.9994021 -0.01489454 -0.04092264 -0.9990514 0.3416857 0.9388012 -0.04362469 0.3416916 0.9387993 -0.04362231 0.3416917 0.9387993 -0.04361927 -0.3416944 -0.9387993 -0.04360049 -0.3417087 -0.9387929 -0.04362457 0.0324918 -0.01182591 -0.9994021 0.3416903 0.9387986 -0.04364675 0.3417072 0.9387935 -0.04362434 -0.3416909 -0.9387997 -0.04361593 -0.04677599 -0.0276944 -0.9985214 -0.01489466 -0.04092293 -0.9990513 0.3417161 0.9387912 -0.04360353 0.3417059 0.9387938 -0.04362839 0.3416879 0.938801 -0.04361397 0.3416935 0.9387983 -0.04362863 2.17892e-7 0 -1 -0.3416931 -0.9387986 -0.04362475 -0.04677587 -0.02769452 -0.9985215 -0.01489478 -0.04092293 -0.9990513 0.341693 0.9387999 -0.04359841 0.3416861 0.9388021 -0.04360377 4.35794e-7 0 -1 0.03249192 -0.01182603 -0.9994021 -0.0148946 -0.04092252 -0.9990514 0.3416862 0.9388017 -0.04361402 0.3416898 0.9388002 -0.04361623 0.3416928 0.9387992 -0.04361647 -0.3417088 -0.9387931 -0.04361909 -0.3416935 -0.9387997 -0.04359728 -0.0148952 -0.04092264 -0.9990513 0.3417125 0.9387921 -0.04361379 0.3417115 0.9387919 -0.04362416 0.3417068 0.9387943 -0.04361009 -0.3416844 -0.9388023 -0.04361379 -0.341697 -0.938797 -0.04362821 -0.3416851 -0.938802 -0.04361414 -0.3416883 -0.9388008 -0.04361587 -0.04677641 -0.027695 -0.9985215 -0.01489472 -0.04092282 -0.9990513 0.3417056 0.9387948 -0.04360872 0.3416851 0.938802 -0.04361414 0.3416921 0.9387989 -0.04362553 -4.35785e-7 0 -1 -0.3416934 -0.9387989 -0.04361563 0.3416931 0.9387992 -0.04361391 0.3416927 0.9387991 -0.04361635 -0.341691 -0.9387999 -0.04361408 -0.3416942 -0.9387983 -0.04362183 -0.04677599 -0.02769464 -0.9985215 0.0324918 -0.01182574 -0.9994021 -0.01489466 -0.04092305 -0.9990513 0.3416959 0.9387978 -0.04361933 0.3416941 0.9387982 -0.04362553 -0.3416941 -0.9387986 -0.04361563 0.3416931 0.9387989 -0.04361909 0.3416942 0.9387987 -0.04361337 -0.3416953 -0.938798 -0.04362034 -0.3416921 -0.938799 -0.04362446 -0.3416916 -0.9387999 -0.04360944 0.3416939 0.9387983 -0.04362446 0.3416923 0.9387992 -0.04361665 8.37295e-6 -7.96909e-5 -1 5.40955e-7 0 -1 2.16849e-4 -7.89426e-5 -1 -0.3416913 -0.9387995 -0.04361927 -0.341694 -0.9387987 -0.04361569 0.3416938 0.9387987 -0.04361879 0.3416931 0.9387988 -0.04361921 0.3416953 0.938798 -0.04362034 -0.03249168 0.01182603 -0.9994021 0.03249168 -0.01182603 -0.9994021 0 0 -1 0 0 -1 0.8683413 -0.3160561 -0.3822197 0.8682816 -0.3160264 -0.3823798 0.8683294 -0.3160406 -0.3822596 0.8682648 -0.3160242 -0.38242 0.8683368 -0.3160455 -0.3822388 0.8683174 -0.3160417 -0.382286 0.8683168 -0.3160423 -0.3822869 0.8683233 -0.3160402 -0.3822737 0.8683145 -0.3160402 -0.3822939 0.8683238 -0.3160411 -0.3822718 0.8682783 -0.316033 -0.3823822 0.8683773 -0.3160591 -0.3821356 0.8683225 -0.3160429 -0.3822736 -0.868278 0.316038 -0.3823784 -0.8683777 0.3160464 -0.382145 -0.8683995 0.316057 -0.3820869 -0.8682501 0.3160287 -0.3824492 -0.8682427 0.3160231 -0.3824712 -0.868225 0.3160151 -0.382518 -0.8684692 0.3160842 -0.3819057 -0.8683159 0.3160405 -0.3822904 -0.8683305 0.3160477 -0.3822514 -0.8683056 0.316034 -0.3823192 -0.8683246 0.3160455 -0.3822665 -0.8683233 0.3160419 -0.3822725 -0.8683084 0.3160355 -0.3823118 -0.8683175 0.3160406 -0.3822867 -0.8683192 0.3160409 -0.3822826 -0.8683186 0.3160433 -0.382282 -0.3417108 -0.9387927 -0.04361385 -0.03600656 -0.002135038 -0.9993494 -1.37649e-4 -3.77491e-4 -1 0.02323997 -0.8192955 -0.5729003 0.1085773 -0.8155064 -0.5684719 0.1760516 -0.7980501 -0.5763002 0.342006 -0.7432357 -0.5750066 0.6180278 -0.5333459 -0.5775673 0.6794688 -0.4617031 -0.5702215 0.7801293 -0.242258 -0.5768096 0.7975143 -0.2076447 -0.5664404 0.6458202 0.5088683 -0.5691832 0.6213077 0.5314989 -0.5757481 0.4915842 0.6555068 -0.5732852 0.2738832 0.7524265 -0.5990345 0.1321526 0.8087172 -0.5731599 0.04508578 0.8180829 -0.5733302 -0.01690632 0.8230128 -0.5677713 0.1138237 0.8124759 -0.5717753 0.425284 0.7006674 -0.5728862 0.5419858 0.6196027 -0.5677536 -0.1770496 0.7983959 -0.575515 -0.3406115 0.742464 -0.5768284 -0.6168411 0.5331845 -0.5789831 -0.6645588 0.4807433 -0.5720556 -0.7855144 0.2361578 -0.572011 -0.8185769 0.09210503 -0.5669644 -0.7610404 -0.2900118 -0.5802679 -0.7024809 -0.4294982 -0.5674961 -0.5329624 -0.6217949 -0.5738661 -0.4472863 0.690316 -0.5686818 -0.5106257 -0.633053 -0.5818122 -0.5013616 -0.6574733 -0.5624638 -0.6133977 -0.5455776 -0.5710416 -0.01534098 -0.823697 -0.5668228 -0.4938482 -0.6568299 -0.5698145 -0.7485673 -0.3564824 -0.5590772 -0.8048911 -0.2344125 -0.5451617 -0.7593817 -0.3218953 -0.5654406 -0.8029047 -0.182382 -0.5675218 0.3856768 -0.7306782 -0.5633497 0.5020464 -0.6497855 -0.570726 0.574909 -0.5933461 -0.5634005 0.4655343 -0.6971359 -0.5452334 -0.9694748 0.2451725 -0.003040075 -0.9944325 0.1053282 0.003151595 -0.9951356 -0.09846633 0.003110766 -0.9357796 -0.3525735 -0.002912759 -0.8456507 -0.5337291 -0.002859234 -0.7208834 -0.6930507 -0.002818048 -0.5666437 -0.823958 -0.002870261 -0.1957822 -0.9806439 -0.002644956 0.2068132 -0.9783774 -0.002485334 0.3995278 -0.9167177 -0.002500653 0.8516114 -0.5241684 -0.002318859 0.9396973 -0.3420002 -0.002254724 0.989302 -0.1458644 -0.002267539 0.998413 0.0562756 -0.002121806 0.4803616 0.8770626 -0.003731727 -0.8742468 -0.4854725 0.003020584 -0.6092275 -0.7929902 0.002925395 -0.04360085 -0.9990453 0.002758204 0.6985662 -0.715541 0.002527594 0.9998169 0.01899969 0.002277731 0.9751902 0.2213578 0.002213299 0.9100336 0.4145292 0.002138733 0.8071115 0.5903955 0.002073347 0.6625863 0.7489823 0.002250254 0.5561245 0.8310989 3.46736e-4 0.09555441 0.995412 -0.004931807 -0.02133667 0.9997605 0.004875063 -0.01087009 0.9998843 0.01065516 -0.2388113 0.9710601 0.003390908 -0.4902022 0.8716034 -0.003084599 -0.655632 0.755074 -0.003161072 -0.7942159 0.6076277 -0.003117978 -0.9002543 0.4353529 -0.003195881 -0.9523876 0.3048732 0.003206253 -0.4299082 0.9028664 0.003357172 0.09574556 0.9953935 -0.004958331 -0.233024 0.08479338 -0.9687673 0.3325769 -0.1222488 -0.9351192 0.2310783 -0.08409279 -0.9692942 -0.30706 0.1124812 0.9450197 -0.1979728 -0.1409561 0.9700197 0.008414268 -0.002704977 0.999961 -0.118973 0.1809358 0.9762724 -0.1165415 0.1237351 0.985448 0.2428194 0.5976106 0.7641338 0.189015 -0.3225962 0.9274724 0.6255957 -0.1948716 0.7554172 0.8329667 0.5531468 -0.01397037 0.9265761 0.3760769 0.004775166 0.1676794 0.1917594 0.9670119 -0.5708746 0.5942279 0.5665646 -0.1662093 0.7009279 0.6935955 0.9526268 -0.1892685 0.2380747 0.9828733 0.1827872 -0.02342998 0.6421958 0.7663373 0.01765674 0.8310478 0.4752221 0.2890042 0.1125253 -0.03640115 0.9929819 -0.1398575 -0.005291402 0.9901576 -0.05090063 0.02961337 0.9982646 -0.01377314 0.00483644 0.9998936 7.24254e-4 -0.05416864 0.9985316 -0.1483157 0.5368614 0.8305314 0.9013658 0.426103 0.0773043 0.9475984 -0.2656528 -0.1774427 0.9845958 0.1347507 -0.1114161 -0.6902466 0.1922338 0.6975715 -0.1960158 -0.09943914 0.9755458 -0.5570705 -0.1613201 -0.8146461 -0.2178781 -0.2734126 0.9368964 -0.7183849 -0.6953782 0.01929944 -0.8590935 -0.5089927 0.05371147 -0.7476262 0.2804219 0.6020121 -0.0493077 0.0139721 0.998686 -0.9394952 0.3404519 -0.03796643 -0.9411685 0.3377164 -0.01222956 -0.883304 0.4277449 0.1918548 -0.9392161 0.3426498 -0.02154529 -0.9959858 -0.08921587 0.007268905 0.8457489 0.5331625 0.02113145 0.7046076 -0.688866 0.1702704 0.8862137 0.456638 0.0781477 -0.4422953 0.8717954 0.2105891 -0.8755356 -0.4831484 -0.002284765 -0.01615458 -0.993054 -0.1165451 0.7725715 0.5606489 0.2980038 -0.01770514 -0.9668656 -0.2546713 0.967051 -0.119606 0.2247377 0.6969531 0.7034294 0.1394395 -0.5425578 -0.837891 -0.05974829 0.840372 0.5113792 -0.1796281 0.8235615 0.5652973 0.0467503 -0.3319428 0.8934238 0.3026682 0.7557042 0.6533036 0.04588598 0.7891287 0.6140375 0.01529365 -0.1805973 -0.9797592 -0.08635151 -0.9849519 0.06040012 0.1619312 0.5054751 -0.7068517 -0.4948289 0.7528466 0.6151662 0.2340785 -0.6072264 0.7672569 -0.2063807 -0.8709285 -0.4364023 0.225913 0.7781502 -0.01453602 0.6279101 0.7769931 -0.1624555 0.6081858 0.7884042 -0.2217186 0.5738116 0.6960152 -0.5189436 0.4962465 0.9498378 -0.07759052 0.3029652 -2.23174e-5 1.13384e-5 -1 -1.06507e-5 7.54399e-6 -1 -3.41766e-5 4.33514e-6 -1 7.55579e-7 2.9509e-7 -1 1.28633e-6 2.26115e-7 -1 0 4.13461e-7 -1 -1.63162e-4 8.32503e-5 -1 -0.01296508 0.004148542 -0.9999074 0.002292037 -0.0401417 -0.9991915 -0.02917724 -0.0434429 -0.9986298 0.02313923 0.00338602 -0.9997266 0.01860678 -0.04989248 -0.9985814 -2.42025e-4 1.69979e-4 -1 0.001681208 1.02866e-4 -0.9999986 3.19685e-4 -4.26458e-4 -1 -0.8071526 -0.02307707 0.5898917 -0.6665156 -0.473101 0.5761358 1.11835e-5 -8.39728e-6 -1 3.68038e-5 -4.80902e-6 -1 -7.55579e-7 -2.9509e-7 -1 1.62227e-4 -8.23447e-5 -1 0.01835471 -0.005857586 -0.9998144 0.06733149 0.02540838 -0.9974071 0.04028445 -0.01729756 -0.9990385 0.03085845 0.04018908 -0.9987155 0.1439894 0.1416876 -0.9793834 -0.09702217 -0.004952728 -0.99527 1.11329e-4 -5.69782e-5 -1 -0.2948977 -0.9325809 -0.2081543 0.5902081 -0.722991 -0.3590801 0.3088847 0.9350418 -0.1740319 -0.5493348 0.682117 -0.4826465 0.1278049 -0.9600093 0.2490943 0.9014043 -0.1678608 0.3991155 -0.3418609 0.9368034 -0.07436776 -0.001205921 0.001042068 -0.9999988 6.55334e-4 -9.97072e-4 -0.9999993 -5.03766e-4 -0.001592516 -0.9999987 5.18684e-4 -9.30284e-4 -0.9999995 4.54359e-4 -2.9343e-4 -0.9999999 -0.001905262 -0.001702427 -0.9999968 0.003689169 -0.003684759 -0.9999864 -0.001086771 -0.004174828 -0.9999908 -0.910649 -0.2745472 -0.3087754 -0.1684333 -0.9256783 -0.3387479 0.6466432 0.7125495 -0.2722609 -0.5183675 0.7425221 -0.4242125 -0.9014174 0.1678329 0.3990977 0.7891353 0.6096944 0.07441854 -4.54859e-4 2.92309e-4 -1 -0.001486182 -6.4838e-4 -0.9999987 -5.62285e-4 7.75791e-4 -0.9999997 8.20319e-4 9.19821e-4 -0.9999993 0.9408002 -0.337938 0.0263229 -0.863593 -0.5038597 -0.01823538 -0.8667951 -0.4969922 -0.04080784 -0.9942345 0.103281 0.02882575 -0.7363804 0.6725982 -0.0731818 -0.9813169 -0.1191673 -0.1510504 -0.9495118 0.2834687 -0.1344356 -4.59756e-6 -3.37784e-5 1 -0.004564702 0.005491793 0.9999745 4.25593e-4 0.01374131 0.9999056 -0.009082973 0.003364622 0.9999531 0.1620989 -0.1173856 0.9797677 0.01359981 0.05532962 0.9983756 0.04697918 0.0122289 0.998821 0.007904767 0.003624439 0.9999622 0.03602772 -0.00710231 0.9993256 0.03703331 -0.019921 0.9991155 0.003536283 -0.002474069 0.9999907 0.001348257 -2.36111e-4 0.9999991 2.04194e-6 1.05214e-6 1 7.70179e-4 -0.002386271 0.999997 -0.001090347 -0.001821279 0.9999977 0.02517819 -0.01898789 0.9995027 -0.03544497 0.04046148 0.9985523 -0.009673058 -7.486e-5 0.9999532 -0.001274466 -4.81026e-4 0.9999992 4.45892e-6 -4.1816e-7 1 0.01355856 -0.0461089 0.9988445 -0.009897172 0.009388983 0.999907 -0.001612782 -4.51185e-5 0.9999987 2.25436e-4 -1.5597e-4 1 6.76493e-4 -1.59832e-4 0.9999998 1.87287e-4 2.36993e-5 1 8.73553e-5 7.34857e-5 1 0.001969397 -9.77684e-4 0.9999977 -0.7185437 0.6950101 0.0256145 -0.5121492 -0.8585724 -0.02359426 -0.9513438 -0.3080807 -0.005607128 0.8803098 0.4714068 -0.05320256 -0.9275681 -0.3731536 -0.0193367 -0.4719165 0.8811607 -0.02916598 0.6104744 0.7920358 -6.38947e-4 0.9911518 -0.132696 -0.003165185 -0.6104707 -0.7920325 -0.003189206 0.9985674 0.02922707 -0.04482412 -0.6023456 0.2139005 0.7690426 -0.6644443 0.241836 0.7071274 -0.9355539 0.3481959 -0.05914855 -0.939694 0.3420164 9.28183e-6 -0.939693 0.342019 3.40846e-5 0.9396927 -0.3420201 -2.78456e-5 0.9396948 -0.3420145 8.52123e-6 0.6644095 -0.2418305 0.7071619 -0.0148946 -0.04092305 -0.9990513 0.3430549 0.938299 -0.04368484 -0.6644654 0.2418441 0.7071049 -0.664463 0.2418451 0.7071067 -0.6644629 0.2418448 0.707107 -0.6644597 0.2418437 0.7071103 -0.6644638 0.2418445 0.7071062 0.6643973 -0.2418104 -0.7071803 -0.6644643 0.2418459 0.7071053 0.6639528 -0.2416934 -0.7076376 -0.6644639 0.2418447 0.7071061 -0.6642186 0.2417313 0.7073752 -0.6644364 0.24185 0.7071301 -0.6644729 0.2418482 0.7070963 -0.6644725 0.2418484 0.7070967 -0.6644524 0.2418388 0.7071188 -0.6644812 0.2418493 0.7070882 -0.6644645 0.2418571 0.7071012 -0.6644626 0.2418385 0.7071093 -0.6644774 0.2418463 0.7070927 0.697058 -0.3090745 -0.6469801 0.6539039 -0.2357016 -0.7189259 0.7168664 -0.2609165 -0.6465487 0.7168654 -0.2609158 -0.6465501 0.7168675 -0.2609121 -0.6465493 0.6875022 -0.1781188 -0.703999 0.7168669 -0.260918 -0.6465476 0.7168669 -0.2609158 -0.6465485 0.6874964 -0.1781163 -0.7040052 0.6875025 -0.1781241 -0.7039972 0.6875008 -0.1781184 -0.7040003 0.7168694 -0.2609148 -0.6465461 0.6875013 -0.1781182 -0.7039999 0.7167623 -0.2605649 -0.6468059 -0.6644641 0.2418454 -0.7071055 -0.6644636 0.2418437 -0.7071067 -0.6640741 0.2412216 -0.7076847 -0.6411489 0.3054706 -0.7039999 -0.6411507 0.3054625 -0.7040018 -0.7168714 0.2609149 -0.6465438 -0.7168641 0.2609225 -0.6465489 -0.7168661 0.2609177 -0.6465485 -0.7168669 0.260918 -0.6465475 -0.7168668 0.2609147 -0.6465491 -0.6411463 0.305472 -0.7040017 -0.6411456 0.3054684 -0.7040038 -0.7168615 0.2609195 -0.6465529 -0.7166832 0.26104 -0.646702 -0.7168675 0.2609159 -0.6465477 -0.6411496 0.3054671 -0.7040007 -0.7168672 0.260917 -0.6465476 -0.001773595 -0.004872202 -0.9999865 -0.4471594 0.005744516 0.8944359 -0.9289754 -0.1798951 0.3234849 -0.9987478 -0.01530873 -0.04762959 -0.8541288 0.0576601 0.5168552 -0.2238884 -0.2591679 0.9395244 0.1441891 -0.3680635 0.9185526 -0.4563208 -0.04693204 0.8885769 0.8051735 0.4349641 0.4031153 0.7553256 -0.07525932 0.651014 0.08112257 0.007456898 0.9966763 -0.3462058 0.2347369 0.9083173 0.02035093 0.9969367 0.07551932 0.3442565 0.9351595 0.0834527 -0.5334542 0.8403836 0.09582352 -0.9157288 0.4002755 0.03493183 -0.2417134 0.4102635 0.8793511 0.2981652 0.7457821 0.5957404 0.007807493 0.03137022 0.9994773 -0.2652497 0.9636139 0.03302735 0.3299309 0.9433509 0.03513753 0.7544267 0.5408026 -0.3719854 -0.330164 -0.9432821 0.03479558 -0.4142798 -0.3034044 0.8580898 -0.7914825 -0.610269 0.0335763 -0.4863256 0.1755548 0.8559603 0.07218903 0.2578271 0.9634906 0.3404569 0.9396134 0.03486907 0.7422646 0.5259937 -0.4151794 -0.004759311 -0.01258927 0.9999095 0.9390395 -0.3425463 0.02944201 0.2599782 -0.9649442 0.03597342 0.2749401 -0.9609747 0.03058838 -0.1037459 -0.195693 0.9751622 -0.419259 -0.3049573 0.8551158 -0.788876 -0.6135327 0.03538954 -0.7914636 -0.610293 0.03358429 -0.9389948 0.3426696 0.02943474 -0.01101124 -0.01917427 0.9997556 1.40357e-5 -1.51117e-4 1 2.91961e-4 0.01577228 0.9998756 -0.3418693 -0.9390967 0.03496849 -0.7914623 -0.6102945 0.03358697 -0.4710678 0.1658607 0.8663634 -0.9415948 0.3349322 0.03492558 -0.2745742 0.961094 0.03012377 0.330092 0.9432946 0.03513807 0.3301576 0.9432753 0.03503787 0.7914335 0.6103313 0.03359889 0.2442586 -7.05512e-4 0.9697099 0.941574 -0.3349561 0.03525674 0.2106196 -0.9769247 0.03546404 -0.577263 -0.4286876 0.694978 -0.4369487 -0.2593345 0.8612906 -0.4890756 0.1424273 0.8605345 -0.8161455 0.3237625 0.4786275 -1.56158e-6 2.79695e-4 1 0.01386094 0.04624104 0.9988342 -0.811579 -0.5828949 0.03966379 -0.820504 -0.5706264 0.03404128 -0.9394491 0.3414194 0.02946418 -0.2552433 0.9662095 0.03591763 -0.2745869 0.961091 0.03010219 0.2981884 0.7457834 0.5957272 0.3301649 0.9432834 0.03475058 0.7888576 0.6135557 0.03540283 0.9389872 -0.3426899 0.02944093 0.9415841 -0.3349252 0.03527587 -0.3332033 -0.9422084 0.03491497 -0.5773032 -0.4287154 0.6949275 -0.4369461 -0.2593199 0.8612963 -0.8161462 0.323762 0.4786267 3.09115e-6 2.03479e-4 1 0.01386111 0.04624152 0.9988342 -0.8115777 -0.5829023 0.03957742 -0.9416057 0.3349509 0.0344482 -0.2745416 0.9611036 0.03011304 0.3299285 0.9433511 0.03515607 0.7544199 0.5407859 -0.3720232 0.4161416 -0.06884121 0.9066902 0.9389889 -0.3426861 0.02943414 0.2603355 -0.9648725 0.03530806 -0.2610423 -0.7075033 0.6567314 -0.3332034 -0.9422084 0.03491503 -0.3419998 -0.9394758 0.02053445 -0.8161428 0.3233744 0.4788945 3.09116e-6 2.03492e-4 1 0.01386201 0.04624426 0.998834 -0.939471 0.3413597 0.02945804 -0.6536839 0.7541339 0.06308436 -0.2746961 0.9610596 0.03011053 0.2981871 0.7457793 0.595733 0.3299311 0.9433494 0.03517907 0.788856 0.6135577 0.03540325 0.4161283 -0.06883668 0.9066966 0.9389873 -0.3426904 0.02943271 0.9415848 -0.3349231 0.03527778 -0.06389015 -0.2260436 0.9720198 -0.3300606 -0.943108 0.04009366 -0.5772517 -0.4286806 0.6949917 -0.436943 -0.2593284 0.8612954 -0.4890927 0.1424387 0.8605229 -0.8161116 0.3237466 0.4786962 -1.55663e-6 2.79782e-4 1 0.01386344 0.04624789 0.9988338 -0.8115859 -0.582892 0.03956693 -0.2552597 0.9662083 0.03583198 -0.2745147 0.9611113 0.03011679 0.32993 0.9433508 0.03515034 0.754432 0.5407907 -0.3719915 0.2748085 -0.9610291 0.03005963 -0.06389009 -0.2260416 0.9720202 -0.3332027 -0.9422085 0.03491866 -0.3419976 -0.9394767 0.02052813 -0.4369431 -0.2593315 0.8612945 -0.4890925 0.142433 0.8605239 -0.8161572 0.323755 0.4786127 -1.55662e-6 2.79799e-4 1 0.01386094 0.04623997 0.9988342 -0.8115823 -0.5828954 0.03958886 -0.8202557 -0.5709835 0.03403663 -0.9416091 0.3349406 0.03445476 -0.6537083 0.7541128 0.06308197 -0.2552334 0.9662125 0.03590613 0.3301548 0.9432868 0.03475677 0.4161334 -0.06883788 0.9066942 0.9389863 -0.3426942 0.02942186 0.9415836 -0.3349276 0.03526932 0.274676 -0.9610663 0.03008019 -0.06389188 -0.2260486 0.9720185 -0.2610424 -0.7075043 0.6567302 -0.3419941 -0.9394773 0.02055513 -0.4337509 -0.2576591 0.8634073 -0.4908065 0.1429309 0.8594648 -0.01515269 -0.03829938 0.9991515 0.01386088 0.04623985 0.9988342 0.3299282 0.943352 0.03513479 0.3301562 0.9432864 0.03475588 0.7888599 0.6135527 0.03540205 0.7914763 0.6102764 0.0335856 0.4161447 -0.06883901 0.9066889 0.9389867 -0.342692 0.02943289 0.2603356 -0.9648721 0.03531634 0.2749503 -0.9609881 0.03007084 -0.06387782 -0.225997 0.9720314 -0.2610709 -0.7075721 0.6566458 -0.333203 -0.9422033 0.03505301 -0.3300651 -0.9431064 0.04009395 -0.4369511 -0.259344 0.8612866 -0.489098 0.1424314 0.860521 -0.01515376 -0.03830271 0.9991514 3.09759e-6 2.03504e-4 1 -0.8202256 -0.5710266 0.03403776 -0.9394555 0.3414015 0.02946692 -0.6536024 0.7542064 0.06306076 -0.2745444 0.9611025 0.03012436 0.3301892 0.9432741 0.0347709 0.7544039 0.5407695 -0.3720797 0.4161165 -0.068838 0.9067019 0.9415799 -0.3349366 0.03528165 0.260344 -0.9648694 0.03532814 -0.06387728 -0.2259904 0.972033 -0.26104 -0.7074896 0.6567471 -0.3420009 -0.9394751 0.02054303 -0.06906962 -0.2732502 0.9594602 -0.01101148 -0.01917475 0.9997556 -0.7880379 -0.6145665 0.03611636 -0.4710828 0.1658585 0.8663555 -0.9393145 0.3417898 0.02946197 -0.9415994 0.3349185 0.03492969 0.3300995 0.9432923 0.03512942 0.3301606 0.9432744 0.0350337 0.7958578 0.6047149 0.03050076 0.7914299 0.610336 0.0335983 -0.8113341 -0.5835273 0.03511381 -0.8143941 -0.5793478 0.03344589 -0.4873308 0.1418973 0.8616113 -0.8162492 0.3234739 0.4786459 0.01366376 0.04560202 0.9988662 -0.9394246 0.3409337 0.03529572 -0.2554523 0.9661558 0.03587639 0.7544109 0.5405047 -0.3724498 0.7914689 0.6102868 0.0335707 0.260958 -0.9647039 0.0353198 -0.06535971 -0.2312027 0.9707078 -0.7439895 0.2032129 0.6365407 0.2982503 -0.6743678 0.6754812 -0.03795689 0.461976 0.8860798 -0.5137713 0.1870071 0.8372977 -0.5731871 0.1623865 0.8031733 -0.5492409 0.2675466 0.7916775 -0.450792 0.1596592 0.8782343 -0.5426221 0.1963605 0.816703 -0.4449027 0.224701 0.866932 -0.5056811 0.1910544 0.8412996 -0.4529305 0.1584247 0.8773572 -0.4435668 0.165562 0.8808166 -0.5108403 0.1717002 0.8423545 -0.5387565 0.09627425 0.8369426 -0.4566174 0.3556597 0.8154796 -0.7148885 0.1818403 0.6751805 -0.4923545 0.1820484 0.8511436 -0.5993033 0.1426216 0.7877148 -0.5386535 0.1647005 0.8262725 -0.5599524 0.1495197 0.8149215 -0.5143013 0.1871964 0.83693 -0.5819036 0.1840712 0.7921528 -0.5456431 0.2002075 0.8137509 -0.5322197 0.1943043 0.8240074 0.8123676 0.4305443 0.3933072 0.7615347 -0.2692951 0.5895295 0.5911149 -0.412073 0.6933823 -0.2485665 -0.5590611 0.7909902 -0.2753241 -0.6769827 0.6825622 0.602347 0.4776043 0.6395875 0.5526095 0.4624753 0.6933537 0.6196792 -0.3008634 0.7248993 -6.53014e-4 1.63841e-4 -0.9999998 -0.5296097 0.2502766 0.8104783 -0.368579 0.2666299 0.8905382 -0.2912755 0.2357751 0.9271294 -0.1519118 0.3781269 0.9132047 0.03136241 0.3329651 0.9424175 0.2177388 0.2316526 0.9481176 0.3072925 0.05754029 0.9498739 0.2779056 -0.1527267 0.9483897 0.2127004 -0.3784241 0.9008628 0.01574057 -0.3874803 0.9217436 -0.3329577 -0.1918854 0.9232114 -0.4896442 -0.07251083 0.8689022 -0.4218575 0.09583276 0.9015833 0.3918675 -0.5322995 0.7503979 0.4232257 -0.3042578 0.8534093 0.6870825 -0.1803488 0.7038409 0.7175446 -0.05165404 0.6945946 0.4230416 0.04798841 0.9048387 0.4468173 0.1371083 0.8840563 0.5714639 0.2993444 0.7640825 0.3124009 0.8627109 0.3976627 -0.03284734 0.6129431 0.789444 -0.5431252 0.8382314 -0.04881972 -0.379803 0.923607 -0.05196022 -0.0806747 0.9931591 0.08442008 0.2236496 0.9733862 0.05000436 0.4543507 0.8894221 0.04993784 0.7002064 0.708935 0.08439332 0.8519111 0.5166501 0.08555787 -0.02051192 0.998547 -0.0498327 0.1946175 0.9795587 -0.05088227 0.784448 0.6180843 -0.05112051 0.9548602 0.293007 -0.04887723 0.9917387 0.1089394 -0.06772488 0.9986203 0.05251169 -5.07108e-5 0.9301139 0.3671433 -0.009700596 0.646443 0.7623505 0.03054815 0.1069116 0.9787541 -0.1749582 -0.228498 0.9726672 -0.04131907 -0.3681206 0.9295245 0.02171742 -0.6887112 0.7250175 0.005169689 -0.7345247 0.6785818 -4.67254e-4 -0.8102133 0.586109 -0.005540311 -0.9041312 0.4272549 0 -0.9039407 0.427658 6.93394e-5 0.9936149 0.1127069 0.005172014 0.7850915 0.6186006 0.03106331 -0.8102247 0.5861184 0.001165449 -0.6871927 0.7234113 -0.06665027 0.8107947 -0.5748373 0.1103371 0.9672372 -0.2538747 0 -5.71792e-4 2.7632e-4 0.9999998 -9.64444e-4 7.38089e-4 0.9999994 -7.11967e-4 0.001265585 0.999999 -1.65971e-5 5.18572e-5 1 -0.00281161 -0.01011872 0.9999449 -4.98052e-4 2.77854e-4 1 -0.002677142 -0.007780969 0.9999662 -0.00960797 -0.008469402 0.9999181 -0.01202613 -0.01416951 0.9998273 -0.001253426 -6.24104e-4 0.9999991 6.23123e-5 -2.26962e-5 1 8.59527e-5 -1.97624e-4 1 1.53761e-7 -6.43139e-5 1 -1.11932e-4 -5.60341e-4 1 -0.00839734 -0.01057082 0.9999089 -7.90909e-4 -5.779e-4 0.9999995 -3.74235e-5 -5.0452e-5 1 8.09974e-5 -1.03229e-4 1 -1.88534e-4 -4.46009e-4 0.9999999 -1.57837e-4 -9.97494e-5 1 -1.85753e-4 -6.99501e-5 1 -4.75862e-4 2.14638e-5 0.9999999 -4.54144e-4 1.14533e-4 0.9999999 -4.79434e-4 -2.38524e-5 0.9999999 -0.9604211 0.2785521 -3.31752e-4 -0.9619576 0.2731987 -5.61907e-5 -0.9638221 0.2665466 7.93604e-5 -0.9529327 0.3031302 0.005616962 -0.9479295 0.3184215 0.006131589 -0.9426597 0.3336979 0.006205022 -0.9313917 0.3639773 0.005498886 -0.9254006 0.3789628 0.004583954 -0.9191808 0.3938247 0.003000259 -0.9129927 0.4079617 -0.003396809 -0.956702 0.2909842 -0.007036447 -0.9268782 0.3753067 -0.006474077 -0.9200544 0.3917548 -0.005307435 -0.9626421 0.270775 0.001075923 -0.9637057 0.2666629 -0.01274532 0.9153866 -0.4025753 7.86245e-4 0.913932 -0.4058632 -0.001870691 0.9117366 -0.4107754 3.4391e-4 0.9093318 -0.4160408 -0.005091428 0.9199178 -0.3920478 -0.007058084 0.9267688 -0.3755596 -0.007380485 0.9333426 -0.3589065 -0.007604777 0.9396259 -0.3421207 -0.007525026 0.945608 -0.3252298 -0.007163703 0.9421557 -0.3351219 0.005991697 0.5715773 -0.3467841 0.7436668 0.5859273 -0.4826442 0.6509561 0.7682127 -0.5880349 0.2531091 -0.4377486 0.1420153 -0.8878107 -0.4699479 0.1578614 -0.8684634 -0.4812886 0.1530665 -0.8630945 -0.4553166 0.1404585 -0.8791805 -0.5090444 0.1648498 -0.8448067 -0.4753019 0.1633927 -0.8645178 -0.1215541 0.03323447 -0.9920284 -0.4759033 0.1681735 -0.8632692 -0.4781363 0.1674171 -0.8621818 -0.4801672 0.1675649 -0.8610236 -0.5025906 0.1779149 -0.8460196 -0.475337 0.1735043 -0.8625261 -0.4694368 0.1826188 -0.8638747 -0.4729818 0.1837122 -0.8617066 -0.4277389 0.1861218 -0.8845328 -0.4633545 0.1871407 -0.8661876 -0.4632367 0.1897007 -0.8656936 -0.502884 0.1989847 -0.8411378 -0.453993 0.194514 -0.8695141 -0.4523378 0.2021743 -0.8686289 -0.4287751 0.2091855 -0.8788592 -0.4597063 0.209292 -0.8630568 0.1661172 0.9835729 0.07063668 0.9328318 -0.3577478 0.04291307 -0.09180378 -0.9926387 0.07899802 0.9365104 -0.3481149 0.04200428 0.9425107 -0.3314256 0.04278934 -0.05557328 -0.9968947 0.05579137 -0.4747656 -0.8747518 0.09698963 0.9429244 -0.3311064 0.03552657 0.776868 0.6241583 0.08308237 0.5012782 0.8648928 0.0260908 0.9460306 -0.3221546 0.03525352 0.3480491 -0.9346657 0.0725376 0.4760528 -0.8745765 0.09213954 0.9488753 -0.3136574 0.03542685 0.9487528 -0.3140661 0.03508031 0.7495065 0.6568639 0.08227932 0.4384906 0.8986167 0.0146315 -0.07852762 -0.992684 0.0917164 -0.01198738 -0.01395064 -0.9998309 0.002937614 -0.005260348 -0.9999819 -1.45252e-7 0 -1 -1.45253e-7 0 -1 3.60646e-7 0 -1 2.07129e-7 0 -1 -3.00983e-7 0 -1 4.14467e-5 -1.09794e-5 -1 -2.88268e-5 6.6656e-6 -1 2.92629e-6 -6.53015e-7 -1 0 0 -1 -8.5306e-6 4.79439e-6 -1 -5.09369e-4 0.001406133 -0.9999989 -0.09429538 0.06029355 -0.9937168 6.26652e-4 -2.51171e-4 -0.9999998 -0.01270073 0.02066701 -0.9997059 -0.01789075 -0.002837121 -0.999836 -0.077425 0.03917491 -0.9962283 0.006102621 -0.001524984 -0.9999802 -0.02354401 0.02067798 -0.999509 -0.04637414 0.01401937 -0.9988258 -0.03061038 0.01434963 -0.9994284 -0.008480608 0.003086507 -0.9999593 0.00527811 -0.002499997 -0.999983 -0.03661078 0.01802498 -0.9991671 0.01326394 -0.005316615 -0.9998979 -0.002864718 -0.001780867 -0.9999943 -0.008480012 0.003086566 -0.9999593 -0.008480548 0.003086805 -0.9999593 -0.008481144 0.003086745 -0.9999593 -0.0084728 0.00308299 -0.9999594 0.001462578 -5.33715e-4 -0.9999988 0.005898296 -0.00214672 -0.9999803 -0.06458473 0.01860851 -0.9977387 0.006177186 -0.002265572 -0.9999784 -5.37696e-4 5.87053e-4 -0.9999998 -0.100828 0.03894692 -0.9941413 -0.008480548 0.003086626 -0.9999593 -0.008480727 0.003086745 -0.9999593 -0.008468449 0.003079831 -0.9999595 0.004198849 -0.001531302 -0.99999 -0.03322321 7.10065e-4 -0.9994477 -0.09840232 0.04042512 -0.9943253 0.00164479 -0.00138843 -0.9999977 0.005946397 -0.002383589 -0.9999795 -0.03258419 0.02226698 -0.999221 -0.008487462 0.003091752 -0.9999592 -0.9383058 0.3440108 0.03519737 0.4842672 0.8689031 0.1024335 -0.9414903 0.335229 0.03489613 -0.7852236 -0.6151967 0.07040518 -0.9445645 0.3264516 0.03503453 -0.9346485 -0.3261806 0.1415576 -0.9474599 0.3179053 0.03544014 -0.7781216 -0.6229602 0.08029603 -0.3041756 0.9509041 0.05708581 -0.9543061 0.2963325 0.03856062 -0.954172 0.2968112 0.03819668 -0.7740479 -0.6272009 0.08642488 -0.9559776 0.2913156 0.03524392 -0.9559708 0.2913421 0.03520929 -0.3877775 0.9197561 0.06064134 0.9628471 0.1011497 -0.2503883 0.5058631 0.7775026 -0.3736208 0.6384885 0.3083891 -0.7051444 0.6939461 0.2368025 -0.6799731 0.8755487 -0.4824048 -0.02645796 0.8786499 -0.4759829 -0.03761076 0.8679001 -0.4959541 -0.02791088 -0.9135574 0.3894818 -0.1171198 -0.9204801 0.375101 -0.1096163 -0.3423338 0.8777831 -0.335119 -0.92926 0.3162906 -0.1908828 0.04241877 0.6305801 -0.7749641 -0.3793979 0.6259239 -0.6813784 0.3316077 0.8707141 -0.3631715 0.2198463 0.6040236 -0.7660437 -0.04569852 0.4094472 -0.9111887 -0.1536891 0.5401906 -0.8273897 -0.8478946 0.5200144 -0.1032466 0.2197755 0.6040838 -0.7660168 0.219778 0.6040844 -0.7660157 0.2198399 0.6040266 -0.7660433 -0.4983263 -0.8669896 0 -3.65656e-4 -5.29965e-5 -1 6.41392e-5 6.2176e-5 -1 -4.73479e-5 1.46105e-4 -1 6.58953e-7 0 -1 1.27212e-6 0 -1 -7.92788e-7 0 -1 -0.001717329 0.001210749 -0.9999979 0.001704752 -0.001507222 -0.9999974 2.878e-6 0 -1 0.3466164 0.3386537 -0.8747404 0.9396927 -0.3420198 -1.38067e-4 0.6644641 -0.2418453 0.7071056 0.6644652 -0.2418461 0.7071043 0.6644545 -0.2418383 0.707117 0.6644571 -0.241842 0.7071133 0.6644706 -0.2418482 0.7070986 0.6644509 -0.2418385 0.7071204 0.6644917 -0.2418568 0.7070757 -0.6642125 0.2417718 -0.7073671 -0.6643694 0.2418174 -0.7072042 0.6644632 -0.2418444 0.7071068 0.6644507 -0.2418398 0.7071201 0.664474 -0.2418429 0.7070971 0.6651554 -0.2406709 0.7068564 0.6644711 -0.2418382 0.7071015 0.6644648 -0.2418425 0.707106 0.6644638 -0.2418437 0.7071065 0.7168689 -0.2609181 -0.6465453 -0.3476581 -0.9369674 0.03501331 -0.4853166 0.8341926 0.2618984 0.148747 -0.1901955 0.9704123 -0.02007555 -0.01283085 0.9997162 0.02163678 0.005698502 0.9997497 -4.51936e-4 -1.19137e-4 1 -3.5172e-4 0.004121482 0.9999915 0.001210868 0.002411544 0.9999964 -2.88923e-4 -0.00131905 0.9999991 6.13174e-4 -0.002497792 0.9999968 -1.72263e-4 -5.81842e-5 1 -0.06457054 -0.01223838 0.9978381 -9.50487e-6 -1.1729e-4 1 -0.00223416 -0.002289116 0.9999949 -0.1071277 0.9779857 -0.1790744 -0.6080549 0.6155502 -0.5013653 -0.2228394 0.6233111 -0.7495505 -0.6053025 0.1128817 -0.7879509 -0.06954973 -0.09782058 -0.9927709 0.5657708 0.8190769 -0.09495538 0.5700466 0.8171533 -0.08548504 -0.1393468 0.990167 0.01232278 0.09066528 -0.9908542 -0.0999388 0.1325725 0.9801436 -0.1474562 -0.7294979 -0.2369066 -0.6416449 0.4739844 0.5873566 -0.6560115 0.7884673 0.6088675 0.08717703 -0.05702263 0.9950778 -0.08104723 -0.7292965 -0.6323645 -0.2612317 -0.03856134 -0.995325 0.08855056 -0.09758949 0.9847047 0.1443369 0.3204184 0.9465079 -0.03814208 0.5621852 0.8229188 0.08217263 0.6022464 0.4032081 0.6890012 0.9891556 -0.05554878 0.1359618 0.142687 0.410457 0.9006472 0.4871721 0.8716694 0.05343866 -0.03993779 0.4540026 0.8901049 0.4993584 0.2544575 0.8281863 0.4459813 0.8948072 0.02051031 0.6930505 0.71597 0.08407181 0.6558259 0.7449599 -0.122177 -0.6679466 0.7441944 -0.004714131 -0.5266969 0.8500423 -0.004323124 0.6262134 0.7796026 -0.008764147 0.8318397 0.5550149 -0.001229763 0.8672885 0.4977968 0.00301361 0.7868863 0.6158352 0.03945869 0.5788098 0.8152686 -0.01778858 0.9241268 0.3820661 0.003916919 0.968853 0.2476116 0.003530204 0.8811188 -0.4597797 0.1105993 0.8248822 0.563394 0.04644012 0.947566 0.3195411 -0.003516554 0.4962888 0.8668006 -0.04852133 0.5246413 0.8513129 -0.004231691 -0.1101126 0.9937247 -0.01965761 -0.135006 0.9908163 -0.007518529 0.6122447 0.6715311 -0.4173757 0.5266149 0.843684 -0.1042798 0.6146997 0.7885537 -0.01809817 0.5177844 0.5815227 -0.6274797 0.6553134 0.3437275 -0.6726187 0.5978096 0.1692924 -0.7835586 0.4253623 0.321704 -0.8459157 0.4865499 -0.0218932 -0.8733786 0.1286966 -0.6404542 -0.7571365 -0.511964 0.5496395 0.6601433 3.24825e-4 -5.38719e-4 0.9999999 3.46911e-4 -1.49758e-4 1 0.1055814 -0.309487 0.9450241 4.96733e-7 0 1 0 0 1 -2.78886e-7 0 1 0 0 1 0 0 1 1.33805e-7 0 1 1.3545e-7 0 1 0 0 1 0 0 1 1.36416e-5 2.54517e-6 1 3.0104e-7 0 1 -1.36168e-7 0 1 0 0 1 3.82504e-7 0 1 0.001849353 0.111463 0.9937669 9.50695e-6 -5.36274e-6 1 -0.7061882 0.1397449 0.6940963 -0.7055292 0.1395369 0.694808 0.7483981 0.09157323 0.6568977 0.6302052 -0.3465334 0.6948065 -0.4210722 -0.3441314 0.839209 -0.7107828 -0.3517326 0.6091569 -0.32696 -0.559061 0.7619369 -0.6084967 -0.4637776 0.6439272 -0.2418457 -0.6644663 0.7071035 -0.1282322 -0.7518932 0.646694 0.115699 -0.6666077 0.7363749 0.1284816 -0.6770544 0.7246308 0.4056757 -0.6768107 0.6142919 -0.5048745 -0.8631716 -0.006048321 -0.7707793 -0.6368511 -0.01789218 -0.9436421 -0.3298496 -0.02718287 -0.9448517 -0.3263819 -0.02702188 -0.9925915 0.1182791 -0.02779322 -0.9989994 0.02993261 -0.03323119 -0.9823634 0.1854548 -0.02384698 -0.9790394 0.2001671 -0.0376169 -0.9807838 0.1932977 -0.02644425 -0.1711705 -0.9852222 -0.006150484 0.5108492 -0.8592405 -0.02718257 -0.1680791 -0.985755 -0.00604844 0.1865171 -0.9822924 -0.0176962 -0.9514221 -0.3058949 -0.03499299 0.8510948 0.5250121 0 0.3473803 0.9375717 -0.01692116 -0.4184358 0.907812 0.02808475 -0.9866943 0.1525006 0.05637526 0.207577 -0.9780161 0.01990777 0.9228084 -0.3847445 0.01990813 0.8762488 0.481562 0.01692026 0.394061 0.9190843 0 -0.4356009 0.8999199 0.01990759 3.42521e-4 -6.62165e-5 -1 2.50967e-4 3.6655e-4 -1 -4.82511e-4 6.6223e-7 -0.9999999 -0.001429677 0.007501304 -0.9999709 0.008329451 -0.04373157 -0.9990086 -0.01337999 0.00872296 -0.9998725 -0.9458596 -0.3239652 0.01990705 -0.9516302 -0.3059595 0.02808308 0.2960355 -0.9535119 -0.05637401 0.9151931 -0.4020364 0.02808016 0.9684293 0.2465821 -0.03663527 -0.4185941 0.9081735 0 0.5833669 -0.8113821 0.03663593 -0.3724312 0.9279056 0.01691961 -0.8648821 0.5019753 0 -0.005094945 0.009512662 -0.9999418 -0.007391333 -0.0108844 -0.9999135 -0.001278519 -0.00982356 -0.999951 0.003443598 0.006570756 -0.9999725 0.06037002 -0.02472293 -0.9978699 5.56975e-5 -1.79873e-4 -1 -2.25766e-6 0 -1 0.006370067 0.01411622 -0.9998801 -0.7576428 0.6524032 0.01864457 -0.05932861 0.9980549 -0.01914882 0.781105 0.6243938 0.002717733 0.9994878 0.02695262 0.01726055 0.6379898 -0.7691436 0.03724753 -0.7248625 -0.6876777 0.04091173 -0.8546463 0.5178729 -0.03724855 0.7433076 0.6687358 -0.01691961 0.7534497 -0.6572878 -0.01692217 0.2522444 -0.9673201 -0.025783 -0.0545839 0.07694989 0.9955398 0.08293992 0.01287782 0.9964714 0.1259792 -0.005365788 0.9920184 -0.04748338 0.05724495 0.9972304 -0.4297297 0.9021002 0.03933829 0.05136686 0.9980798 -0.03461498 0.4878664 0.8709985 0.05786359 -0.2703257 -0.9611172 0.05637311 -0.9744755 0.2215354 0.03632932 -0.8883928 0.45762 -0.03663545 0.7865759 0.614915 -0.0563749 0.9528929 -0.2980219 -0.05637449 0.2960343 -0.9535121 -0.05637675 -0.9516283 -0.3059659 0.02808302 0.07256144 0.2524639 0.9648818 0.1803722 -0.2174525 0.9592603 -0.5325312 0.8464105 0 0.1014222 0.9944644 0.02746319 0.8406664 0.540774 0.02904474 0.9228082 -0.3847451 0.01990753 0.838554 0.5441281 0.02742224 0.95072 -0.309697 -0.01480555 0.2964378 -0.9548447 -0.01990771 -7.33938e-5 -7.20261e-4 0.9999998 -2.29808e-4 -4.6278e-4 1 0.003089487 0.009401798 0.9999511 -0.01307553 -0.08624416 0.9961883 -0.0115897 0.001791298 0.9999313 -7.86239e-4 -5.05813e-4 0.9999997 0.009618937 -0.004010379 0.9999458 -0.8028058 0.5935693 0.05637693 -0.51561 0.8549667 -0.05637574 0.8404438 0.5406173 0.03724819 0.3143807 -0.9488815 -0.02808439 -0.3363664 -0.9410184 0.0366339 -0.9445439 -0.3235102 0.05637449 0.7530555 -0.6569363 -0.03663748 0.1890259 -0.9815706 0.02808254 0.004695534 0.006940901 0.9999649 -2.6066e-5 -8.00978e-4 0.9999998 0.00308901 0.009401857 0.9999511 -0.01307964 -0.08625745 0.996187 -0.010495 0.003468155 0.999939 -0.01140934 0.008435726 0.9998993 0.005118429 -0.01544868 0.9998676 -0.6802986 0.006105005 0.7329097 0.1960281 0.4847707 0.852391 -0.4101276 0.9118183 0.01956194 -0.2167961 0.976216 0.001336514 -0.9946976 0.1009589 -0.01959365 0.8157559 -0.5782958 -0.01079779 0.5308394 0.8473132 0.01643735 0.7181863 0.6958507 -4.62583e-4 0.9927572 0.1200388 0.004904747 0.9822378 -0.1876142 0.003161132 -0.997148 0.07288038 0.01960849 -0.9537356 0.3006438 -0.001349925 0.2445777 -0.9696289 -0.001289308 -0.736284 -0.6766715 0.001350939 -0.6091314 0.7930683 -0.00135225 -0.2168079 0.9762135 0.001336574 -0.4354485 0.9000008 -0.01957815 -0.9960047 0.08683609 -0.02083742 0.8157692 -0.5782767 -0.01079922 0.3795979 0.9251506 0.001348316 0.718172 0.6958655 -4.62566e-4 0.9735938 -0.2281342 0.008360862 0.9822381 -0.1876124 0.003161787 0.4249656 -0.9051628 0.009209394 -0.5726277 -0.8196091 0.01840019 -0.9960368 0.08702945 0.01834905 0.2445908 -0.9696256 -0.001289308 -0.9913902 -0.1309341 -0.001359343 -0.8145349 -0.5791583 0.03330045 -0.9984089 0.0290848 0.04830992 -0.9392821 0.3418111 0.03023648 -0.9417517 0.3345048 0.03478842 0.8232178 0.5665979 0.03576779 0.830196 0.556093 0.039182 0.9394568 -0.3413033 0.030546 0.9417622 -0.3344722 0.03481638 0.8110857 0.5833529 0.04288798 0.8443031 0.5348536 0.03292316 0.998486 -0.02900314 0.04674023 0.9392614 -0.3418663 0.03025966 -0.8124549 -0.581555 0.04136359 -0.9993013 0.02907705 0.02348846 -0.9495695 -0.3091855 0.05217468 -0.9994002 0.0290715 0.01882296 -0.7834255 0.619362 0.05133539 -0.8204012 -0.5706819 0.03555321 -0.9993274 0.02907747 0.0223419 -0.9392771 0.3418072 0.0304408 -0.9416841 0.3346968 0.03477215 0.9392648 -0.3418645 0.03017407 0.7834434 -0.6194886 0.04950273 0.7768901 0.6268249 0.05943316 0.9393754 -0.3419045 0.02598816 0.9426944 -0.3319011 0.03419226 0.8200417 0.5712739 0.03432148 0.998372 -0.029024 0.04910224 0.9392823 -0.3418098 0.030245 0.7248811 -0.68847 0.0235902 0.8269848 0.5609942 0.03717225 0.7062938 -0.7053834 0.05986082 -0.958446 0.2828785 0.03689247 -0.2455552 0.9682493 0.04686135 0.9389755 -0.3422331 0.03466618 0.7834092 -0.619519 0.04966193 0.2984922 -0.9538651 0.03230661 0.8053323 0.5912178 0.04360842 0.9332792 -0.3574001 0.03542798 0.2434452 -0.968743 0.04766148 0.2280637 -0.9729358 0.03718978 0.8717906 -0.4854643 0.06561648 0.2409859 -0.9698095 0.03735321 0.251375 -0.9668588 0.04466372 -0.2535893 0.9665974 0.03717333 0.3380869 0.9407709 0.02544498 0.330061 0.9432387 0.03688567 0.8145332 0.579565 0.02530127 0.7913452 0.6100487 0.0401684 -0.2561429 0.9649553 0.05702644 -0.9284928 0.3696322 0.03568172 -0.9285902 0.3694068 0.03548359 0.9515182 0.295839 0.08421635 0.7853354 0.6160996 0.06057769 0.9393717 -0.3419141 0.02599477 0.5749062 -0.8154857 0.06682825 -0.7665722 -0.6412014 0.03504157 -0.7105657 0.7015677 0.05384415 -0.3329473 0.9423633 0.03312748 0.2797067 0.9590591 0.04438376 -0.6866339 0.7228513 0.07758849 -0.5642243 0.8198187 0.09771519 0.7827867 0.621223 0.03642779 0.8117458 0.581771 0.0511012 -0.2833951 0.9582527 0.03793489 0.1959171 0.3586354 0.9126869 -0.6652498 0.2400021 0.706995 -0.6468717 0.2364332 0.7250217 0.7313379 -0.4496249 -0.5128182 -0.3019597 0.4162687 0.8576368 -0.6638171 0.07578134 0.7440457 -0.05541944 -0.9588381 0.2784926 -0.2944258 0.1452645 0.9445697 0.703882 -0.2218734 0.6747758 0.06678974 0.9723259 0.2238783 0.4105565 -0.6638231 0.6251258 -0.6366419 0.2342342 0.7347255 -0.1015276 0.5398542 0.8356133 -0.941702 0.3346437 0.03479933 -0.9993469 0.02774447 0.023153 -0.9438615 -0.3261465 0.0524795 0.3361302 0.5762567 0.7449461 -0.4746111 -0.001338601 0.8801946 -0.09045046 -0.7678703 0.6341877 0.7892947 -0.1966319 0.5816786 -0.1186475 -0.01290148 0.9928527 1.0972e-4 0.553385 0.8329257 -0.7563753 0.222801 0.6150254 -0.4635444 0.166468 0.870296 -0.6681003 0.2169972 0.7117263 -0.938706 0.3416604 0.04581844 -0.9342296 0.3549169 0.03534281 0.002153158 -0.9992444 0.03880733 -0.8417723 -0.5352803 0.06996095 0.09778159 -0.3917031 0.9148811 0.2223249 0.2799364 0.9339205 -0.775008 -0.3138556 0.5485047 -0.4847043 0.1941393 0.8528609 -0.2916131 0.955725 0.0393927 0.2061201 0.2875972 0.9353087 -0.1562645 0.02505058 0.9873975 -0.1153447 -0.3641146 0.9241842 -0.6679372 0.2368097 0.7055361 0.300517 0.3675013 0.8801321 -0.5014258 -0.8247952 0.2613142 0.7431005 -0.2690697 0.6127015 0.6993983 -0.2392876 0.6734861 0.130559 0.9846866 0.1155279 -0.9392612 0.341867 0.03025436 -0.9417583 0.3345128 0.03453451 -0.997047 -0.05703628 0.05142271 -0.7052224 0.2213014 0.6735631 -0.2033577 0.1231493 0.971329 0.2492545 -0.9647129 0.08486068 0.05616086 -0.9967163 0.05833262 0.04977148 0.3970283 0.9164559 0.6710718 -0.2349914 0.7031655 0.6268222 -0.2302531 0.7443639 0.08308142 -0.6190311 0.7809598 -0.05075883 -0.9606621 0.273042 0.3319059 -0.9427487 0.03261262 -0.01059252 -0.1704379 0.9853116 0.4659851 -0.1689277 0.8685168 0.4595144 -0.1672118 0.8722883 0.8639525 0.1671481 0.475024 0.4040351 0.4614788 0.7898057 -0.003096282 0.8324034 0.5541614 0.1246108 -0.06417918 0.9901279 0.07697397 -0.5337019 0.8421623 -0.7980003 -0.6014307 0.03842633 0.6656823 0.2861151 0.6892063 0.6898509 -0.2396566 0.683133 -0.6645727 -0.2831307 -0.6915057 0.03604555 0.005910873 0.9993327 0.06028962 -0.7052521 0.7063884 0.3738666 0.7851091 -0.4937888 0.3304242 -0.94332 0.03110224 0.08439004 0.783037 0.6162236 -0.6747587 0.2060184 0.7087011 0.1803633 -0.6703187 0.7198208 -0.2598195 -0.9417476 -0.2135547 0.1225591 0.30795 0.9434755 -0.4596794 0.1672633 0.8721914 -0.1184032 -0.1119987 0.9866292 0.7476285 -0.282193 0.6011812 0.7021784 -0.2777413 0.6555953 0.3576133 0.8390774 0.4099535 -0.5294021 0.8440527 0.0854898 -0.07393676 0.006704986 0.9972405 0.7300781 -0.2191761 0.6472619 -0.3257696 0.9448629 0.0332908 -0.4938846 0.8093491 0.3178558 -0.4595187 0.1672072 0.8722868 -0.5627239 -0.3808171 0.7337031 -0.08370679 0.6209748 0.7793481 0.5599741 0.6418271 0.5239152 0.8078488 0.5876075 0.04580384 -0.2689152 0.9614183 0.05796343 -0.6358529 0.233029 0.7357912 0.131684 0.326052 0.9361354 -0.6993671 0.05351138 0.7127568 -0.6929064 -0.02028226 0.7207422 0.1350537 -0.06450152 0.9887367 -4.45251e-4 0.8183439 0.5747288 -0.2806883 0.9591499 0.0352934 -0.2967333 0.9541305 0.03980523 -0.6730509 0.2687455 0.6890417 -0.3638226 -0.5046657 0.7829086 0.7428765 0.6405133 -0.194621 0.8142125 0.5786957 0.0465787 -0.5242519 0.8474898 0.08319324 0.4428419 0.8957675 0.03862398 0.6733672 -0.2731811 0.6869853 0.04171001 -0.08404439 0.9955888 0.8597664 0.5095383 0.03424125 0.429987 -0.6611451 0.6148157 -0.04583609 0.4362801 0.8986427 -0.2701258 0.9621032 0.03727704 -0.2827621 0.9582282 0.04294496 0.6616225 0.5026177 0.5564451 0.1925627 -0.5278005 0.8272523 -0.04726284 7.21875e-4 0.9988823 -0.7893747 0.2905363 0.5408109 0.9978426 0.05762284 0.03146195 0.9892039 0.1411707 0.03932601 -0.2362905 0.03563958 0.9710286 0.09912765 0.1256132 0.9871146 -0.7676913 -0.6398219 0.03575122 0.5398596 -0.8374483 0.08504182 0.2960382 -0.9532517 0.06060254 -0.01767575 -0.3700813 0.9288313 0.5498098 -0.7433695 0.3809343 0.2746298 -0.008805155 0.9615098 0.5319898 -0.8424358 0.08537501 0.270867 -0.9608567 0.05818587 0.3624029 -0.3704165 0.8552519 0.5119448 -0.03123855 0.8584502 -0.2173196 0.967729 0.1275651 -0.07366454 0.06028193 0.9954596 0.6869755 -0.2213219 0.692157 0.9134574 -0.2571583 0.3153812 0.7846146 -0.06491214 0.6165764 0.8657895 0.1145372 0.4871239 0.6713846 0.1832002 0.718109 0.8358221 -0.5216949 -0.1709849 0.2744818 -0.9608082 0.03882485 0.2622566 -0.9643626 0.03501892 0.09510052 0.1148374 0.9888218 -0.4774689 0.1783974 0.8603476 -0.8467075 -0.1749881 0.5024595 0.09727567 -0.2213832 0.9703231 -0.06681638 -0.8022536 0.5932325 0.03211534 0.05505985 0.9979665 0.4423969 0.7580443 0.4792223 -0.06420814 0.9942608 0.08557313 -0.2847065 0.9567176 0.06028079 0.07609671 0.03809231 0.9963726 0.006107866 -0.5908656 0.8067469 0.9391219 -0.3418072 0.03489995 0.7109814 0.6973616 0.09051138 0.8991889 0.4351639 0.04573667 -0.1075436 0.004956603 0.9941881 -0.2537835 0.07175034 0.9645962 -0.03213316 0.314157 0.9488272 0.6283947 -0.2289112 0.7434514 0.3104578 -0.9495785 0.04378086 -0.2633102 -0.775039 0.5744411 -0.6182845 -0.4763866 0.625124 -0.1390089 0.6403473 0.7554019 -0.3024174 -0.7996703 0.5187207 -0.003201305 -0.01473069 0.9998865 -0.6632737 0.2340502 0.7108365 -0.6377599 0.2314524 0.7346374 0.255065 0.7211896 0.6440711 0.1357431 -0.6101023 0.7806082 -0.1974763 -0.594093 0.7797798 -0.1740496 0.6888096 0.7037387 0.2757414 0.7542976 0.5958204 0.5162282 0.4594468 0.7227843 0.6387757 -0.2316479 0.7336927 0.1352121 -0.6103878 0.7804771 0.1905512 -0.6771939 0.710703 -0.5466641 -0.4619632 0.6983898 -0.6450157 0.2328153 0.7278406 -0.1912841 0.6679276 0.719224 0.2144646 0.6374593 0.7400342 0.5669336 0.4566912 0.6855798 0.5588305 0.4431201 0.7009658 0.6602733 -0.2351652 0.7132577 0.6506415 -0.2341673 0.7223789 0.1579674 -0.6695189 0.7258035 0.1441296 -0.7511734 0.6441779 -0.2876168 -0.561066 -0.7761968 -0.6577657 0.233852 0.716001 -0.165232 0.691945 0.7027877 0.2190667 0.6381001 0.7381315 0.6012944 0.472779 0.6441468 0.6580014 -0.233533 0.7158886 0.6379638 -0.2314671 0.7344558 0.163677 -0.6449173 0.7465196 -0.2403341 -0.6741573 0.698392 -0.2147515 -0.569402 0.7935132 -0.2061845 0.7915993 0.575203 -0.1136397 0.654096 0.7478265 0.2746618 0.7995891 0.5340584 0.2129286 0.5468006 0.8097349 0.5968375 0.4600821 0.6573504 0.5515153 0.4496986 0.7025682 0.6450136 -0.2328153 0.7278424 0.1587415 -0.629142 0.7609084 0.1956749 -0.674107 0.7122438 -0.5863401 -0.4669143 0.6619639 -0.5706873 -0.4400066 0.6933327 -0.6576114 0.2341335 0.7160508 -0.1240495 0.5853081 0.8012653 0.2728966 0.8007912 0.5331612 0.2031431 0.5223665 0.8281703 0.596838 0.4600787 0.6573523 0.657631 -0.234093 0.716046 0.08936643 -0.5382726 0.8380193 -0.2536934 -0.7096697 0.6572736 -0.2187594 -0.5694619 0.7923746 -0.580695 -0.4034188 0.7071399 -0.5773462 -0.3978267 0.7130255 -0.6605452 0.2343827 0.7132636 -0.6425709 0.2324998 0.7301003 -0.2038716 0.7908125 0.5771066 -0.1231912 0.6729276 0.7293781 0.2129237 0.5467882 0.8097445 0.657634 -0.2340947 0.7160428 0.6450167 -0.2328186 0.7278386 -0.6578143 0.233854 0.7159558 -0.1912723 0.6679165 0.7192375 -0.1965635 0.6735544 0.7125217 0.2144706 0.637468 0.7400249 0.5588351 0.4431208 0.7009618 -0.2625076 -0.77134 0.5797625 -0.2043443 -0.5341041 0.8203514 -0.1912696 0.6679453 0.7192114 0.5467569 0.4585725 0.7005485 0.1298031 -0.5921886 0.7952759 0.1956944 -0.6740926 0.712252 -0.2541255 -0.7111492 0.6555052 -0.6529862 0.233023 0.7206312 -0.642644 0.2319197 0.7302205 -0.16619 0.7352131 0.6571474 0.2184222 0.6616066 0.7173343 0.516616 0.4585196 0.7230959 0.6579421 -0.2336273 0.7159125 0.158694 -0.6288971 0.7611207 0.1954443 -0.6743033 0.7121213 -0.2689741 -0.6751599 0.6868858 -0.6449794 0.2328085 0.7278749 -0.1913008 0.6679202 0.7192265 0.2144759 0.6374859 0.740008 0.5669609 0.4567081 0.6855459 0.1220998 -0.6622189 0.7392955 0.1833372 -0.7552659 0.6292542 -0.7976881 -0.6020269 0.03546273 -0.8101497 -0.5845395 0.04439723 0.9433878 0.3190245 0.09079104 0.7819032 0.6206403 0.05859309 0.94696 0.3083937 0.09033435 0.177538 -0.9835204 0.03417783 0.2565826 -0.9650692 0.05297952 -0.944541 -0.3156375 0.09063822 0.1745095 -0.9778203 0.115819 -0.5903109 -0.806985 -0.01756674 0.925816 -0.3742691 0.05279648 -0.9642981 -0.2562516 0.06681627 -0.9212613 -0.3852097 0.05377006 0.1566655 -0.9793781 0.1275714 -0.2940595 -0.9544729 0.05010557 0.9167954 -0.3970248 0.04310083 0.8939508 0.4455723 0.04813778 -0.9399848 -0.3288034 0.09119713 -0.3420196 -0.9396929 0 -0.2631152 0.9633942 0.05140322 0.9342514 -0.3533418 0.04820835 -0.4214587 -0.906734 0.01435351 -0.9250112 0.3782668 0.03562021 0.9387183 -0.3416482 0.04565691 0.9387152 -0.3416586 0.0456435 0.938718 -0.3416497 0.04565274 -0.9350369 0.3528507 0.0346744 0.9387103 -0.3416724 0.04564076 -0.8263476 -0.5603693 0.05599904 -0.1985684 -0.9703382 0.1378926 0.4161059 0.9084982 0.03856039 -0.9318429 0.3611434 0.03527623 -0.927385 0.371354 0.04531294 0.7945384 0.6056569 0.0434556 -0.8456842 -0.5327554 0.03146171 -0.9459452 -0.3114563 0.09045809 -0.7499448 -0.6593 0.05391073 -0.9387138 0.3416628 0.04563957 -0.9387202 0.3416429 0.04565685 0.1935219 -0.9803984 0.03699356 0.2355552 -0.9707099 0.04728752 -0.9387196 0.3416451 0.04565262 -0.8236653 -0.5653938 0.04365289 -0.9386463 0.3418502 0.04562383 -0.938712 0.3416472 0.04579234 -0.372977 0.9270712 0.0377773 -0.9489943 -0.2829774 -0.1390454 -0.2964882 -0.9418535 -0.1581348 0.9955396 0.08120238 -0.04803365 0.7299015 0.678996 -0.07879281 -0.3426608 0.9364249 -0.07544684 -0.8648038 0.4993261 -0.05280125 0.6278466 0.7753856 0.06772071 0.9694219 0.2375716 0.06148993 0.9844437 -0.1735767 0.02723538 0.5906295 -0.8061943 0.03475332 -0.01743376 -0.9952793 0.09547352 -0.6548923 -0.7396147 0.1551977 0.6181043 0.3777502 0.6893852 -0.0290786 0.643749 0.7646842 0.3228483 0.06195056 0.9444211 0.4335694 -0.1001387 0.8955389 0.2758554 -0.4258649 0.8617094 -0.127748 -0.2161349 0.9679701 -0.01438933 -0.184153 0.9827923 -0.2179785 -0.390751 0.8943149 -0.2915589 -0.1604409 0.9430016 -0.2907946 0.2925143 0.9109742 -0.2934191 0.1559728 0.9431744 0.7248798 0.5295711 0.4405722 0.4129169 0.1182212 0.9030634 0.5461012 -0.2235441 0.8073424 0.4725999 -0.3182193 0.8218187 -0.3875224 -0.3380475 0.8576423 -0.3033561 -0.1629586 0.9388395 -0.3714555 -0.037409 0.9276968 -0.4399538 0.04100233 0.8970839 -0.8023608 0.3511703 0.4825938 -0.6088538 0.2671625 0.7469413 -0.03355264 0.2895088 0.9565871 0.04661893 0.5102851 0.8587409 3.24325e-7 0 -1 -3.69936e-7 0 -1 3.42523e-7 0 -1 -5.32323e-7 -1.29105e-7 -1 1.50508e-6 -6.5868e-7 -1 6.86926e-6 0 -1 -1.61722e-6 1.72143e-6 -1 1.05298e-5 -3.82583e-6 -1 -4.29282e-6 0 -1 -6.83747e-6 5.60362e-6 -1 -0.4266801 -0.130643 0.8949171 0.9558972 0.2936174 0.007030129 0.9456287 0.3227384 0.04032826 0.0151208 -0.003250956 0.9998805 0.5291992 0.1922067 0.8264411 0.9426429 0.3319725 0.0349096 0.938905 0.3410354 0.04639434 -0.2613027 -0.9639995 0.04925286 -0.2555291 -0.9657651 0.04475259 0.04610854 0.02907979 -0.9985132 0.02552551 0.01315152 -0.9995877 0.4630392 0.8856541 0.03480666 -0.8113802 0.5820681 0.05347037 -0.4462344 -0.1911904 -0.8742547 -0.4741557 -0.1688945 -0.8640897 -0.4730534 -0.1646448 -0.865513 -0.4741222 -0.1989072 -0.8576971 -0.540495 -0.2144672 -0.8135533 -0.407591 -0.1714465 -0.8969257 -0.4595802 -0.2017968 -0.8649071 -0.4749677 -0.1876649 -0.8597602 -0.4686309 -0.1737375 -0.8661411 -0.4705333 -0.1754906 -0.8647552 -0.4735219 -0.166469 -0.8649076 -0.4774808 -0.1712874 -0.8617846 -0.4708058 -0.1532382 -0.8688269 -0.4844151 -0.1640501 -0.8593193 -0.4959344 -0.1637534 -0.8527802 -0.08565962 0.214251 -0.9730154 -2.52666e-4 -0.006390392 -0.9999796 -1.60468e-5 -8.78664e-6 -1 0.01029872 0.003748476 -0.99994 0.00199306 2.46685e-4 -0.999998 -0.03268748 -0.0078606 -0.9994348 -0.04011875 -0.01493722 -0.9990833 -0.01839792 -0.004273414 -0.9998216 -0.08606505 -0.01940447 -0.9961006 9.58841e-4 -3.58573e-4 -0.9999995 -4.14258e-7 0 -1 9.63139e-7 0 -1 3.78982e-4 -0.001067101 -0.9999994 -0.06771451 -0.009444177 -0.9976601 -0.001285254 -7.22835e-5 -0.9999992 -0.06125462 -0.02301186 -0.9978569 0.003117024 0.001249372 -0.9999944 3.02608e-7 0 -1 0.001269459 4.16522e-4 -0.9999992 -0.1043347 -0.03580594 -0.9938976 0 0 -1 0.004040122 0.001838982 -0.9999902 0.002458333 9.85331e-4 -0.9999965 -7.48839e-4 2.9724e-4 -0.9999998 -0.02966457 -0.02213335 -0.9993149 0.00139904 4.58942e-4 -0.999999 -0.04360926 -0.005166828 -0.9990354 4.07593e-5 1.15073e-5 -1 -3.02596e-7 0 -1 -0.002597212 -8.5199e-4 -0.9999964 0.001943111 0.001481056 -0.9999971 -0.02418988 0.004240751 -0.9996985 -0.09986013 -0.02658617 -0.9946463 -3.28115e-5 -8.34764e-6 -1 8.21769e-6 1.9648e-6 -1 -3.56128e-6 -2.03061e-6 -1 4.38948e-6 2.55508e-6 -1 -0.08703559 -0.04164993 -0.9953342 0.0187447 0.006751477 -0.9998015 0.9396926 0.3420202 -1.04854e-5 -0.1764625 0.5330957 -0.8274479 -0.2117583 0.6026791 -0.769374 0.07932823 0.4897163 0.8682656 0.2046453 -0.5096804 0.8356712 0.1378003 -0.3912615 0.9099043 -0.9548235 -0.2752802 0.1119508 0.2470214 0.9667864 0.06560945 0.2631537 0.964356 0.02770775 0.4812167 0.8765918 -0.004198968 0.001120805 4.4049e-4 0.9999994 0.001431703 4.10691e-4 0.9999989 0.6635449 0.2465109 0.7063573 0.6962606 -0.5184731 -0.4963939 -0.2386324 -0.9520027 0.1916909 -0.4458801 -0.1699051 0.8788193 -0.4238613 -0.1558199 0.8922231 -0.1776002 0.5336852 0.8268242 0.2114525 0.6517223 0.7283859 -0.8232996 0.566633 0.03324162 -0.3351721 0.9418203 0.02518528 0.2753152 0.9612295 0.01547652 0.2140976 0.9759763 0.04040312 0.9419716 0.3343917 0.02952462 0.9364249 0.3485919 0.03989976 0.006667554 0.002015531 0.9999758 -0.01437836 0.05804258 0.9982106 0.02917695 -0.1251736 0.9917057 0.8934456 0.3991901 0.205918 0.4534432 0.2334265 0.8601752 -0.5648764 -0.1953039 0.80173 0.2127518 0.9446247 -0.2498417 -0.2369068 -0.6426999 0.7285686 -0.647098 0.5162614 0.5610156 -0.5648944 0.4124165 0.7147076 0.02175182 0.01831358 0.9995957 0.7783573 0.2314475 0.5836026 -0.2178481 -0.6182844 0.7551601 -0.9405109 -0.337742 0.03700786 -0.01244175 -0.003972768 0.9999148 0.4697496 0.1909791 0.8618946 -0.7321299 -0.3227425 0.5998526 0.2602974 0.838154 0.4793154 0.2624503 0.9641187 0.03994101 0.2566194 0.9657611 0.03810316 0.9388476 0.3425949 0.0345565 0.9389108 0.3419793 0.03868997 0.9628266 -0.2661584 0.0460956 -0.005098342 -0.001918494 0.9999852 0.722827 0.6868338 0.07603025 -0.1317178 0.370427 -0.9194751 -0.1564056 0.3913936 -0.9068343 -0.9178228 -0.3954336 0.03512567 -0.9155853 -0.4005964 0.03501617 -0.458498 -0.8857744 0.07199531 -0.004251897 0.005676448 -0.9999749 0.002388238 5.19096e-4 -0.9999971 2.94751e-4 6.45008e-4 -0.9999998 1.79322e-5 5.76836e-4 -0.9999999 -0.1539952 0.2445373 -0.9573333 -0.09745126 0.5610026 -0.8220581 -0.1983804 0.5984591 -0.7762035 -0.3011229 0.6131256 -0.7303438 -0.2822771 0.5584446 -0.7800381 -0.5969203 -0.7955972 0.1034957 -0.9177278 0.3953781 -0.03810423 -0.5873044 0.809009 -0.02404373 -0.1087855 0.9933561 0.0375415 -0.4804953 0.8148853 -0.3241704 0.5939261 -0.8043065 -0.01851588 -0.9869782 0.09227609 0.1317543 0.9047136 -0.4180156 0.08219802 -0.8032112 0.5761343 -0.151397 0.708449 0.6553928 0.2618402 -0.3417179 0.9398003 -0.002081453 -0.342003 0.9396982 -0.0011307 -0.939125 -0.3406665 -0.04461854 0.9387973 0.3416956 -0.04363334 -1.8589e-5 -7.05198e-6 -1 1.50173e-6 3.20506e-6 -1 5.35778e-6 4.84514e-6 -1 1.93173e-6 -3.55173e-7 -1 -7.77508e-6 0 -1 -3.31954e-6 -1.35827e-6 -1 0.9934502 0.01241225 -0.1135907 0.6990198 -0.6356061 -0.3276832 -0.5753015 -0.7857585 -0.2271822 -0.2943262 -0.909128 -0.2947177 -1.90157e-5 -1.41632e-4 -1 -4.34774e-5 -1.22261e-4 -1 -4.35367e-7 0 -1 4.84065e-7 0 -1 -1.93444e-6 0 -1 -0.9396929 -0.3420196 -1.23251e-7 -0.9396277 -0.3421988 -5.71262e-5 -0.9396916 -0.3420231 0 0.9805387 -0.1900336 -0.04930669 -0.07151657 0.9974349 -0.003028988 0.4443331 0.8239867 -0.3515878 -0.3523565 0.7138295 -0.605221 0.4142356 0.8555551 -0.3105393 0.7233824 -0.6903151 0.01352876 0.9990699 -0.03882998 -0.01875257 0.7026281 -0.5717935 -0.4235163 0.939686 0.3420384 -1.34609e-5 0.9397082 0.3419776 -3.79899e-6 0.9303385 0.3666952 0.002235054 0.001166403 -9.31589e-4 -0.9999989 1.81904e-7 0 -1 -0.03297424 0.0977742 -0.9946622 -0.902441 -0.3290107 -0.2781229 0.08389639 -0.1872674 -0.9787197 0.08768624 -0.9581542 -0.2724918 -0.9716873 -0.2362706 0 -0.8351049 0.5500902 8.41099e-4 -0.5317191 0.8469208 0 -0.9063042 0.4226034 -0.004358708 0.2867 -0.7674722 -0.573402 -0.03667587 0.07271236 -0.9966784 0.07243669 -0.1728507 -0.9822808 -0.2337356 0.6165106 -0.7518526 -0.3345568 0.919188 -0.2077624 -0.3420181 0.9396934 0 -0.3420202 0.9396926 0 -0.3420087 0.9396969 0 -0.2758304 0.6809333 -0.6784154 -0.3515419 0.9310317 -0.09797197 -0.2104455 0.6956402 -0.6868751 0.9396935 0.3420181 -1.10725e-5 -0.9396913 -0.342024 0 -0.9327174 -0.3604155 -0.01178741 -0.9396933 -0.3420187 7.7105e-6 -0.9842377 0.1768334 -0.002460002 -0.9819681 0.189046 6.09966e-4 -0.9848104 0.1736336 -2.87536e-6 -0.9848094 0.1736391 7.23861e-6 0.6401243 0.7682669 -0.002638101 0.6427978 0.7660359 1.14717e-5 0.6428048 0.7660301 -2.75521e-6 0.9832118 -0.1785936 -0.03740161 0.8697588 -0.3826804 0.3115694 -0.5242146 -0.2700638 0.8076291 -0.515778 -0.1855042 0.8363978 -0.5391911 -0.1962677 0.8189945 -0.4397144 -0.1550666 0.88465 -0.3855156 -0.09260582 0.9180425 -0.5403253 -0.1967447 0.8181322 -0.5008538 -0.1842733 0.8456884 -0.5387487 -0.1960953 0.819327 -0.5525579 -0.2008562 0.8089108 -0.5393803 -0.1963106 0.8188597 -0.5459755 -0.2498774 0.7996699 -0.5531509 -0.299082 0.7775436 -0.5457919 -0.1969409 0.814448 -0.4473789 -0.3404318 0.8270178 -0.5375431 -0.2341527 0.810074 -0.3300721 -0.1155514 0.9368566 -0.5594536 -0.2892813 0.7767421 -0.652428 -0.2358558 0.7202151 -0.4231227 -0.3141028 0.8498864 -0.6117628 -0.2161042 0.7609502 -0.9189487 -0.2303129 0.3201394 -0.03676569 0.05284929 0.9979255 -0.4603477 -0.09521538 0.8826178 -0.5531522 0.314064 0.7716131 0.4954193 0.2043523 0.8442747 0.7015267 0.2551661 0.6653951 0.3471887 -0.9139249 0.2102407 0.8126589 0.4074363 0.4166308 -0.3430463 -0.08973783 0.9350222 -0.002221763 0.01664435 0.9998591 -0.1345167 -0.1643106 0.9771937 0.01424092 -0.002570629 0.9998954 0.001188218 4.09236e-4 0.9999992 3.72809e-4 1.14955e-4 1 -0.0314967 -0.01141804 0.9994387 -0.003633439 -0.001343429 0.9999926 -0.005089998 -0.002169013 0.9999847 -0.005297839 -0.001903176 0.9999842 -0.175926 -0.04423475 0.9834091 -0.002340853 4.97552e-4 0.9999972 7.83501e-5 2.61651e-4 1 -0.003508448 -9.4812e-4 0.9999935 -6.58461e-4 -4.84373e-4 0.9999997 0.003147006 0.001483082 0.999994 0.003359615 0.00150299 0.9999933 -6.23171e-4 7.58757e-5 0.9999998 0.001715421 3.07493e-4 0.9999986 4.756e-4 7.62094e-5 0.9999999 3.45796e-4 3.47897e-4 0.9999999 0.001622557 6.08997e-4 0.9999986 6.55695e-4 1.64191e-4 0.9999998 2.19738e-5 -3.13988e-4 1 -0.2467271 -0.07969987 0.9658021 0.002812087 6.94624e-4 0.9999958 0.01059257 0.01393193 0.9998469 0.003708958 0.001389682 0.9999923 -0.009892165 -0.005525827 0.9999358 -2.65364e-4 1.68746e-4 1 -0.01315349 -0.003325819 0.999908 -0.00858432 0.007097184 0.9999381 -3.79935e-4 -2.97434e-4 1 0.2295938 0.06609296 0.9710399 0.2445799 0.1818841 0.9524174 -0.00263977 -8.94767e-4 0.9999961 -0.001972436 -7.76929e-4 0.9999979 -0.03258472 0.01959264 0.9992769 2.81686e-4 1.85498e-4 1 -0.002156972 -5.69802e-4 0.9999975 -0.001978337 -6.19637e-4 0.9999979 -0.00101453 -5.13533e-4 0.9999994 1.41601e-4 -9.96679e-5 1 -4.3936e-4 -1.80141e-4 0.9999999 -0.001154303 -5.64939e-4 0.9999992 3.33362e-4 -3.25097e-5 1 -6.24485e-4 -2.17153e-4 0.9999998 -4.55018e-4 -1.59577e-4 0.9999999 0.09107744 0.0981568 0.9909946 -0.001414895 -6.69042e-4 0.9999988 2.74758e-4 5.69673e-5 1 0.1085171 0.02212625 0.9938484 -0.00443989 -0.001574218 0.9999889 -6.92917e-5 -9.83456e-6 1 -2.39176e-4 -1.46083e-6 1 0.09102523 0.01259869 0.9957689 -5.80313e-4 -1.24787e-4 0.9999999 0.01144397 0.0187776 0.9997582 -0.001157939 -5.09314e-4 0.9999992 -9.39429e-4 -0.001065969 0.999999 -1.54098e-4 4.79153e-5 1 2.19215e-4 4.26833e-4 1 -8.16598e-4 0.001034975 0.9999992 0.001459121 5.63952e-4 0.9999989 -0.004637062 0.01142859 0.999924 -0.001090168 -2.69647e-4 0.9999994 5.69116e-4 9.01374e-5 0.9999999 -4.0806e-5 -2.91428e-4 1 6.51818e-5 -2.16458e-4 1 -9.22402e-5 -1.58591e-4 1 -2.57396e-5 -3.29748e-4 1 -8.36924e-5 -3.04176e-5 1 3.25166e-4 1.18323e-4 1 2.83416e-4 3.58791e-5 1 -0.002577185 -8.50226e-4 0.9999964 -0.004637479 0.0114299 0.999924 3.18446e-4 -0.002020657 0.999998 -3.16556e-5 -1.649e-4 1 -3.83277e-4 -2.46958e-4 1 0.003188848 0.001271724 0.9999941 -0.001556158 -4.17049e-4 0.9999988 9.33366e-4 2.94979e-4 0.9999995 0.9396932 0.3420189 0 0.8653237 0.3349523 0.3728563 0.9305429 0.3397081 0.1367056 -0.2305933 -0.08188241 0.969599 -0.9397204 -0.3419438 -3.66671e-5 -0.9387974 -0.341697 -0.04361993 -0.9387984 -0.3416942 -0.04362058 -0.9387978 -0.3416956 -0.04362046 -0.9387989 -0.3416928 -0.0436204 -0.9387986 -0.3416942 -0.04361736 -0.9387973 -0.3416969 -0.04362142 -0.9387993 -0.3416917 -0.04362052 -0.9387979 -0.3416954 -0.04362225 -0.9387971 -0.3416977 -0.04362022 -0.9388009 -0.3416876 -0.04361677 -0.9387998 -0.3416912 -0.04361176 -0.9387971 -0.3416978 -0.04361969 -0.9387959 -0.3417015 -0.0436176 -0.9387943 -0.3417059 -0.04361534 -0.9437553 -0.3297951 -0.02368944 -0.9387943 -0.3417047 -0.04362809 0.9387975 0.3416962 -0.04362261 0.9387992 0.3416923 -0.04361885 0.9387978 0.3416957 -0.04362052 0.938797 0.3416981 -0.04362052 0.9387988 0.3416934 -0.04361861 0.9387987 0.3416936 -0.04361945 0.9387985 0.3416941 -0.04361784 0.9387987 0.3416932 -0.04362291 0.9387978 0.341696 -0.04361754 0.9387972 0.3416976 -0.04361957 0.9387995 0.3416911 -0.04362177 0.9387997 0.3416907 -0.04361879 0.9387985 0.3416942 -0.04361802 0.9387958 0.3417024 -0.04361331 0.9388024 0.3416831 -0.0436232 0.9387995 0.3416917 -0.04361933 0.9388016 0.341686 -0.04361581 -0.9387956 -0.3417024 -0.04361772 0.9388012 0.3416869 -0.04361724 0 0 -1 0 0 -1 -0.3416896 0.9388003 -0.0436142 -0.3416969 0.9387971 -0.04362803 0 0 -1 0.01803094 0.05128264 -0.9985214 -0.0324921 -0.01182591 -0.9994021 0.3416844 -0.9388027 -0.04360359 0.01803112 0.05128276 -0.9985215 -0.0324921 -0.01182585 -0.9994021 -0.01489448 0.04092288 -0.9990514 0.342663 -0.9383815 -0.04497182 0.34158 -0.9384919 -0.0505591 -0.006225943 0.002195775 -0.9999783 -8.79461e-4 0.002416253 -0.9999967 0.007735788 -7.05746e-4 -0.9999699 -0.3416951 0.9387977 -0.04362809 0.01803016 0.05128192 -0.9985215 -0.0148946 0.04092305 -0.9990513 0.3416876 -0.9388011 -0.04361444 0.3416897 -0.9387999 -0.04362231 4.35789e-7 0 -1 -0.3417075 0.9387938 -0.04361343 -0.3417001 0.9387962 -0.04362189 -0.3417107 0.9387923 -0.04362428 -0.0324921 -0.01182562 -0.9994021 0.341705 -0.9387943 -0.04362219 0.3416914 -0.9387986 -0.04363775 -0.3416888 0.9388007 -0.04361283 -0.3416876 0.9388011 -0.04361444 -0.01489514 0.04092311 -0.9990513 0.3416859 -0.9388017 -0.04361426 0.3416916 -0.938799 -0.04362869 0.3416838 -0.9388012 -0.04364019 -4.35794e-7 0 -1 -0.3416863 0.9388017 -0.04361283 -0.03249198 -0.01182597 -0.9994021 -0.01489466 0.04092329 -0.9990513 -0.3417024 0.9387952 -0.04362469 -0.3417088 0.9387931 -0.04361909 -0.03249198 -0.01182603 -0.9994021 0.3416893 -0.9388002 -0.04361969 0.3416843 -0.9388023 -0.04361402 -0.0324918 -0.01182615 -0.9994021 0.3417082 -0.9387933 -0.04361897 0.3417091 -0.9387933 -0.04361361 -0.341686 0.9388014 -0.04361921 -0.3416941 0.9387977 -0.04363399 0.01803106 0.0512827 -0.9985215 -0.0324918 -0.01182603 -0.9994021 0.3416869 -0.9388014 -0.04361414 0.3416922 -0.9387991 -0.04362249 0.3416897 -0.9387999 -0.04362416 0.3416967 -0.9387976 -0.04361796 -0.3416954 0.938798 -0.04361885 -0.3416986 0.9387972 -0.04361402 -0.341695 0.9387983 -0.04361569 0.01803082 0.0512824 -0.9985214 -0.0324918 -0.01182603 -0.9994021 -0.01489466 0.04092246 -0.9990514 0.3416942 -0.9387986 -0.04361641 -0.3416937 0.9387982 -0.04362779 0.01803088 0.05128264 -0.9985214 0.3416932 -0.938799 -0.04361641 0.3416949 -0.9387983 -0.04361909 0.3416952 -0.9387978 -0.04362535 4.35788e-7 0 -1 -0.3416957 0.9387979 -0.04361921 0.01803076 0.05128264 -0.9985214 -0.03249174 -0.01182585 -0.9994021 0.3416963 -0.9387975 -0.04362243 0.3416958 -0.9387981 -0.04361492 -0.3416944 0.9387986 -0.04361569 -0.3416952 0.938798 -0.04362189 0.0180307 0.05128228 -0.9985215 -0.03249192 -0.01182603 -0.9994021 0.3416957 -0.9387977 -0.04362183 0.3416949 -0.9387983 -0.04361659 -5.75641e-5 5.56369e-5 -1 -1.3524e-7 0 -1 5.58268e-6 5.33172e-5 -1 -2.17764e-4 -7.90786e-5 -1 -0.3416965 0.9387976 -0.04361873 0.3416922 -0.9387995 -0.04361402 0.3416947 -0.9387981 -0.04362177 0.03249168 0.01182603 -0.9994021 0 0 -1 0 0 -1 -0.8682666 -0.3160272 -0.3824134 -0.8683778 -0.3160572 -0.3821359 -0.8682161 -0.3160206 -0.3825337 -0.8684208 -0.3160651 -0.3820316 -0.8682358 -0.3160206 -0.3824887 -0.8683586 -0.316054 -0.3821823 -0.8683184 -0.3160421 -0.3822833 -0.868341 -0.3160499 -0.3822258 -0.8682959 -0.3160307 -0.382344 -0.8683169 -0.3160409 -0.3822879 -0.8683179 -0.3160402 -0.3822862 -0.8683129 -0.3160367 -0.3823004 -0.8683247 -0.3160439 -0.3822677 -0.8683301 -0.3160501 -0.3822501 -0.8683096 -0.3160393 -0.3823056 -0.8683205 -0.3160412 -0.3822794 -0.8682605 -0.3160153 -0.3824373 -0.8683083 -0.316037 -0.3823106 0.8683284 0.3160474 -0.3822565 0.8683453 0.3160597 -0.3822076 0.8682787 0.3160202 -0.3823916 0.8683539 0.3160592 -0.3821886 0.868353 0.3160602 -0.3821898 0.8683361 0.3160479 -0.3822385 0.8682932 0.3160384 -0.3823437 0.8683181 0.3160427 -0.3822836 0.8683097 0.3160407 -0.3823042 0.8683212 0.3160427 -0.3822764 0.8683184 0.3160408 -0.3822845 0.8683155 0.3160419 -0.3822902 0.8683193 0.3160412 -0.3822823 0.8683195 0.3160387 -0.3822839 -0.3417056 0.9387946 -0.04361367 -0.3416953 0.9387987 -0.04360365 -0.3447119 0.9377014 -0.04347407 -0.3416309 0.9386289 -0.04758185 0.006983101 0.01282739 -0.9998934 0.03112477 0.02783435 -0.9991279 -0.473235 0.6694234 -0.5726439 -0.5194801 0.6239627 -0.5837903 -0.5028163 0.6585793 -0.5598653 -0.64784 0.4981783 -0.5763002 -0.6928194 0.4430819 -0.5689285 -0.7581169 0.3160129 -0.5704337 -0.8172921 -0.08306568 -0.5702052 -0.7915532 -0.2163639 -0.5715158 -0.7939251 -0.2119269 -0.569886 -0.6670249 -0.4825279 -0.5676659 -0.6558077 -0.4927783 -0.5719142 -0.5665099 -0.5963709 -0.5686901 -0.4456661 -0.6937039 -0.5658239 -0.285631 -0.7645609 -0.5778076 -0.3296945 -0.7479285 -0.5761116 -0.1676537 -0.8049363 -0.5691834 -0.1343339 -0.8065169 -0.5757474 0.1391367 -0.8068568 -0.5741282 0.1321557 -0.8087489 -0.5731145 0.1666206 -0.8213382 -0.545565 0.2738829 -0.7524246 -0.5990372 0.4185836 -0.7044897 -0.5731337 0.4915494 -0.6555064 -0.5733155 0.5419801 -0.6196003 -0.5677616 0.5194787 -0.623966 -0.5837879 0.4734126 -0.6692582 -0.5726903 -0.01687711 -0.8230223 -0.5677583 0.6438686 -0.5073256 -0.5727601 0.7381709 -0.3498106 -0.576833 0.815254 -0.01194947 -0.5789803 0.7995792 0.2099293 -0.5626748 0.7579744 0.3061899 -0.5759538 0.7533316 0.3239366 -0.5723257 0.3248528 0.7364734 -0.5933614 0.2620349 0.7805688 -0.5674946 0.008629441 0.8188977 -0.5738746 -0.01623725 0.8235563 -0.5670022 -0.03001081 0.8290772 -0.5583284 0.7276571 -0.3811686 -0.5702857 0.7863649 -0.2412964 -0.5686882 0.8178113 -0.09277021 -0.5679599 -0.03849107 0.8258647 -0.5625531 0.0782231 0.8363654 -0.5425626 0.2506163 0.7812842 -0.5716525 -0.7079598 0.4335109 -0.5575494 -0.8022706 0.1750373 -0.5707224 0.7941857 0.6076678 -0.00300312 0.6556322 0.7550747 -0.002959251 0.4902403 0.8715826 -0.00290966 0.3047026 0.9524433 -0.002856492 -0.2939683 0.955811 -0.002812266 -0.4803835 0.8770545 -0.002648532 -0.6470766 0.7624208 -0.002525866 -0.7873272 0.6165305 -0.002487182 -0.9666504 0.256088 -0.00244069 -0.9984125 0.0562756 -0.00238198 -0.989301 -0.1458703 -0.002322018 -0.9396997 -0.3419936 -0.002256095 -0.5758653 -0.817542 -0.002061843 -0.3995323 -0.9167169 -0.002000331 -0.2067929 -0.978383 -0.001928567 0.1957803 -0.9806408 -0.003734588 0.3420094 -0.9396955 0.001407206 0.2055503 -0.9786448 -0.001890301 0.5395553 0.8419446 0.003061652 0.1608812 0.9869694 0.002969801 -0.04301077 0.9990703 0.002932429 -0.2444864 0.9696484 0.002898275 -0.6087715 0.7933408 0.002759814 -0.756906 0.6535182 0.002728819 -0.8738616 0.4861678 0.002661764 -0.9543271 0.2987526 0.002586722 -0.9945037 -0.1046722 0.002464115 -0.9526304 -0.304121 0.002400279 -0.8710198 -0.4912424 0.002349078 -0.7536873 -0.6572291 0.002279579 -0.4306774 -0.9025034 0.002141833 -0.2387694 -0.9710742 0.002075016 -0.0261234 -0.9996563 0.002247691 0.3891463 -0.9211588 -0.005626678 0.4715885 -0.8818144 0.002818644 0.6589799 -0.7521448 0.004875898 0.6510413 -0.7589674 0.01066875 0.8456468 -0.5337331 -0.003211677 0.9357755 -0.352581 -0.00331372 0.9875935 -0.1570007 -0.003163933 0.9989805 0.04503685 -0.003114402 0.9255433 0.3786286 0.003204941 0.9100621 -0.4144583 0.003351509 0.6465439 0.2593977 -0.7174217 0.850139 0.3094261 -0.4260506 -0.3333203 -0.1201163 -0.9351309 -0.7721042 -0.2847913 -0.5681103 -0.8603022 -0.3127282 -0.4025933 -0.9895932 0.06092149 0.1303606 -0.01010864 -0.005131781 0.9999358 0.1055184 -0.04456174 0.9934184 -0.3685519 -0.1129088 0.9227249 -0.7499133 -0.2706243 0.6036495 -0.883577 -0.337776 0.3243443 0.005152523 -0.05022478 0.9987246 -0.2227645 -0.9729481 0.061221 0.6858314 0.3933603 0.6122932 0.8192754 -0.08824777 0.5665689 0.5778213 -0.4301366 0.6936175 0.8553735 0.1869699 0.4830926 -0.6377687 -0.7702266 0.0014683 -0.01803815 -0.9996554 0.0190736 -0.02061432 -0.05211126 0.9984286 0.6159633 -0.03162544 0.7871398 -0.4688711 -0.8822731 0.04188197 -0.9075194 -0.4113224 -0.08498579 0.7591013 0.2745598 0.5902391 0.5707426 0.1731281 0.8026704 0.1138098 0.9934211 -0.0127229 0.7060019 0.2507541 0.6623321 0.04675126 0.02099096 0.998686 0.9384635 0.3430909 -0.03968775 0.9341621 0.3532293 0.05069702 0.9392407 0.3425892 -0.02144074 -0.1661981 0.9853845 0.03735947 0.2022278 0.9750264 0.09180217 0.6459658 0.7624952 -0.03645783 0.7268703 0.6864308 0.02173429 -0.7017416 0.7018326 -0.1224326 -0.7689808 -0.6136936 -0.179022 -0.9147619 0.3031593 0.2670302 -0.3834781 -0.9147365 0.1272856 0.1280016 -0.9908539 -0.04271268 0.9962731 -0.08553951 -0.01109492 -0.7396304 0.4205707 -0.5254209 0.8284373 0.5438128 0.134012 0.7182927 0.6657378 0.202111 0.6056224 -0.7955375 0.01848703 -0.3151487 -0.9318822 -0.1796585 -0.2675703 -0.9624024 0.04677474 0.8290145 -0.4705733 0.302152 -0.5467475 0.8365261 -0.03593403 0.8029066 0.5954854 0.02716898 0.8360317 -0.5423492 -0.08311784 0.979725 -0.06740891 -0.1886664 0.8920063 -0.4512593 -0.02626949 -0.7240002 -0.6103967 0.3213094 -0.8573904 -0.2008929 0.4738392 -0.8169779 0.06147599 0.5733829 2.70768e-5 7.01495e-6 -1 1.63666e-5 5.16484e-6 -1 -3.44497e-7 -2.72216e-6 -1 -1.07551e-6 -2.93871e-6 -1 0.0801444 0.05771446 -0.995111 0.007977485 -0.0424689 -0.999066 -0.0177735 0.01341134 -0.9997522 1.20901e-4 -0.001199007 -0.9999994 -0.01989609 0.01120692 -0.9997394 -3.16714e-4 -0.001739382 -0.9999985 -3.72705e-5 4.40858e-5 -1 0.5339892 0.6121236 0.5832327 0.5550646 0.7106373 0.432317 -4.36776e-6 2.40305e-6 -1 7.99018e-7 2.36772e-6 -1 -0.001546323 -2.86846e-4 -0.9999989 -1.08876e-5 -3.6628e-6 -1 -0.07159113 -0.008513927 -0.9973977 -0.004749417 0.005026519 -0.9999762 3.52006e-5 -4.40866e-5 -1 -1.17608e-4 -2.90499e-5 -1 0.5355695 0.7848445 -0.3117442 0.1315367 0.9376936 0.3216034 -0.3678377 0.8901688 -0.2688776 -0.9561919 0.1819123 -0.2293582 0.3644182 -0.9148211 -0.1740742 0.1335418 -0.9798113 0.1487837 -0.001735925 0.002305209 -0.9999959 0.003676652 4.87547e-4 -0.9999932 -0.005191624 4.46114e-4 -0.9999864 0.5211179 0.7956668 -0.3087891 -0.3643522 0.9148133 -0.1742532 0.3677843 -0.8901965 -0.2688585 0.9561951 -0.1819165 -0.2293412 0.7891377 0.5470069 0.279366 -0.1330683 0.9799236 0.1484683 -0.8971213 -0.4339751 0.08269917 0.002177655 0.002067565 -0.9999955 -0.00399369 -0.005902826 -0.9999746 0.00173676 -0.002309501 -0.9999959 9.98649e-4 -3.78106e-4 -0.9999995 -0.9379531 -0.3458324 0.02537715 -0.942392 -0.3337837 -0.02204465 0.3254602 0.9454736 -0.01247286 0.6006674 0.7780061 0.184134 0.93018 -0.1009014 -0.3529648 0.6947526 0.7087486 -0.1224505 -1.57228e-4 -1.01444e-4 1 -1.86918e-5 2.85718e-5 1 -0.01210445 0.01040166 0.9998727 -0.01249581 -0.07064706 0.9974232 0.01782375 -0.04954653 0.9986128 -0.02812576 -0.03956723 0.998821 -0.03802669 -0.005139648 0.9992635 -0.004300594 -3.77932e-4 0.9999908 -0.001688838 -6.36041e-4 0.9999984 1.08833e-6 -6.78569e-7 1 -1.15143e-6 -2.35129e-6 1 -3.35405e-4 0.002095758 0.9999977 -0.03149062 -0.001639068 0.9995027 -1.34533e-5 -3.27985e-5 1 -0.04201149 0.02715951 0.998748 -0.005601584 0.04030168 0.9991719 -2.7391e-4 -2.56063e-5 1 -2.00192e-5 -1.12563e-4 1 0.9285036 -0.3684302 -0.04626399 -0.885566 0.4634832 0.03092306 -0.2532662 0.9656549 -0.05802601 0.781769 0.6201937 -0.06478393 0.927881 -0.3717341 -0.02916854 0.8859806 -0.4637113 -0.00320518 0.8446066 0.535378 -0.003188788 -0.1420314 0.9898562 -0.003458499 0.664475 0.2418498 0.7070939 0.940494 0.3346276 -0.05912315 -0.9355562 -0.3481968 -0.05910623 -0.9396923 -0.3420211 2.78456e-5 -0.9396924 -0.3420211 2.55636e-5 -0.6644025 -0.2418182 0.7071728 -0.01494896 0.04075998 -0.9990571 0.3417108 -0.9387927 -0.04361385 0.6644636 0.2418453 0.7071061 0.664461 0.241841 0.70711 0.6644632 0.2418467 0.707106 0.6644644 0.2418413 0.7071067 0.6644644 0.2418459 0.7071052 0.6644634 0.2418443 0.7071066 0.6644693 0.241847 0.7071002 -0.6651937 -0.2420499 -0.7063493 0.6645289 0.2418639 0.7070384 -0.6667606 -0.2424824 -0.7047218 0.6645218 0.241859 0.7070467 0.6641458 0.2417782 0.7074276 0.6645053 0.2418523 0.7070645 0.6645023 0.2418496 0.7070683 0.6643917 0.2418417 0.707175 0.6646846 0.2418211 0.7069066 0.6644393 0.2419055 0.7071083 0.6644607 0.2418633 0.7071027 -0.6648023 -0.2419945 -0.7067367 0.6644435 0.2418361 0.7071282 -0.6628071 -0.2411005 -0.7089127 0.6644418 0.241836 0.7071298 0.6644667 0.2418462 0.7071028 0.6644791 0.2418595 0.7070867 0.6644627 0.2418448 0.7071071 0.6644675 0.2418497 0.7071009 -0.6644626 -0.2418434 -0.7071077 -0.6628521 -0.234488 -0.7110855 -0.7357924 -0.2118601 -0.6432145 -0.6831644 -0.2510312 -0.6857622 -0.6411471 -0.3054698 -0.7040019 -0.716868 -0.2609151 -0.6465475 -0.6411507 -0.3054615 -0.7040022 -0.7168685 -0.2609148 -0.6465471 -0.7168641 -0.2609202 -0.6465498 -0.716865 -0.2609239 -0.6465473 -0.6411483 -0.3054656 -0.7040026 -0.716871 -0.260913 -0.6465451 -0.6411495 -0.3054701 -0.7039995 -0.6411462 -0.305471 -0.7040023 -0.6411496 -0.3054698 -0.7039996 -0.7168806 -0.26091 -0.6465356 -0.7168694 -0.2609162 -0.6465455 0.6643965 0.2418806 -0.7071571 0.6874995 0.1781198 -0.7040013 0.6875026 0.1781158 -0.7039994 0.7168716 0.260923 -0.6465403 0.6874937 0.1781288 -0.7040047 0.7168673 0.260928 -0.646543 0.6874981 0.1781374 -0.7039982 0.6874932 0.1781363 -0.7040033 0.7292882 0.3039037 -0.6130101 0.7168628 0.2609264 -0.6465487 0.7167582 0.260889 -0.6466798 0.7168679 0.2609199 -0.6465457 0.6874998 0.1781175 -0.7040016 -0.001217842 -3.28912e-4 -0.9999993 0.003127872 -5.80093e-4 -0.999995 -4.35786e-7 0 -1 0.08146446 -0.8642158 0.4964823 -0.7537297 -0.2079408 -0.6234198 0.5513094 0.3229911 0.7692431 0.6690149 0.5364293 0.5144539 0.58663 0.758853 0.2828559 0.6371468 0.6386842 0.4314239 0.7764454 0.606795 0.1700953 -0.2132154 0.2706577 0.9387671 -0.2426685 0.232676 0.941793 0.3195158 0.3290174 0.8886267 -0.05732232 -0.05784887 0.9966784 -0.8280214 0.2686351 0.4921543 -0.6831166 0.5022509 0.5301848 -0.7200989 -0.09146946 0.687816 0.3073902 -0.9482044 0.0801236 0.9652286 -0.2449707 0.09123176 0.8180621 -0.5740045 0.0359646 0.8225924 -0.5676716 0.03302669 -0.2099444 -0.9770734 0.03537064 -0.4673676 -0.2057899 0.8597779 -0.9391005 -0.3423773 0.02946496 -0.9366087 -0.3486801 0.03444528 -0.8165965 0.5760867 0.0359801 -0.8283379 0.5594167 0.03015571 -0.3536325 0.9347233 0.03516286 0.2099605 0.9770693 0.03538691 0.4796978 0.174598 0.8598871 0.4853964 0.1781213 0.8559575 0.1166262 -0.2483522 0.9616234 0.2767078 -0.805933 0.5233591 0.3431652 -0.9386277 0.03486776 -0.1464387 -0.8706995 0.4695085 -0.1679177 -0.1733847 0.9704337 5.60255e-4 -0.00268203 0.9999963 -0.9392684 -0.3419167 0.02946084 -0.8191863 0.572398 0.03598099 -0.1227422 0.2537421 0.9594527 0.1977561 0.4384332 0.8767377 -1.65943e-4 2.15127e-4 1 -5.24518e-6 6.79512e-6 1 -0.3418205 0.9391106 0.03507232 0.9392566 0.3419489 0.02946341 0.9365925 0.348676 0.03492575 0.6831218 -0.5033328 -0.5291512 0.8202008 -0.5709868 0.03528594 0.8281137 -0.5597506 0.03011631 0.1461623 -0.4073621 0.9014948 0.3535558 -0.9347576 0.0350238 -0.2139599 -0.9762645 0.03360021 -0.4377534 -0.2371712 0.8672496 -0.9395759 -0.3410737 0.02942985 -0.789279 0.6130096 0.03546822 -0.8009964 0.5980278 0.02770906 0.4662116 0.2052659 0.8605304 0.8333027 0.2765901 0.4786487 1.93699e-4 -2.51086e-4 1 1.2347e-4 -1.60057e-4 1 0.247051 0.9681904 0.03966301 0.2617786 0.9645273 0.03404897 0.9854992 -0.1575195 0.06307905 0.3536258 -0.9347268 0.03513795 0.3534134 -0.9348204 0.03478443 -0.1251558 -0.5031239 0.8551037 -0.4371368 -0.2377981 0.867389 -0.9395841 -0.3410506 0.02943581 -0.3503969 0.9359501 0.03492027 -0.3419083 0.9395088 0.02054756 0.1640353 0.6999467 0.6951022 0.4678895 0.2060112 0.859441 0.8330702 0.2768936 0.478878 1.23459e-4 -1.6005e-4 1 0.01252222 -0.03970634 0.9991329 0.2430477 0.9697831 0.02117979 0.9366109 0.3486745 0.03443968 0.9854983 -0.1575163 0.06310224 0.8166086 -0.576074 0.03590673 0.8280836 -0.5597951 0.0301181 0.3534947 -0.9347841 0.03493362 -0.2099393 -0.9770749 0.03535968 -0.2140761 -0.9762393 0.0335893 -0.9395821 -0.3410556 0.0294367 -0.93658 -0.3486738 0.03527605 -0.8196365 0.5717926 0.03534787 -0.8284519 0.5592523 0.03007042 -0.3503921 0.9359454 0.0350939 -0.3533756 0.9346223 0.04008716 0.1666529 0.6994572 0.6949723 0.1680356 0.4794958 0.8613059 -0.01301074 0.0390793 0.9991515 1.23472e-4 -1.60059e-4 1 0.01252222 -0.03970646 0.9991329 0.3533853 -0.9348302 0.03480499 -0.9365815 -0.34867 0.0352748 -0.2547881 0.7097261 0.6567891 -0.3418992 0.9395124 0.02053439 0.1666691 0.6995225 0.6949027 -0.01301014 0.03907734 0.9991516 1.93778e-4 -2.51195e-4 1 0.939118 0.3423294 0.02946275 0.9366183 0.3486545 0.03444099 0.8166087 -0.5760737 0.03591179 0.04810541 -0.2133744 0.9757855 0.3536173 -0.9347299 0.03514093 0.3534944 -0.9347841 0.03493392 -0.1251509 -0.5030881 0.8551255 -0.2140774 -0.9762393 0.03358525 -0.437147 -0.2377952 0.8673846 -0.9365796 -0.3486749 0.03527706 -0.2548061 0.7097799 0.6567241 -0.3419014 0.9395114 0.02053791 0.1680126 0.4794527 0.8613343 0.4661722 0.205254 0.8605546 0.833307 0.2765883 0.4786422 -0.0130105 0.03907841 0.9991515 1.93699e-4 -2.51085e-4 1 1.23484e-4 -1.60068e-4 1 0.2612863 0.9646611 0.03403723 0.936613 0.3486678 0.03445327 0.3536238 -0.934727 0.03515547 0.3534069 -0.9348228 0.03478521 -0.2099319 -0.9770761 0.03537189 -0.9395759 -0.3410727 0.02943938 -0.9365797 -0.3486754 0.03526932 -0.8196418 0.5717962 0.03516101 -0.09634751 0.2142126 0.9720237 -0.2547942 0.7097406 0.6567711 -0.3503983 0.9359496 0.03492438 0.8332871 0.276589 0.4786764 1.93716e-4 -2.51099e-4 1 0.9391146 0.3423388 0.02946555 0.9366148 0.3486633 0.03444707 0.8165955 -0.5760923 0.03590786 0.8281182 -0.5597451 0.03009653 0.04811334 -0.21341 0.9757773 0.3536265 -0.9347265 0.03513818 0.3534134 -0.9348204 0.03478139 -0.125115 -0.5030618 0.8551463 -0.2099375 -0.9770745 0.03537863 -0.2140135 -0.9762533 0.03358221 -0.8282621 0.5595337 0.03006762 -0.2547848 0.7097278 0.6567885 -0.3503882 0.9359536 0.03491306 -0.3418952 0.9395138 0.02053344 0.1640321 0.6999762 0.6950733 0.1666362 0.4761984 0.8634046 0.8330482 0.2768784 0.4789249 1.23456e-4 -1.60046e-4 1 0.2430526 0.9697816 0.02119415 0.9854992 -0.1575115 0.06310147 0.8165805 -0.5761136 0.0359115 0.8280791 -0.5598022 0.03010982 0.3534286 -0.9348137 0.03480774 -0.1251339 -0.5030741 0.8551363 -0.209933 -0.9770771 0.03533428 -0.2139554 -0.9762665 0.03357189 -0.4371531 -0.237815 0.867376 -0.9365878 -0.3486546 0.03526169 -0.09635543 0.2142253 0.9720202 -0.2547906 0.7097451 0.6567677 -0.3533689 0.9346242 0.04010057 0.1977635 0.4384505 0.8767274 -1.65975e-4 2.15154e-4 1 -5.2509e-6 6.79506e-6 1 -0.3417539 0.9391387 0.03496891 -0.3419514 0.9390556 0.03526806 0.208637 0.9773252 0.03613817 0.4057625 0.1535179 0.9009934 0.9392496 0.3419672 0.02947461 0.05399829 -0.2029094 0.9777076 -0.1251541 -0.5031258 0.8551029 -0.2099838 -0.9770652 0.03536415 -0.7892755 0.6130142 0.0354681 0.1513658 0.1718811 0.9734194 0.2474891 0.9681121 0.0388363 1.52612e-4 -2.74893e-4 1 0.00684446 -0.01232844 0.9999006 0.9391613 0.3416894 0.03499203 0.819325 -0.5722081 0.03583914 0.3536253 -0.9347269 0.03514182 0.3534119 -0.9348204 0.03479814 -0.1245291 -0.5021557 0.8557642 -0.2099603 -0.9770695 0.03538298 -0.9362936 -0.3499718 0.02956795 -0.9397481 -0.3398696 0.03691065 -0.8381038 0.5449279 0.0252099 0.5012075 0.2713866 0.8216692 0.5305545 0.2047477 0.8225512 0.5439585 0.2442973 0.8027628 0.5855332 0.1560577 0.7954853 0.5392319 0.1962431 0.8189736 0.5013791 0.2106153 0.8392022 0.5428491 0.1973533 0.8163127 -0.5434491 -0.1978271 -0.8157987 0.5654887 0.2058855 0.798645 0.5527077 0.1984731 0.8093966 0.5408859 0.1968096 0.817746 0.4962421 0.1926823 0.8465325 0.605608 0.2316191 0.7613091 0.5272364 0.147495 0.8368197 0.543228 0.2763092 0.7928156 0.4779207 0.1656292 0.8626464 0.5195124 0.2204388 0.8255383 0.5143147 0.1871905 0.836923 0.6459208 0.1235965 0.7533329 0.5254626 0.1669037 0.8342854 0.53533 0.2344696 0.8114469 0.5433152 0.2231898 0.8093177 0.4975419 0.1773036 0.8491263 0.1643801 0.08676207 0.9825739 0.4910252 0.2893673 0.8216817 0.6171039 0.2202131 0.7554397 0.5372604 0.217159 0.8149806 0.5419017 0.1669477 0.8236936 0.5526735 0.1571356 0.8184502 -0.7793465 -0.4483044 -0.4377695 0.00882852 3.52824e-4 0.999961 -0.7557571 -0.2809588 0.5915179 -0.8335294 -0.1212661 0.5390024 -0.05038225 0.8243091 0.5638937 -0.2720478 0.6792926 0.6815803 0.5769359 -0.3931828 0.7159276 0.2470089 -0.627489 0.7384065 -0.153317 -0.7482494 0.6454585 -0.1045381 -0.6711013 0.7339584 -0.001909911 1.73363e-4 -0.9999982 7.07985e-4 5.78322e-4 -0.9999996 0.4981777 -0.05651175 0.8652315 -0.07722336 -0.3581177 0.9304774 -0.2331781 -0.2663838 0.9352367 -0.3963862 -0.1081459 0.9116922 -0.3065736 0.2081056 0.928819 -0.1418014 0.3214288 0.9362564 0.3893006 0.4350032 0.811922 0.3913777 0.1961705 0.8990778 -0.01802825 0.4059302 0.9137263 -0.3332849 0.476526 0.813538 -0.3812668 0.3901213 0.8381175 -0.4248826 -0.1239463 0.896723 -0.2932321 -0.3086886 0.904835 -0.2086457 -0.5073865 0.8360776 -0.07725381 -0.3709115 0.9254494 -0.003969311 -0.7172569 0.6967976 0.3852473 -0.4125301 0.8254716 0.5588278 -0.2996386 0.7732583 0.721137 -0.221275 0.656505 0.9685884 -0.2252992 0.105247 0.9548659 -0.2929998 -0.04880797 0.8846273 -0.4633921 -0.05198508 0.8519098 -0.5166507 0.08556765 0.7001969 -0.7089453 0.08438575 0.4543904 -0.8894003 0.04996711 -0.08067053 -0.9931595 0.08441954 -0.6012805 -0.790089 0.119253 -0.7702789 -0.6377058 -0.001302659 -0.9041299 -0.4272576 -3.00247e-5 0.1945877 -0.9795588 -0.05099433 -0.5431237 -0.838231 -0.04884338 -0.6874031 -0.7236383 -0.06184387 -0.8102256 -0.5861171 0.001166105 -0.7345052 -0.6786029 -4.66002e-4 -0.4205355 -0.9072688 -0.003647446 -0.2403849 -0.9704974 -0.01870298 -0.005126953 -0.9995225 0.03047394 0.1066997 -0.9789397 -0.1740471 0.3308439 -0.9047471 0.2682819 0.3794964 -0.923155 0.06137841 0.6800284 -0.723087 0.1212717 0.8002372 -0.5982579 -0.04132544 0.9053164 -0.4247223 -0.003643095 0.9902492 -0.1393046 9.15035e-4 0.9988603 -0.04772734 -4.64842e-4 0.9672468 0.2538382 0 0.9673552 0.2534244 6.99314e-5 -0.6887111 -0.7250174 0.005170345 0.9974157 0.07183665 0.001168131 -0.9042105 -0.4270871 0 0.8910644 0.4506603 0.05394071 -0.0181843 0.006851375 0.9998112 -0.02142006 0.01351964 0.9996792 1.39805e-4 -1.34267e-4 1 -0.001173317 0.00834465 0.9999646 -0.01183849 0.002071559 0.9999279 -0.001706719 0.008548319 0.999962 -0.003299951 0.006738483 0.9999719 -1.35656e-7 -6.3408e-5 1 8.60403e-5 8.07609e-5 1 1.03237e-4 6.35148e-5 1 -6.2312e-5 -2.28377e-5 1 -5.96021e-4 3.35331e-5 0.9999998 -4.31356e-4 1.14085e-4 1 -4.12151e-4 2.04728e-4 0.9999999 -4.75012e-5 4.02515e-4 1 -3.07699e-4 1.01096e-4 1 -1.64451e-4 5.36236e-4 1 -4.64118e-5 4.83879e-4 0.9999999 1.75818e-5 5.54556e-5 1 2.6449e-5 4.6568e-5 1 4.52888e-4 5.2109e-4 0.9999998 4.2083e-4 2.03684e-4 0.9999999 -3.4908e-5 3.96369e-4 1 0.8941799 0.4476452 -0.007503688 0.9308347 0.3653892 0.006128013 0.9474472 0.3198649 0.005503654 0.957279 0.2891506 0.002998709 0.9618092 0.2737209 1.99328e-4 0.9616262 0.274342 -0.003399014 0.9199187 0.392046 -0.007040739 0.9267634 0.3755732 -0.007382154 0.9333356 0.3589249 -0.007596909 0.9456024 0.3252462 -0.00715661 0.956618 0.291297 -0.005309283 0.9154919 0.4023352 9.88008e-4 0.9096437 0.4151932 -0.01276451 -0.9599972 -0.2800095 2.18897e-4 -0.962159 -0.2724884 -4.75649e-4 -0.9626715 -0.2706712 8.62035e-4 -0.9637511 -0.2664789 -0.01314532 -0.9687132 -0.2481544 -0.003761291 -0.9606652 -0.2764343 0.026582 -0.9602594 -0.2791074 9.78887e-4 -0.9570949 -0.2897625 -0.002676248 -0.9567002 -0.2909904 -0.00703901 -0.9513517 -0.308019 -0.007384955 -0.9268733 -0.375319 -0.006452202 -0.9129985 -0.4079487 -0.003386795 -0.9127339 -0.4085547 2.1354e-4 -0.952928 -0.3031458 0.005580544 -0.9479292 -0.3184222 0.006143093 -0.9254009 -0.3789623 0.004574775 -0.9191804 -0.3938255 0.002997875 -0.7756385 -0.01969599 0.6308701 -0.9968134 0.0108428 0.07902938 0.4288782 0.1771488 -0.8858227 0.4266188 0.172587 -0.887812 0.5944413 0.2231391 -0.7725598 0.4882816 0.1953369 -0.8505437 0.1145663 0.05270391 -0.9920166 0.4726549 0.1770719 -0.8632745 0.4738768 0.179084 -0.8621889 0.4583664 0.1630399 -0.8736809 0.4756428 0.1726265 -0.8625336 0.4815341 0.1746384 -0.8588519 0.4803946 0.1632841 -0.8617188 0.4744976 0.1601935 -0.8655577 0.4790574 0.1507099 -0.8647488 0.4760013 0.1447172 -0.867456 0.4728146 0.1428162 -0.8695113 0.4984518 0.1421834 -0.8551782 0.4853487 0.136959 -0.8635271 0.4800624 0.1296173 -0.8676056 0.4542355 -0.8863984 0.08926421 0.5051839 -0.8601177 0.07061678 -0.94123 -0.3351459 0.04199463 -0.9350407 -0.3519484 0.04279291 -0.5981801 0.7994161 0.05580973 -0.9352419 -0.3522421 0.03533077 0.430804 -0.9023585 0.01253205 -0.9318313 -0.3611972 0.03503084 -0.7490016 0.6611571 0.04322022 -0.9227122 0.3741863 0.09266561 -0.928497 -0.3696467 0.03542304 -0.9286649 -0.3692578 0.03507423 -0.9295958 0.3685758 -0.001903772 -0.9278453 -0.3713663 0.03449898 -0.9247445 -0.3781605 0.04292297 -0.004683077 0.002322673 -0.9999864 0.02448821 0.01436823 -0.999597 0.00426644 0.001750826 -0.9999895 1.81582e-6 0 -1 -7.81283e-7 0 -1 -6.21399e-7 0 -1 8.42753e-7 0 -1 -4.35809e-7 0 -1 -2.07128e-7 0 -1 -1.80592e-7 0 -1 2.62534e-5 1.33698e-5 -1 2.29644e-6 9.81261e-7 -1 3.02873e-7 6.59457e-7 -1 0.001268565 4.39553e-4 -0.9999992 0.008242309 0.01710438 -0.9998198 7.57653e-7 0 -1 -0.001543104 -6.8987e-4 -0.9999986 0.02301436 -0.007668256 -0.9997057 0.002536714 0.001016557 -0.9999964 -0.002904474 -2.19896e-4 -0.9999958 0.01187503 0.0136789 -0.999836 1.21035e-6 0 -1 0.0845474 0.01977604 -0.9962232 -0.004616081 -0.002209186 -0.999987 0.09199959 0.03534531 -0.9951316 0.04453593 0.01906949 -0.9988258 0.03267282 0.00868386 -0.9994285 0.00847876 0.003086209 -0.9999594 0.008482754 0.003087222 -0.9999593 -0.013583 -0.00445491 -0.9998978 0.08103913 0.02208125 -0.9964663 0.06360101 0.02842414 -0.9975705 0.008480846 0.003086447 -0.9999593 -0.001456856 -5.24452e-4 -0.9999989 0.0479117 0.02735179 -0.9984771 -0.005908668 -0.002150356 -0.9999803 -0.006189584 -0.002236187 -0.9999784 2.7391e-4 -1.95808e-4 -1 0.008480906 0.003086745 -0.9999594 0.008466422 0.003083884 -0.9999594 -0.006772577 -0.00246185 -0.9999741 0.02718877 0.02103823 -0.999409 0.1041417 0.03329062 -0.9940052 9.09523e-7 0 -1 -0.003146827 -5.00232e-4 -0.9999949 0.03923773 0.003633916 -0.9992234 0.008452236 0.003081738 -0.9999595 0.0445131 0.009291231 -0.9989656 0.07732772 0.02807396 -0.9966105 0.8899804 0.4316651 0.1469706 0.9366443 0.3485254 0.03503882 0.4081557 0.912014 0.04048985 0.933286 0.3573935 0.03531676 0.9334161 0.3570808 0.03504025 0.05875712 -0.997981 -0.0241211 0.506263 0.8506814 0.1415592 0.9300923 0.365606 0.03550505 0.1957671 0.9772141 0.08202332 -0.1579639 0.9871256 0.02511221 0.9265555 0.374504 0.03523927 0.921517 0.3864164 0.03858631 0.9217369 0.3859302 0.03819829 0.06842052 0.9943231 0.08148711 0.2168071 0.9703047 0.1072545 0.9195999 0.3912845 0.03510671 0.9194391 0.3916155 0.03562372 0.6737761 -0.7350204 0.07596623 -0.5419684 -0.09164035 0.8353876 -0.5888584 -0.1556252 0.793112 -0.6516504 -0.07235568 0.7550607 -0.3423252 -0.8777859 -0.3351202 0.0898863 -0.9239543 -0.3717917 0.04241633 -0.6305803 -0.7749642 -0.1704179 -0.6585721 -0.7329669 -0.9105188 -0.3493049 -0.2212281 -0.9292624 -0.3162857 -0.1908791 -0.98079 -0.1932572 -0.02650886 -0.9827421 -0.1827346 -0.02874177 -0.9823636 -0.1854542 -0.02384698 0.806186 -0.481767 -0.3434597 0.9628475 -0.1011492 -0.2503871 0.9479555 0.297746 -0.1128177 0.9462416 0.3043213 -0.1096149 0.8264675 -0.4523764 -0.3351225 0.693944 -0.2367908 -0.6799793 0.3190291 -0.8769373 -0.3594461 0.2198458 -0.6040223 -0.766045 0.2198477 -0.6040298 -0.7660384 0.2208644 -0.604034 -0.7657427 0.2208469 -0.6040551 -0.7657312 -0.1755523 0.9844701 0 -0.0870251 0.9962007 -0.003322362 3.29191e-4 2.00709e-4 -1 1.30591e-6 8.39522e-6 -1 2.67195e-6 0 -1 -0.007458448 9.35725e-4 -0.9999718 7.98574e-7 0 -1 -0.6644635 -0.2418448 0.7071064 -0.6644572 -0.2418446 0.7071124 -0.6644777 -0.241849 0.7070916 0.6640084 0.2418015 -0.7075485 0.6643667 0.2418121 -0.7072085 -0.6644623 -0.2418444 0.7071076 -0.6642943 -0.241746 0.7072992 -0.6644614 -0.2418448 0.7071082 -0.6644992 -0.241865 0.7070659 -0.6644771 -0.2418555 0.7070899 -0.6640205 -0.2444034 0.7066426 -0.6644696 -0.2418452 0.7071005 -0.6644631 -0.2418414 0.7071079 -0.6644665 -0.2418448 0.7071036 -0.6411482 -0.3054687 -0.7040014 -0.7168685 -0.2609188 -0.6465454 -0.3420158 0.9388845 0.03900068 -0.6888089 -0.6121502 0.3883485 0.004256844 -0.003960728 0.9999831 -1.47854e-4 7.20989e-5 1 5.33513e-4 -0.001645624 0.9999985 7.27126e-4 -0.001020908 0.9999993 6.10757e-4 -0.002526581 0.9999967 -6.32345e-4 0.001271367 0.9999991 -0.008482396 -0.02502632 0.9996508 -0.002075254 0.001508057 0.9999968 -1.18168e-4 4.84763e-5 1 -0.7723868 0.4818213 -0.4138442 0.6944784 -0.5071828 -0.5103581 0.6324258 -0.3770425 -0.6766659 0.590003 -0.1772541 -0.7877039 0.5047464 -0.256503 -0.8242799 0.5053301 0.14219 -0.8511308 0.2690504 -0.04187178 -0.9622156 0.1660773 -0.9701229 -0.1768617 0.4335677 -0.9004164 0.03563195 0.6787204 -0.7343362 0.009439647 0.8286093 -0.5318833 0.1746627 0.0365498 -0.9993314 0.001065194 -0.04468911 0.4197599 -0.9065344 -0.1878674 -0.9791367 -0.07744246 -0.3132851 0.7614709 -0.5674632 0.5384641 0.7973173 -0.2726569 0.7065621 -0.649229 0.2815524 0.7014667 -0.67676 0.2234737 -0.2863059 0.671787 0.6831772 0.3016085 -0.9498516 0.08254855 -0.793717 -0.5928822 0.1360302 -0.8188977 0.03892493 -0.5726181 -0.852453 -0.0205208 -0.522401 -0.2150005 0.9763491 0.02274036 0.2332823 -0.9721953 0.02038848 0.0908184 -0.9940652 -0.05988663 0.9898732 -0.1418285 -0.005985677 0.9491965 -0.3146577 -0.004088461 0.4805321 -0.8766838 0.02268266 0.2754777 -0.9609792 0.02512222 0.02000659 -0.9997933 -0.003625512 -0.1921346 -0.9813475 0.006452918 -0.3943237 -0.9189658 -0.003306329 -0.2028294 -0.9785894 0.03497546 -0.5829842 -0.8124759 0.003527641 -0.6745117 -0.7382583 0.002984642 -0.970528 -0.2141054 0.1106082 -0.2697357 -0.9618142 0.04643267 -0.5204921 -0.8538594 -0.003511369 -0.6329833 -0.7741518 -0.004603445 0.1450648 -0.9878537 -0.05569046 0.390415 -0.9205139 -0.01517641 0.5134673 -0.8581091 2.83866e-4 0.7403141 -0.6722193 -0.007509768 0.03634959 -0.9993286 0.004600703 -0.6678909 -0.7160155 0.2030854 0.2220664 -0.9749648 -0.01141053 0.2600094 -0.9655779 -0.007392227 0.3292784 -0.9276598 -0.176134 0.6018422 -0.3242896 -0.7298097 0.3315118 -0.9292448 0.1631076 0.843101 -0.5377325 0.004953086 0.03966754 -0.9991673 0.009563505 0.2384815 -0.9695881 -0.05500566 -0.2076612 -0.9769791 0.04887557 -0.02287441 -0.7782682 -0.6275153 0.3880174 -0.837143 -0.385531 -0.08992397 -0.6682507 -0.7384814 -0.4248095 0.2046377 -0.8818505 -0.1240651 0.2331457 -0.9644952 0.7475516 -0.0829662 0.6590017 0.7433487 -0.09095978 0.6626908 0.03806936 0.1675063 0.9851358 -2.4598e-5 6.09946e-5 1 -0.2798131 0.1692165 0.9450241 0 0 1 0 0 1 -2.1967e-7 0 1 -2.17573e-7 0 1 1.99506e-7 0 1 -4.76542e-7 0 1 0 0 1 -8.94493e-7 0 1 -3.33227e-7 0 1 0.6302051 0.3465345 0.694806 -0.5160233 -0.5489145 0.6575812 -0.4672362 -0.5440797 0.6968987 -0.7067412 -0.1398417 0.6935136 -0.7055486 -0.1394647 0.6948027 0.1349558 0.7111592 0.6899562 -0.2417995 0.6642897 0.7072852 -0.2418441 0.6644617 0.7071082 -0.4502344 0.3679524 0.8135724 -0.5195361 0.1795713 0.8353661 0.3420165 -0.939694 2.05194e-5 -0.1680815 0.9857546 -0.00604856 0.1810891 0.983304 -0.01789283 0.1865109 0.9822935 -0.01769632 0.5108438 0.8592438 -0.02718293 0.5146844 0.8569549 -0.02698695 0.7780224 0.6273254 -0.03382569 0.784527 0.6192042 -0.03322172 0.8757398 0.48155 -0.03448873 0.8757412 0.4815477 -0.03448712 0.8787325 0.4758235 -0.03770035 -0.5021645 0.8647503 -0.006150126 -0.7707753 0.636856 -0.01789236 -0.998999 -0.02994656 -0.03323137 -0.9925912 -0.1182816 -0.02779316 -0.7742866 0.6325877 -0.01769655 0.1280498 0.9910908 0.03663659 -0.493167 0.8697069 -0.01990771 -0.9954109 0.0881465 -0.03724908 -0.6374256 -0.7684469 -0.05637526 0.162565 -0.9860772 -0.03499245 0.7355371 -0.6772732 -0.0169211 0.7922143 0.6092389 0.03499269 -0.5094111 0.8600651 -0.02808076 -0.9149887 -0.4019594 0.03499239 0.9998277 -0.007646262 0.01692104 4.09714e-4 0.005685865 -0.9999839 -0.06211924 -0.01985788 -0.9978712 0.01249331 -0.02419281 -0.9996293 0.008981585 -0.002525389 -0.9999565 0.0139696 0.00215882 -0.9999001 0.002064049 -0.01252448 -0.9999195 0.5742686 0.818492 0.01692116 0.5325389 0.8464055 0 -0.7760421 0.6306812 0 0.735544 -0.6772657 -0.01692169 0.988069 0.1527201 -0.01990741 -0.7433037 0.6687402 0.01691955 -0.9975924 0.06934994 0 -0.7062278 -0.7077048 0.01990652 0.7007238 -0.7134328 0 0.008304774 0.01320171 -0.9998784 -0.001333534 0.01308846 -0.9999135 -0.001025319 -0.008704185 -0.9999617 -0.06213331 -0.01985937 -0.9978703 0.01249635 -0.02419435 -0.9996292 -1.37793e-4 1.13168e-4 -1 -0.01029598 1.97614e-4 -0.9999471 1.99708e-6 0 -1 0.2947809 -0.9548907 0.03588831 0.06654852 0.9961096 0.05776757 0.850608 0.5225796 0.05810916 0.9866944 0.1524994 -0.05637484 -0.7191752 -0.6939472 -0.03499239 -0.9991447 0.01917892 -0.03663563 -0.3938301 0.9185169 -0.03499311 0.08075034 0.2677159 0.9601081 0.04973334 0.1281664 0.990505 -0.265138 -0.08292216 0.9606382 0.6022881 -0.797706 0.03023886 0.6205091 -0.7839422 0.02007651 -0.1944643 -0.9805731 -0.02569156 0.7922145 0.6092388 0.03499484 0.97499 0.2205455 -0.02746438 -0.8396871 0.5401367 -0.05637365 -0.1014319 0.9945389 -0.02457773 -0.05498188 0.1695562 0.9839856 0.09127789 -0.023862 0.9955396 -0.05525761 -0.06317764 0.9964715 -0.09995353 -0.07686734 0.9920185 0.9116962 -0.4091731 0.03724902 0.6527947 -0.7570959 -0.02578401 -0.7876768 0.6157671 0.01990854 0.05932492 0.9980402 0.01990753 0.8550656 0.5181376 0.01990765 -0.3284181 -0.9439876 -0.03207993 -0.8408523 0.5408987 -0.01990789 0.8039224 0.5944011 -0.01990717 3.1248e-4 -0.01279753 0.9999181 -0.04331105 -0.03600627 0.9984126 -0.0454216 0.07447439 0.9961881 2.25073e-4 0.01469284 0.9998921 -0.0089643 -0.002137005 0.9999576 -0.0156008 0.012196 0.9998039 0.9850348 0.1713675 -0.01842969 0.88108 -0.4710761 0.04225307 0.1811479 -0.9827502 0.03724843 0.5742688 0.8184921 0.01692116 0.2261973 -0.9738367 0.02183938 -0.7193366 -0.6940939 0.02808296 -0.9996727 0.01918894 -0.01692098 -0.3938257 0.9185188 -0.03499382 -3.32e-4 1.77477e-4 1 -4.61388e-4 -8.02555e-5 1 5.86227e-4 5.87322e-4 0.9999997 -0.01386368 0.01247292 0.9998261 -3.15285e-4 -4.49234e-4 0.9999999 0.3795984 0.02573001 0.9247936 -0.7450289 0.0864008 0.6614127 0.7935683 -0.6084797 0.001336812 0.9062539 -0.4223362 -0.01833277 0.9763979 -0.2159757 0.001351952 -0.1037603 0.9944054 -0.01979488 0.3038931 -0.9527053 0.001348912 -0.1028839 -0.9946933 -4.61644e-4 -0.5002047 -0.8658543 -0.009575963 -0.6833481 -0.7300763 0.004905164 -0.07422906 0.9970479 0.01964294 0.8188049 0.5736937 0.0208373 0.9238636 0.3827195 0.001349389 -0.9991869 -0.03963822 -0.007388234 -0.8106321 0.5855546 -0.001289069 -0.3034687 0.9528404 -0.001450121 0.1290829 0.9916329 0.001351654 0.6752871 0.7375538 0.001359045 0.9062904 -0.4221438 0.020796 0.9062532 -0.4223378 -0.01833164 0.9763953 -0.2159875 0.001352012 0.303881 -0.9527091 0.001348316 -0.8924625 -0.4510443 0.008361697 -0.8730379 -0.4876419 0.003162503 0.8268765 0.5620422 0.01959347 -0.9991881 -0.03960824 -0.007386982 -0.8106165 0.5855759 -0.001289308 0.1290909 0.9916319 -0.001350998 0.6752706 0.7375688 -0.001359283 0.7836366 0.6194589 0.04673606 0.9392413 0.3419206 0.03027093 -0.2662796 -0.9632452 0.03541368 -0.939051 -0.3424178 0.03055411 -0.936432 -0.3491172 0.03482073 -0.3029796 -0.9524281 0.03292775 -0.9971238 0.05463683 0.05252569 0.2485539 0.9676636 0.04299062 0.7835931 0.6195131 0.0467503 0.9928878 -0.1057535 0.05468243 0.2562666 0.9660004 0.03421401 0.7842035 0.6200633 0.02337449 0.9392555 0.3418663 0.03044068 0.9983511 0.02906501 0.04950159 0.27275 0.961304 0.03875845 -0.7835107 -0.6194376 0.0490728 -0.9983501 -0.02909535 0.04950422 0.8071964 -0.5888448 0.04117989 0.8116829 -0.5823922 0.04461163 -0.192263 -0.9795419 0.05943536 -0.939374 -0.3419078 0.02598863 -0.2630001 -0.9641556 0.03514313 -0.2703034 -0.96202 0.0381273 -0.7834993 -0.6194499 0.04909944 -0.9392437 -0.3419159 0.03024512 -0.9978322 0.06143659 0.02359014 -0.2637027 -0.9639863 0.03451651 -0.9944668 0.08632898 0.05986088 -0.3469294 0.9365149 0.05079454 0.2437316 0.9690921 0.03815191 0.7946718 -0.6058046 0.03869897 0.8087982 -0.5862911 0.04591566 0.8043094 -0.5921944 0.04891091 -0.9983429 -0.02906322 0.0496661 -0.8417797 0.5388537 0.03230917 -0.8299043 0.5566848 0.03689098 -0.2716152 -0.9609868 0.05224567 -0.9472427 -0.3176339 0.04289644 -0.7846478 0.6188595 0.03661578 -0.9498743 -0.3105818 0.03574651 -0.9526463 -0.3009963 0.04320245 -0.8001005 0.5987118 0.0371946 -0.8120772 0.5817443 0.04587256 -0.8083468 0.5874884 0.03785675 -0.8140165 0.5791218 0.04466742 0.7895821 -0.6115772 0.05033451 0.3403317 -0.940148 0.01720964 0.7892848 -0.612347 0.04539495 0.8151093 -0.5785923 0.02877444 0.9487938 0.3138975 0.03547972 0.7890425 -0.6132394 0.03673398 0.8082079 -0.5870881 0.04612839 -0.2055578 -0.9767677 0.06058901 -0.9910154 0.1082431 0.07856208 0.1751162 0.9839236 0.03505617 0.8601377 -0.5089889 0.03306818 0.5363568 0.839761 0.08439695 0.2247234 0.9724404 0.06212252 0.9393792 0.341894 0.02598834 0.4021912 -0.9144793 0.04438471 -0.2424229 -0.9686141 0.05493533 0.4923087 -0.8695622 0.03864818 -0.9212784 -0.386159 0.04612517 0.1552886 -0.5204723 0.8396393 0.6547892 0.2380075 0.7173587 0.1733152 0.713081 0.6793212 0.1489077 0.6782472 0.7195883 -0.7147651 -0.3023202 0.6306452 0.2642602 -0.9496665 -0.1682266 0.6325002 0.2753419 0.7239684 0.4715185 0.1722766 0.8648648 0.9390299 0.3424562 0.03076744 0.6495838 0.3325204 0.6837186 0.3281462 -0.36772 0.8701162 0.4497098 0.1644815 0.8778992 0.6512976 0.2632203 0.7117068 0.938708 0.3416547 0.04581969 0.9437969 0.3286303 0.03534692 0.5072146 0.8569983 0.0910356 0.3260013 0.9425589 0.07284182 -0.1444239 0.9290529 0.3405914 0.416506 0.1412674 0.8980904 0.4766258 0.1600984 0.8644053 -0.7204763 -0.2781024 0.6352739 0.8855066 -0.4632927 0.0351842 0.8361058 -0.5466341 0.0460267 -0.07373869 0.7746056 0.6281312 0.1358346 0.08126056 0.9873934 -0.1136355 -0.06531953 0.991373 -0.01796299 -0.9661164 0.2574808 0.6512265 0.2433263 0.7188161 -0.1461149 0.9541391 0.2612838 -0.7421962 -0.2715309 0.6127118 -0.6895737 -0.2662538 0.6734962 0.5337769 -0.8378039 0.1147475 -0.04009324 -0.1308825 0.9905868 -0.08025145 0.7892482 0.6088081 -0.665097 -0.2513237 0.7031944 -0.6282019 -0.2265421 0.7443394 -0.3357769 0.6099069 0.7178214 -0.3894906 -0.7455902 0.5407332 -0.04659169 -0.03783476 0.9981973 -0.6076949 -0.04292047 0.7930099 -0.5866978 -0.2664385 0.7647197 -0.8203915 0.570279 0.04170954 -0.09810215 0.1352349 0.985945 -0.465578 -0.1701204 0.8685023 -0.4596319 -0.1673304 0.8722035 0.1721841 -0.147745 0.973922 -0.136048 -0.03481882 0.9900903 0.245759 0.9682653 0.04544061 -0.9464919 0.3111508 0.08566421 -0.8359317 0.5454621 0.06073999 -0.6640791 -0.2479998 0.7053332 -0.1919059 0.3250735 0.9260126 0.3270322 0.6442008 -0.6914154 -0.02381914 -0.02769857 0.9993326 -0.2149191 -0.116609 0.9696453 -0.4994989 0.5014531 0.7064318 0.2179856 -0.8418371 -0.4937537 -0.8595032 0.5101836 0.03109693 -0.646206 0.1020921 0.7563036 -0.5689991 0.3976507 0.7198014 -0.4063298 0.8884044 -0.2136208 -0.6462017 -0.26444 0.7158876 -0.01771247 -0.2224801 0.9747763 0.4601765 0.1674693 0.8718897 0.4593303 0.1670701 0.8724125 -0.3957259 -0.002223312 0.918366 -0.3671174 0.7793044 0.5078479 -0.7541545 -0.2644401 0.6011012 -0.7145857 -0.237371 0.6580443 0.2303515 -0.8921719 0.3885454 0.5500646 0.1255599 0.8256294 0.6354064 0.2312855 0.7367264 -0.03206962 -0.4502236 0.8923399 -0.8544157 0.510997 -0.09410655 0.6604013 -0.7263858 0.1903517 -0.03491967 0.1738641 0.9841504 -0.07471817 3.83223e-4 0.9972047 0.480783 -0.4028745 0.7788067 0.9487708 -0.3042038 0.08540481 0.1446321 -0.1718056 0.974456 0.5936169 0.4322123 0.6788312 0.4946137 0.5125033 0.7019243 -0.02195012 0.01465398 0.9996517 0.4989625 -0.8383948 0.2193869 0.8645788 -0.5014032 0.03314489 0.6709641 0.2191257 0.7083721 -0.8727123 -0.1530702 -0.4636193 0.06332957 -0.8691459 0.4904843 -0.1547706 -0.969755 -0.1887363 -0.2517417 -0.9666729 0.04658001 0.9699759 -0.2318483 0.07343876 0.2347773 -0.9712796 0.03867369 -0.6931635 0.7078857 -0.1357287 0.1280133 0.7089018 0.6935927 0.04751962 0.0571652 0.9972332 -0.7224377 -0.2364562 0.6497478 0.7504872 0.0515021 0.6588753 0.6964427 -0.2168219 0.684073 0.6196019 0.2217751 0.7529339 0.6344794 0.2309476 0.7376308 0.1043115 -0.3261164 0.939557 0.8297717 -0.5566998 0.03955447 -0.1828547 -0.8109458 0.5558159 -0.6617229 -0.2408587 0.710007 -0.6534469 -0.2357761 0.719317 -0.06439524 0.318161 0.9458472 0.03667175 0.02982747 0.9988821 0.7910658 0.2859658 0.540776 -0.6376433 -0.769329 0.03929382 -0.05921339 0.0658015 0.9960743 -0.4655905 -0.1700208 0.868515 -0.4594767 -0.1672716 0.8722968 0.004803001 -0.1599302 0.9871167 0.589179 -0.7621008 0.2684596 0.1771506 0.9835312 0.03583729 0.2216163 0.9740262 0.0464698 -0.9518488 0.294538 0.08503669 -0.8395248 0.5399323 0.06059342 -0.2243496 0.2948533 0.928832 0.7772051 0.295153 0.5557312 -0.3942103 -0.145776 0.9073851 -0.8631303 0.5038999 0.03303128 -0.8274494 0.5596652 0.04585188 0.09023022 0.1744156 0.9805293 -0.5221765 -0.7329575 0.4360104 -0.0688942 -0.1643258 0.9839974 0.1331336 -0.5267646 0.8395204 0.07707613 0.0420798 0.9961369 -0.4626271 0.3963276 0.7930325 0.02506673 0.8388326 0.543812 0.2363136 0.970606 0.04560524 -0.9490658 0.3032929 0.08536773 -0.47569 0.5317648 0.700675 -0.4122572 -0.3051404 0.8584482 0.0944761 0.001030445 0.9955266 -0.4061044 0.4435467 0.7989654 -0.6685094 -0.2720339 0.6921653 -0.8650421 -0.3901638 0.3153958 -0.6427894 -0.4546048 0.6165682 -0.9214562 0.3847345 0.05383324 -0.3884887 -0.5680746 0.7255121 -0.6192789 -0.5546078 0.5557913 0.1891893 0.1578361 0.9691725 -0.5982509 -0.2344301 0.7662497 -0.9756116 -0.137615 -0.1710092 -0.8281601 0.5591462 0.03881365 -0.8206417 0.5703741 0.03493863 9.71358e-4 -0.1490915 0.9888229 0.4713383 0.1662698 0.8661378 0.5415596 0.1971545 0.8172168 -0.02061545 0.5986989 0.800709 -0.467239 0.6562435 0.5924798 -0.2502163 -0.9672991 0.04152649 0.6882832 -0.7203772 0.08557522 -0.03380715 -0.07809036 0.9963729 -0.3844796 0.4487018 0.8067479 -0.7504906 -0.2731568 0.6017885 -0.9389359 -0.3422788 0.03527969 -0.9391205 -0.341811 0.03490066 0.6512351 -0.757551 0.0448268 0.5324989 -0.7748636 0.3406339 0.7022979 0.2945524 0.6480869 0.691264 0.2874766 0.6629565 0.1647577 -0.2270513 0.9598451 -0.6487577 -0.2411158 0.7217872 -0.6285038 -0.2285595 0.7434673 -0.1622961 0.3469007 0.9237531 -0.8546674 0.517062 0.04680305 0.1674154 0.7623535 0.6251315 0.6331167 0.251389 0.7320976 0.5189224 -0.4034262 0.753636 0.5289698 -0.4187729 0.7381194 0.1751624 -0.4815277 0.8587487 0.257494 -0.6453588 0.7191723 -0.133148 -0.7334583 0.6665662 -0.6582319 -0.2452419 0.7117494 -0.4595637 -0.1188535 0.8801563 -0.5526368 0.4253301 0.7167196 -0.2823521 0.8069686 0.5187283 0.1634767 0.7397471 0.6527248 0.1231353 0.6844959 0.7185424 0.2488706 -0.6393457 0.7275304 0.2681784 -0.7164108 0.6440777 -0.1003524 -0.6848586 0.7217328 -0.6541726 -0.2439501 0.7159236 -0.6375054 -0.2326515 0.7344796 -0.5815495 0.3954134 0.710949 0.1623576 0.7401158 0.6525862 0.6549526 0.2437958 0.7152627 0.6438 0.2362127 0.7278222 0.5760888 -0.415782 0.703738 -0.6541688 -0.2439451 0.7159288 -0.2608166 0.7704253 0.5817384 0.128999 0.6938208 0.7084998 0.1330074 0.6992475 0.7023974 0.2454623 -0.6261805 0.7400313 0.2681824 -0.71642 0.6440658 -0.6489499 -0.2388479 0.7223682 -0.5513558 0.4113506 0.7258081 -0.2159197 0.6007305 0.7697412 0.1277385 0.8229826 0.5535184 0.6432476 0.2362053 0.7283129 0.5786268 -0.3905824 0.7159863 -0.1567009 -0.7486514 0.6441785 -0.654155 -0.2440545 0.7159042 -0.5260034 0.379899 0.7609187 0.6487584 0.2391137 0.7224522 0.7175958 -0.4854384 0.4994057 0.5241215 -0.4371314 0.7308987 0.2223383 -0.6363345 0.7386773 0.1028113 -0.4797839 -0.8713423 -0.09767222 -0.7057519 0.701694 -0.414445 0.3548878 0.8380275 0.6541979 0.2436635 0.715998 0.6471952 0.2388823 0.7239294 0.4691068 -0.3673042 0.8031355 -0.1159216 -0.8323014 0.542067 -0.6486624 -0.2395803 0.7223838 -0.5777511 0.4061934 0.7079623 -0.2618568 0.7067816 0.6571841 0.6566798 0.2450465 0.7132489 0.1028269 -0.4797394 -0.871365 -0.09766048 -0.7057483 0.7016993 -0.654219 -0.2433824 0.7160744 -0.6486362 -0.23958 0.7224075 -0.5274226 0.3801773 0.7597965 -0.583203 0.3905886 0.7122603 -0.2638796 0.7079745 0.6550875 -0.1830406 0.5403085 0.8213179 0.1855276 0.6823084 0.7071315 0.5835574 -0.3896363 0.7124916 0.2681729 -0.7164123 0.6440782 -0.1407347 -0.7142567 0.6855882 -0.1432455 -0.6986646 0.7009626 -0.6567256 -0.2445733 0.7133691 -0.6487568 -0.2391858 0.7224299 -0.2618454 0.7067639 0.6572077 0.1852952 0.6814588 0.7080111 0.1861776 0.6759784 0.7130156 0.6542146 0.2436721 0.71598 0.5835165 -0.3896307 0.7125282 0.2456809 -0.6267383 0.7394863 -0.1461403 -0.7086068 0.6903039 -0.6542522 -0.2433446 0.7160569 -0.6451639 -0.237155 0.7263065 0.1623545 0.7401206 0.6525814 0.6569631 0.2448627 0.713051 0.6438929 0.2360424 0.7277953 0.5223309 -0.4411195 0.7297835 0.2415956 -0.6510661 0.7195447 -0.1592196 -0.779495 0.6058356 0.6542242 0.2433732 0.7160728 0.583508 -0.3896424 0.7125289 -0.1432629 -0.6986309 0.7009925 -0.6435137 -0.2356067 0.7282716 -0.6487364 -0.2391221 0.7224692 -0.5191722 0.4288408 0.7392941 -0.6259992 0.4607992 0.6291179 0.9369033 0.3425218 0.06993573 0.2244344 0.9738349 0.03570705 0.2446695 0.968589 0.04440873 -0.5176884 -0.8507387 0.090788 -0.5272885 -0.8448721 0.09032213 -0.768327 0.637416 0.05809092 0.2115394 0.9755423 0.05973744 -0.7941198 0.5981081 0.107891 -0.2440308 -0.9641976 0.103789 0.5739867 0.8161337 0.06682091 0.4646862 0.8837957 0.05451601 -0.7495645 0.6495552 0.1274015 -0.3958736 0.9168565 0.05156016 -0.9575078 -0.2851675 0.04311066 -0.9581531 -0.2823237 0.04728674 -0.1649171 -0.9788252 0.1212583 0.8134031 -0.5801386 0.04259824 -0.1977568 -0.9785777 0.05725324 -0.1757114 -0.9825373 0.06120556 -0.9429478 -0.3294955 0.04777282 0.02445405 0.9971478 0.07140243 0.3932008 -0.9181887 0.04819518 0.9544713 0.2947281 0.0460444 -0.9387063 -0.3416812 0.04565685 0.7706441 -0.6362501 0.03596377 0.9430868 0.3307341 0.03467345 -0.9387136 -0.3416632 0.04564106 -0.4716628 0.8709308 0.1378904 0.2651724 -0.9634304 0.03854268 0.9491201 0.3116363 0.04531937 -0.2166005 -0.9752039 0.04540652 -0.5055772 0.8618187 0.04074704 0.524511 0.8466717 0.089639 0.6515648 0.7552475 0.07116514 0.9387122 0.3416572 0.04571545 -0.7784321 0.6266378 0.03699517 0.9387089 0.3416746 0.04565274 -0.7984405 0.5996823 0.053608 0.2677254 0.9624661 0.04452037 0.7679628 -0.6390704 0.04268896 0.545104 0.8267601 -0.1390303 -0.9230084 0.3719574 -0.09850597 -0.7104002 -0.7021571 -0.04803037 -0.122707 -0.9893081 -0.07882082 0.9863107 0.143337 -0.08152073 0.973815 -0.2163599 0.06980651 0.01745772 -0.9975512 0.06772589 -0.5899094 -0.8051275 0.06145507 -0.8657025 -0.499817 0.02724343 -0.9845601 -0.1736033 0.02243483 -0.9706701 0.2378955 0.03472054 0.02627867 0.9875295 0.1552255 -0.2305941 -0.6865869 0.6895105 -0.02067941 -0.4049717 0.9140954 -0.4312133 -0.6197993 0.6556707 -0.3982275 -0.2017954 0.8948148 -0.4240025 0.01716023 0.9054985 -0.04107624 0.2476775 0.9679714 -0.0769639 0.442866 0.8932785 0.4561227 -0.02368342 0.8896017 0.3318338 -0.05964928 0.9414502 0.3577796 -0.1049706 0.9278873 -0.215076 -0.8724274 0.4388769 -0.5165812 -0.3551002 0.7791328 -0.4779254 0.1492705 0.8656244 -0.1630315 0.6446325 0.7469068 0.8403934 0.2467361 0.4825558 0.6381146 0.1866953 0.7469637 0.09211957 -0.09305387 0.9913904 -0.1492622 0.6519669 0.7434111 -6.30233e-7 0 -1 5.14772e-7 0 -1 5.53577e-7 0 -1 1.34608e-6 -1.00117e-6 -1 2.54598e-6 -5.6931e-7 -1 -1.07408e-5 -3.44096e-6 -1 3.43371e-6 0 -1 8.54604e-6 0 -1 -1.79392e-6 -4.36105e-6 -1 -0.8617936 -0.507259 0 -0.8690471 -0.4945057 -0.01487892 -0.005779445 0.9998443 0.01668238 -0.7420421 -0.4253502 0.5181224 -0.55312 -0.8322384 0.03791457 0.9171345 -0.3980708 0.02010285 0.09033489 0.9491609 0.3015514 0.7241022 0.5696182 -0.3888589 0.1435093 0.8692583 0.4730698 -0.9018014 0.3368871 -0.2706684 -0.130218 -0.970274 -0.2039893 -0.3194509 0.9476028 0 -0.3194507 -0.9476029 0 -0.319451 0.9476028 0 -0.319451 -0.9476028 0 0.308776 0.9511349 0 0.3087762 -0.9511348 0 0.308775 -0.9511351 0 0.308776 -0.9511349 0 0.8098693 -0.09352606 0.5791068 -0.35952 -0.6795305 -0.6395184 0.6881947 0.7255261 0 -0.9830662 -0.1814658 -0.02552092 -0.155726 -0.9278203 -0.3389676 -0.9284279 0.2121431 -0.3049868 -0.4983753 -0.3830791 -0.7777355 0.764203 -0.5738083 0.2945133 0.04205214 0.9972838 0.06047147 0.5206661 0.8537605 0 -0.1953267 -0.9789164 -0.05975145 -0.2146025 0.9767004 0.001433849 -0.1010698 0.9930777 0.05984663 0.7452749 0.5811259 0.3268917 -0.04667395 0.1268442 0.9908239 9.01801e-4 -0.003363072 0.999994 -0.001230597 -0.005567371 0.9999839 0 0 1 0 0 1 0 0 1 -9.05403e-6 -3.5016e-5 1 1.08427e-5 3.80683e-5 1 5.06222e-4 0.001799881 0.9999983 -0.1005724 -0.05445975 0.9934382 6.39097e-4 -5.51583e-4 0.9999997 0.03618532 -0.09002912 0.9952816 -0.01499223 -0.008951365 0.9998476 0.09604138 -0.06390196 0.9933241 -4.36928e-4 -4.86583e-4 0.9999999 -0.001991331 0.02967697 0.9995576 -0.005142807 0.0380454 0.9992629 0.009237945 -0.006049156 0.999939 -2.01713e-5 -3.98297e-4 1 0.006973683 0.0222761 0.9997276 -0.002482056 -0.0107792 0.9999389 0.03766191 0.1591216 0.9865404 -0.001871943 0.005665063 0.9999823 -3.78023e-4 -3.78242e-4 0.9999999 0.03369677 -0.1156905 0.9927136 -0.005660235 -4.11211e-4 0.9999839 -3.868e-4 -0.01815062 0.9998353 -0.001476109 0.002845644 0.9999949 -0.02970141 0.05726397 0.9979172 5.67206e-4 0.003876864 0.9999923 -0.1095758 0.3807231 0.9181739 0.003548622 -0.001994013 0.9999918 -8.54807e-5 -0.003313481 0.9999945 2.77761e-4 -8.82235e-5 1 0 0 1 -2.36662e-5 5.8161e-5 1 3.56824e-6 6.55134e-7 1 -2.03048e-5 -6.76978e-5 1 0.06054913 -0.02388536 0.9978795 0 0 1 1.29415e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.02103823 -0.1849651 0.98252 -8.55572e-4 0.001518249 0.9999985 -0.007214605 0.001721739 0.9999726 -0.004411578 -0.003848552 0.999983 -0.005474805 -0.01466786 0.9998775 0.03944754 0.02459269 0.998919 0 0 1 0 0 1 0.002075195 5.93358e-5 0.9999979 -1.55477e-5 -5.34324e-5 1 -0.003233432 0.01144367 0.9999293 -0.00819534 0.008364558 0.9999315 -0.002076625 4.58054e-4 0.9999977 -2.58999e-7 0 1 0 0 1 7.72539e-4 -0.006023824 0.9999817 0 0 1 0.0837112 -0.0575093 0.9948292 0.005858659 -0.09722608 0.9952452 0 0 1 0.00718373 -0.007252812 0.999948 0.01706433 0.04068559 0.9990263 0.009981691 0.006315231 0.9999303 -0.001185238 4.04703e-5 0.9999994 -8.59082e-5 -4.90195e-5 1 -1.99387e-6 0 1 -1.80505e-7 0 1 -5.41957e-4 0.008600473 0.9999629 -1.59426e-5 -2.76244e-5 1 7.00915e-7 6.90925e-6 1 2.92485e-5 5.57381e-5 1 0.03347837 0.06300538 0.9974516 -0.01591289 0.1928948 0.9810904 0.0435332 0.08615714 0.99533 0.1074714 -0.2099428 0.9717891 -2.57835e-7 0 1 -0.07777512 0.1495619 0.9856888 -0.01128005 0.01317751 0.9998496 -0.005847394 -0.02315187 0.999715 2.20678e-5 -1.42677e-5 1 -0.001322209 -0.007941722 0.9999676 -0.004580318 -5.48682e-4 0.9999893 -0.07415378 -0.04700213 0.9961386 7.81871e-4 0.01145118 0.9999341 1.56243e-4 -1.17391e-4 1 -1.16101e-4 -0.002186298 0.9999976 0.02209705 0.02230817 0.999507 -9.78762e-6 5.39372e-5 1 -0.1168954 0.001667857 0.9931429 0.01702201 0.04701751 0.9987491 -9.69558e-7 -1.50151e-5 1 0 0 1 0.02615934 0.1770284 0.9838581 -1.44732e-6 -1.92894e-5 1 0.02326589 0.0333963 0.9991714 0.008570194 0.02775198 0.9995781 -0.01635265 -0.04498571 0.9988538 -0.002294719 0.006710112 0.9999749 -0.001059412 -0.003953158 0.9999917 0.001026093 -6.04779e-4 0.9999993 -6.75842e-4 5.11978e-5 0.9999998 -7.25819e-4 -6.78934e-4 0.9999995 -5.60722e-6 1.9416e-5 1 8.41983e-6 8.00896e-6 1 0 0 1 0 0 1 -0.03758937 0.08289992 0.9958487 -3.7075e-6 -1.64677e-5 1 -4.85077e-7 0 -1 8.99147e-5 1.56833e-5 -1 -2.27587e-6 -6.66604e-6 -1 -2.32038e-4 -4.76896e-4 -0.9999999 1.07508e-4 1.38348e-4 -1 -2.48848e-7 0 -1 5.30029e-7 0 -1 -2.13521e-6 3.80825e-6 -1 0 0 -1 0 0 -1 -4.59731e-7 0 -1 9.13343e-5 -1.58901e-4 -1 -7.91568e-5 -4.7482e-4 -0.9999999 5.49195e-7 3.53694e-7 -1 -5.00115e-7 8.36803e-7 -1 0 1.19127e-6 -1 1.11766e-5 6.43821e-6 -1 -7.46147e-5 -6.61619e-5 -1 1.08087e-6 -2.94222e-6 -1 -7.76191e-5 3.64957e-5 -1 5.03301e-5 -1.759e-6 -1 -3.35272e-6 4.27879e-5 -1 1.39998e-7 0 -1 -1.3463e-6 2.42574e-6 -1 -7.70873e-7 1.63082e-7 -1 2.63951e-6 -7.74949e-6 -1 1.22423e-6 -1.17037e-6 -1 -9.09581e-6 -7.57144e-6 -1 0 0 -1 -4.26633e-7 0 -1 -1.42336e-5 -5.50335e-4 -1 0 0 -1 -5.57932e-6 -2.60178e-5 -1 3.65098e-6 1.0314e-5 -1 -4.61355e-7 -1.68635e-5 -1 1.94536e-5 3.20226e-5 -1 7.08863e-7 1.22347e-5 -1 0 0 -1 -7.4996e-7 -8.90171e-6 -1 1.70847e-5 -8.19205e-6 -1 0 0 -1 0 0 -1 7.23022e-5 -8.50045e-5 -1 -3.69753e-4 5.62343e-4 -0.9999998 -0.009330272 -0.004805326 -0.9999449 -0.02270364 0.04661905 -0.9986547 -0.03164881 -0.07590109 -0.996613 -5.98921e-4 0.02461451 -0.9996969 0.008048593 -0.002238392 -0.9999651 9.22202e-4 -0.00398308 -0.9999917 0 0 -1 0 -1.37792e-6 -1 -1.03481e-5 -6.17913e-5 -1 3.91931e-7 1.84759e-7 -1 5.6817e-7 -2.8444e-7 -1 6.154e-6 4.25863e-5 -1 0 0 -1 -1.56801e-7 0 -1 -9.15664e-7 2.34027e-7 -1 2.38419e-5 1.61214e-4 -1 -3.50614e-4 -1.30511e-4 -1 1.27481e-7 0 -1 -7.63379e-6 2.16774e-5 -1 6.41288e-5 -9.11493e-5 -1 1.83112e-7 1.24408e-7 -1 0 1.41632e-7 -1 0 3.24806e-7 -1 0 0 -1 0 0 -1 -4.66996e-7 3.79689e-7 -1 -1.47219e-6 0 -1 -1.23531e-5 -2.23409e-5 -1 1.19814e-6 1.87968e-6 -1 0 0 -1 0 0 -1 -1.32648e-7 0 -1 0 0 -1 0 0 -1 -1.8786e-6 -1.21138e-5 -1 3.50661e-6 6.59157e-6 -1 0 0 -1 -1.13121e-6 1.05968e-6 -1 1.09096e-5 2.19078e-5 -1 9.96398e-5 1.72692e-4 -1 4.15318e-4 -6.73626e-4 -0.9999997 -1.7288e-4 8.26005e-4 -0.9999997 1.85608e-6 -9.84377e-6 -1 7.82294e-5 -1.46617e-5 -1 -3.17211e-6 1.42273e-5 -1 0.01851701 -0.04698711 -0.9987239 -2.94897e-6 5.22249e-6 -1 -5.41087e-6 2.44572e-6 -1 1.03913e-5 -2.80129e-5 -1 0 0 -1 -6.66339e-6 -7.98893e-6 -1 -7.25765e-6 -1.24509e-5 -1 -4.72268e-6 -1.8425e-5 -1 0 0 -1 0 0 -1 2.82736e-6 -6.27381e-6 -1 2.94806e-7 0 -1 -2.35062e-6 -1.46371e-5 -1 5.27683e-6 -6.60194e-5 -1 1.33032e-5 -4.32955e-5 -1 6.40049e-6 -1.79055e-5 -1 -7.08797e-7 3.42784e-6 -1 4.15361e-6 8.89701e-6 -1 -6.83605e-6 1.93118e-5 -1 4.65105e-5 5.19975e-5 -1 -3.28476e-5 -4.0055e-5 -1 1.69921e-5 -9.90596e-6 -1 -0.07912701 0.2303134 -0.9698942 -7.29342e-6 8.5251e-6 -1 -9.85277e-6 -1.06685e-5 -1 1.80505e-7 0 -1 1.64724e-6 1.13684e-5 -1 -2.7723e-5 -1.29515e-4 -1 -1.04492e-4 1.83329e-4 -1 -5.32701e-7 0 -1 2.53359e-4 3.71613e-6 -1 -0.6865436 -0.4381802 0.5802208 -0.4407373 0.7564917 0.4831883 0.8202369 0.4539798 0.348014 -0.4238958 -0.9051128 -0.03291457 -0.08349794 0.9746255 -0.2076861 0.9583872 0.2840809 -0.02814346 0.6377046 -0.7215687 0.2695767 4.45296e-7 -1 0 4.45294e-7 -1 0 0.401964 -0.8838051 -0.2394023 -0.6662379 -0.6662227 0.3350738 -0.9997408 0.0227707 0 -0.6046819 0.6624032 -0.4422465 -0.3224804 0.9240747 0.2051641 0.01656979 -0.7261381 -0.6873493 -0.8788097 -0.4771726 0 -0.9366571 0.1479377 -0.3174712 -0.5256649 0.6385408 -0.5620874 -0.2265573 -0.8005831 0.5547418 0.9996076 0 -0.02801603 0.08086365 0.264566 0.9609713 0.3334528 0.4646344 -0.8203195 -0.9990308 0 0.04401564 -0.9999558 0.009408771 0 -1.43716e-4 1 0 -0.3203348 -0.9473045 0 -0.320337 -0.9473037 2.27145e-4 0.5932024 0.5246706 0.6105995 0.5618439 0.2799427 0.7784367 -0.7920128 -0.5567019 0.250597 0.8524621 -0.3994401 -0.3372775 -0.3232161 -0.8899267 0.3218101 0.9999822 0 -0.005960643 -4.45294e-7 1 0 -0.5632322 -0.616991 -0.5496286 -0.8966506 -0.02042263 -0.4422677 -0.9281764 0.3721408 0 0.7385908 0.6741541 -4.02894e-6 0.8917353 0.4525575 0 -0.5791659 -0.6700878 -0.4642728 -0.7749864 0.484842 -0.4053696 -0.3284056 0.9377306 0.1131865 0.861009 -0.2631936 0.435193 0.7959042 -0.5711189 -0.2008975 0.5354347 -0.7460568 -0.3958649 0.2839596 -0.9290457 0.2371518 0.03089827 -0.993115 0.1129959 -0.9878571 -0.03113329 0.1522138 -0.7365003 0.6208289 -0.2685867 -0.7531337 0.6060666 -0.2558772 -0.5136031 0.8523226 0.09878337 -0.3203339 0.9473047 0 -0.05350321 -0.04536527 0.9975367 0.9070739 -0.4209715 0 -0.7071086 0.7071051 0 0.9070739 0.4209715 0 0.4209713 -0.9070741 0 -0.3777702 -0.9244812 -0.05122917 0.6320261 0.6306662 0.4503368 0.950634 0.1992534 -0.2378936 0.7682202 -0.6383253 -0.04877132 -0.3944097 -0.9006187 0.1825566 -0.9713466 0.007681488 0.2375436 -0.2683386 0.8726011 0.4081196 0.6426693 -0.71751 0.2686181 -0.9750596 -0.1992672 -0.0977317 -0.6597461 0.7426005 -0.1152378 0.7268451 -0.6628129 0.1799314 -0.1989581 -0.9077844 -0.369247 -0.7203892 0.6568858 0.2225769 -0.3330405 -0.9376645 -0.09934443 -0.927362 0.2157596 -0.3056918 0.3608698 0.8961373 0.2582846 0.9526035 -0.257226 0.1624242 0.7396275 -0.6575506 -0.1434514 -0.0534715 -0.9818544 0.1819423 -0.7071032 -0.7071104 -1.30213e-6 -0.9758731 -0.1455789 0.1627225 -0.7610158 0.6487002 -0.006558716 -0.1568049 0.9872085 -0.02883899 0.9380826 0.3460429 -0.01598328 -0.6594982 0.7415134 0.1233693 0.9567819 -0.2563707 0.1372681 0.5204032 -0.8514524 -0.06488084 -0.9760487 -0.2163937 -0.02242338 -0.8592111 0.4932749 -0.1357796 -0.2588118 0.9659277 0 0.2563685 0.956782 0.1372716 0.9567815 0.2563717 0.1372686 -0.8253322 -0.5276238 0.2010969 -0.7526361 0.6479161 0.117234 0.0324819 0.9984342 -0.04554241 0.3081749 -0.9454772 -0.1053628 -0.969308 -0.2212591 -0.1071761 -0.8218273 0.5696725 0.008557558 0.95526 0.02920776 0.2943215 -0.1118617 -0.9918472 0.06104332 -0.06828087 0.9284594 0.3651039 -0.1168797 -0.9908258 0.06784987 -0.5203947 -0.8514571 -0.06488597 -0.4879978 0.8699749 -0.07072401 0.9429908 0.3327819 -0.004963219 0.9769378 0.1781136 0.1177636 0.7071042 -0.7071094 0 -0.4538398 -0.8374683 0.3044279 0.9659219 -0.2588336 0 -0.7004241 -0.7004035 0.1372635 -0.9636143 -0.2582048 0.06912243 0.2819215 0.8920213 0.3532966 0.9340184 0.3561025 0.02829533 0.9787292 -0.1143848 -0.1703098 0.1267923 0.986589 0.1027908 -0.5159584 -0.8520671 -0.08813935 0.2563687 -0.9567823 0.1372689 -0.5750615 -0.8181102 0 -0.9928874 -0.1190265 -0.002709209 -0.6267781 0.7734619 -0.09437149 0.1051206 0.9915105 -0.07652807 0.5203835 -0.8514644 -0.0648806 -0.4771919 -0.8764007 -0.06488358 -0.5223132 -0.8512765 -0.05017191 -0.5489434 0.8358045 0.009590685 0.9443632 0.3269273 0.03601306 0.4734683 -0.8200613 0.3214458 -0.9567814 0.256372 0.1372697 -0.04173344 0.9550012 0.2936509 0.7589048 -0.6468868 0.07484108 -0.9983839 0.02670019 -0.05016845 -0.5203945 0.8514579 -0.0648781 -0.476066 0.8779771 -0.05017232 0.7709874 0.5961118 0.2241188 0.7718273 0.5939055 0.2270662 0.4068584 -0.9014564 0.147793 -0.8200664 -0.4734652 0.3214372 0.6924949 -0.66713 -0.2745698 0.002223193 -0.9973917 -0.07214659 0.2563644 0.9567835 0.1372691 0.7071107 0.7071029 0 0.9567849 0.2563609 0.1372658 0.1453175 -0.9822816 -0.118346 -0.9747459 0.1844454 -0.1258984 0.02670472 0.9983838 -0.05016618 0.868623 -0.4830669 -0.1101842 -0.8498361 0.5099289 -0.1332333 -0.02494889 0.9975815 -0.06487601 0.7473539 0.6586487 -0.08743125 0.6042342 -0.7639703 0.2263853 -0.764267 -0.4504358 0.4615231 -0.2496939 0.862712 0.4397512 0.9362035 -0.2840401 -0.2069883 -0.9941296 0.07124602 -0.08142769 0.4746116 0.8541151 0.2126764 0.8106681 -0.4802093 -0.3349874 -0.9284347 -0.3367979 0.1567684 -0.705927 0.7059258 0.05775737 0.9762412 -0.08738589 -0.1982845 0.4462919 -0.7779222 0.4423355 -0.2156115 -0.9764487 -0.007723748 0.2563699 0.9567816 0.1372724 0.9567809 0.2563725 0.1372714 0.7250073 -0.6821904 -0.09476691 -0.1844495 -0.9747458 -0.1258935 -0.925971 -0.3592758 0.1161842 -0.01013016 0.9967719 -0.0796436 -0.9975857 0.01144659 -0.0684973 0.08896273 0.996035 0 0.965928 0.2588109 6.51064e-7 0.972054 -0.234728 0.003729701 -0.7563375 -0.6431862 0.1194375 -0.7300928 0.6672179 0.1475969 0.9141088 -0.3704867 0.1647569 -0.258805 -0.9659296 0 -0.7779063 -0.6063962 0.1647589 -0.9752072 0.1822115 -0.1255792 0.6447137 0.7609842 0.07243925 -0.1265414 -0.9836629 -0.1280418 -0.9600872 0.06052213 0.2730743 -0.2585596 0.9649666 0.04456967 0.9983341 -0.04630887 -0.03441876 -0.7417286 0.6705551 -0.01395541 -0.149048 0.975475 0.1619671 0.4178776 -0.9004017 -0.1210592 -0.9737629 0.2188315 -0.06243944 0.9467635 -0.2651751 0.1825406 0.3300522 -0.9429924 -0.04279184 -0.705793 -0.7058075 -0.0607621 -0.9958887 -0.02218449 -0.0878269 -0.36585 -0.4661157 -0.8055371 0.005329728 -0.9999858 0 -0.3435527 -0.8485344 -0.4024439 0.3525744 -0.8448311 -0.4024323 0.844816 -0.3525962 -0.402445 -0.3553573 -0.9347306 0 -0.4090387 -0.9041662 -0.1231698 -0.458579 -0.8886536 0 -0.4999994 -0.8660258 0 0.5449496 -0.8384689 0 0.1311578 -0.9898536 0.05465739 0.07922738 -0.9893894 0.1217857 0.06231909 -0.9889675 -0.1343865 -0.01253777 -0.9917826 0.1273195 -0.08304446 -0.9584651 -0.2728521 -0.124172 -0.9797109 0.157315 -0.144787 -0.9894629 0 -0.6822026 -0.7311603 -0.002057731 -0.6795766 -0.7333416 0.0196411 0.3420166 -0.9396935 -8.89534e-4 0.3420318 -0.9396885 0 0.999831 0.01838803 0 0.9852178 0 0.1713069 0.9688166 -0.2477793 0 0.982419 -0.1866896 0 0.9980416 -0.06255477 0 0.9921734 0.1248686 0 0.9824191 0.1866893 0 0.9688164 0.24778 0 0.9688165 0.2477796 0 -0.9186921 0.3949747 0 -0.525349 0.5366784 -0.6602914 0.005327045 0.9999858 -8.74037e-6 0.3525732 0.8448284 -0.4024391 0.6984641 0.6984861 -0.1557729 0.8037375 0.3354506 0.491405 0.6089028 -0.5960389 -0.5234263 -0.5013592 0.6387739 -0.5836155 0.3856404 -0.8969495 0.2162478 0.3420299 0.9396887 -9.25979e-4 -0.6734193 0.739059 0.01726871 -0.2583032 0.9339395 -0.2470557 -0.1581071 0.9403359 -0.3012818 -0.06726306 0.9770088 -0.2023109 -0.07467544 0.9934548 -0.08643704 0.07577663 0.9721294 0.2218614 0.1612682 0.9686245 -0.1891006 0.1695367 0.9837452 -0.05918461 0.2185129 0.9757558 0.01236301 0.5439385 0.8390944 0.007202565 -0.5 0.8660254 0 -0.5000044 0.866023 1.90669e-4 -0.4501304 0.8923822 0.03220123 0.9995301 -0.03065341 0 0.9957733 0.09184575 0 0.9770603 0.2129628 0 0.9957732 0.0918473 0 0.9882742 0.1526895 0 0.6777642 -0.6968734 0.2345276 0.8910285 -0.4458427 -0.08539688 0.9057646 -0.4237813 0 0.6604546 -0.7490491 0.05220437 -0.6820595 -0.7312961 9.42189e-4 -0.2721579 -0.9588111 0.08131003 -0.2824968 -0.9588899 -0.02694195 -0.19764 -0.9715359 0.1306009 -0.217101 -0.9743295 0.05957585 -0.1138806 -0.992683 -0.04014706 -0.06071138 -0.9981042 0.01011306 -0.007528543 -0.9940585 -0.1085867 0.114755 -0.9833772 0.1407151 0.1873838 -0.9778138 -0.09363543 0.2277642 -0.9737051 -0.004677474 -0.4992426 -0.864866 -0.05257093 -0.458221 0.8870545 -0.0562852 0.5386421 0.8422248 -0.02285051 0.5441035 0.8371856 -0.05542451 0.2165768 0.9762589 -0.003610491 0.2182754 0.975436 -0.0296759 0.1568775 0.9866214 0.04435819 0.1547139 0.9859461 0.06303972 0.1095963 0.9936116 -0.0269196 0.0469734 0.9882096 0.1457237 0.009806871 0.9994966 -0.03017318 -0.04688346 0.9965966 0.06780308 -0.06150597 0.9807829 0.1851535 -0.2692692 0.9629677 -0.01368761 0.9037873 0.4053819 -0.1372372 0.6197654 0.7645868 -0.176913 0.415585 0.9094155 0.015895 0.4210402 0.907042 0 -0.4779969 -0.3130937 0.8206652 0.001216709 -8.73306e-4 0.9999989 9.65736e-4 -0.001345932 0.9999986 5.70158e-4 1.98932e-4 0.9999999 1.32428e-4 2.90689e-4 1 0 -0.001531183 0.9999989 -5.97309e-4 0.004786729 0.9999884 -0.006434977 0.001908004 0.9999775 6.71038e-4 0.00148493 0.9999987 -1.81988e-4 7.0971e-5 1 -1.33463e-4 -5.32541e-4 0.9999999 -1.46789e-7 0 1 4.40884e-5 -1.53429e-4 1 -1.45701e-5 9.13138e-6 1 1.04658e-4 -0.001218914 0.9999993 1.95484e-4 3.29563e-5 1 3.62062e-5 -0.001944243 0.9999982 -6.83999e-4 0.001006126 0.9999994 0.008594214 0.003038704 0.9999585 -2.92816e-4 -4.82378e-4 0.9999999 -3.01803e-4 -4.58485e-4 0.9999999 -8.82783e-4 -3.22634e-4 0.9999996 0 1.61432e-4 1 -7.85663e-5 -2.3626e-4 1 1.19306e-4 -2.77018e-4 1 6.72825e-4 -2.72306e-4 0.9999998 5.92475e-4 2.47207e-4 0.9999999 5.77499e-4 1.73575e-4 0.9999999 -1.06551e-6 0 1 5.33074e-7 0 1 0.001538038 6.60264e-4 0.9999986 0 0 1 4.90662e-5 1.43864e-5 1 7.05152e-6 -0.00124073 0.9999992 5.25692e-4 -0.001260936 0.9999992 -5.88116e-7 0 1 -5.88302e-7 0 1 5.88392e-7 0 1 -8.82454e-7 0 1 -2.94058e-7 0 1 -0.001678824 -7.21935e-4 0.9999983 -0.001200079 -0.001225829 0.9999986 -1.67451e-4 -0.001371681 0.9999991 4.49874e-4 -2.40453e-6 1 1.21193e-4 2.81644e-4 1 -1.66843e-5 -2.60596e-4 1 -2.41958e-5 1.6001e-4 1 0 2.31015e-7 1 1.57203e-5 -1.56802e-5 1 -4.57123e-4 0.003224611 0.9999948 3.29254e-4 -5.96757e-4 0.9999998 2.40327e-4 0.003842532 0.9999926 -2.90465e-5 5.28276e-5 1 3.75661e-4 -0.001606881 0.9999986 9.85494e-6 1.98441e-5 1 -3.43375e-6 -1.20134e-5 1 5.74827e-4 -2.00649e-4 0.9999998 5.69981e-4 0 0.9999999 -0.03827524 -0.004114449 0.9992588 -0.9989323 -0.01465946 -0.04381418 -0.6069608 -0.6038991 0.5166282 0 -0.9999992 0.001246333 0.9565014 0.2883978 -0.04395145 0.7392686 0.3624912 0.567523 0.3214726 0.7887229 0.5239958 0.419255 0.8969751 0.1402184 0.9127297 -0.3270151 -0.2449195 0 0.999858 0.01685237 0.001938045 0.9999981 0 -0.9890812 0.01706343 0.1463812 -1 -1.05484e-5 0 0.3421652 -0.9396399 0 0.3575264 -0.9254152 0.1256256 0.5326517 -0.3319013 0.7785394 0 -2.90257e-7 1 8.4284e-4 6.4169e-4 0.9999995 -0.01654893 -0.02959537 0.9994249 8.1492e-5 0.0550884 0.9984816 -3.72829e-4 0.02721554 0.9996296 -2.26045e-7 0 1 1.29644e-6 0 1 -2.45983e-7 0 1 0.02052342 -0.05244666 0.9984129 -1.03388e-4 4.30579e-4 1 2.47358e-4 -2.08652e-4 1 4.81417e-7 -2.40419e-4 1 7.55967e-4 -0.007054865 0.9999749 -0.01643902 0.009571492 0.9998191 -0.01551944 0.04686301 0.9987809 0.003688156 -0.01264154 0.9999134 -0.006354928 -0.001654803 0.9999784 -8.83575e-4 9.7425e-4 0.9999992 -9.48056e-4 0.00161302 0.9999983 -6.34869e-4 -0.001175045 0.9999992 0.02917641 0.08699607 0.9957814 -1.48475e-5 -0.04413795 0.9990255 1.58079e-7 0 1 6.45825e-5 7.77736e-7 1 -4.43272e-5 6.0864e-5 1 -5.59473e-4 -2.09015e-5 1 -0.0153374 -0.0252465 0.9995636 0.02516722 0.03248858 0.9991552 2.42588e-5 0.01657992 0.9998626 -0.006158828 8.80837e-4 0.9999806 0.003108084 -0.1905819 0.9816665 2.57035e-4 0.01180243 0.9999303 -3.35982e-4 0.008182942 0.9999666 2.02524e-4 0.01066166 0.9999432 -0.005723714 9.95717e-4 0.9999831 -0.07164883 0.08410358 0.9938778 0.06382709 -0.06628197 0.9957575 5.32577e-6 0 1 -1.1221e-6 0 1 0 0 1 -6.92751e-7 0 1 0 0 1 4.95978e-4 0.00421226 0.9999911 -7.69047e-7 0 1 2.83281e-7 0 1 0 0 1 0 0 1 0 0 1 -3.23053e-7 0 1 -4.54534e-7 0 1 0 -1.97054e-7 1 3.48716e-6 1.75591e-5 1 -7.76741e-6 4.54092e-7 1 1.90899e-6 0 1 -2.17971e-6 -3.94491e-6 1 -2.60442e-7 0 1 7.23736e-6 -7.1572e-6 1 1.00182e-4 0.006171941 0.9999811 -1.63084e-7 0 1 -1.39798e-7 0 1 0 -1.5772e-6 1 -2.30568e-4 -0.00309056 0.9999952 -7.81228e-4 -0.002343714 0.999997 0.004448592 -0.001068472 0.9999896 3.2069e-7 0 1 8.24884e-5 -9.04533e-5 1 1.14278e-5 1.35078e-4 1 -9.27033e-7 2.9687e-7 1 -0.02179372 0.001321613 0.9997617 -0.01634562 -0.02030277 0.9996603 -3.03594e-4 -0.02215898 0.9997544 -0.02128386 0.0318551 0.9992659 0.8330217 -0.5519403 -0.03790658 0.4356347 -0.8982653 0.05781084 0.402828 -0.9139948 -0.04840767 0.8177664 0.57503 0.0244683 0.8304077 0.5565689 -0.0255779 0.3339391 0.9404522 -0.06351828 0.1151461 -0.9933054 0.009271264 0.3420208 -0.9396905 0.001891911 0.341888 -0.9397408 -1.2437e-4 0.09917366 0.9942351 -0.04075813 0.1387497 0.9842743 0.109328 0.342012 0.9396956 -2.9138e-4 0.3419996 0.9397001 -9.65956e-5 0.9772348 -0.2105399 -0.02617406 0.9736145 -0.1635715 -0.1591205 0.9852069 -0.1713695 0 0.9924956 -0.1222811 0 0.9930636 -0.1025483 -0.05751925 0.9975923 -0.0667501 0.01881581 0.9991935 -0.0373122 -0.01484137 0.9994457 -0.03329491 0 0.9754693 0.1546466 -0.1566658 0.9775415 0.2106077 -0.00755465 0.9938758 0.1099661 -0.01088607 0.9747521 0.2169039 0.05301922 0.9934738 0.1090545 0.03342199 -0.2408432 -0.9386667 0.2467784 -0.9216656 0.3072887 -0.2368677 -0.4579566 0.8872396 0.0555132 0.4520548 0.8914718 0.03040462 0.298747 -0.8770073 -0.3763092 -0.4868371 0.8658077 0.1156141 0.8617167 -0.4876304 -0.1402179 -0.6011654 0.7968768 -0.0598967 0.9047826 -0.4257112 -0.01176744 0.6715451 0.7375938 0.07058751 0.9994863 0.02182155 0.02347296 0.9997583 0.01886975 0.01127976 -0.2632293 0.9643865 -0.02586579 1.09299e-4 1 0 0.1950914 -0.9807851 0 0.8637587 -0.5029144 -0.03159242 4.32125e-7 -1 0 4.32125e-7 -1 0 0.7592168 -0.6438266 0.09527564 -0.7623381 -0.6428502 -0.07472771 -1.93902e-5 -2.83909e-5 -1 5.42702e-4 8.741e-4 0.9999995 1.35486e-7 0 -1 0 0 -1 8.15488e-6 0 -1 -6.91084e-7 -5.48806e-7 -1 0 -6.88777e-7 -1 9.45349e-6 -9.05714e-6 -1 -9.19978e-4 4.03705e-4 -0.9999996 1.07351e-4 1.97312e-4 -1 5.07263e-4 -8.98686e-4 -0.9999995 3.1412e-5 3.3529e-5 -1 -9.79645e-5 -2.20695e-4 -1 2.09423e-7 0 -1 0 0 -1 0 0 -1 -4.43026e-4 4.19984e-4 -0.9999999 -2.02098e-4 2.42824e-6 -1 7.77632e-4 0.002226829 -0.9999973 6.73086e-4 8.07655e-6 -0.9999998 -4.79671e-4 -0.002484977 -0.9999969 -3.07311e-7 0 -1 5.60782e-7 0 -1 2.29512e-7 1.4654e-6 -1 1.25259e-5 1.86303e-5 -1 -2.70014e-4 -5.47469e-5 -1 2.11005e-4 3.11663e-4 -1 0.00119841 7.44664e-4 0.9999991 -1.52719e-5 3.794e-5 -1 4.52646e-5 1.73815e-4 -1 4.24931e-7 0 -1 0 0 -1 -2.3168e-6 0 -1 -2.15932e-5 4.6279e-5 -1 -1.98254e-5 3.35611e-5 -1 -0.0214141 2.47306e-4 -0.9997707 0.02032345 0.023844 -0.9995092 -6.27597e-6 -2.11963e-7 -1 -2.59804e-7 0 -1 1.26166e-4 -7.21766e-6 -1 4.94891e-7 2.63095e-5 -1 3.95288e-5 0.002161026 -0.9999977 2.01029e-4 -0.001476943 -0.9999989 8.11693e-5 6.84669e-5 -1 -2.52117e-4 3.80592e-4 -1 1.77118e-4 -1.3032e-4 -1 1.48844e-4 -1.78715e-6 -1 2.2936e-4 8.37585e-5 -1 1.54231e-4 -1.17335e-4 -1 -1.75027e-5 -2.02584e-4 -1 0 -1.73234e-4 -1 -7.13752e-4 -1.55929e-5 -0.9999998 -7.95528e-6 -8.26043e-6 -1 -2.18104e-6 0 -1 -7.49847e-7 0 -1 -4.23531e-7 0 -1 8.31768e-7 2.10428e-6 -1 -3.97314e-4 1.35087e-4 -1 7.77686e-4 3.59658e-4 -0.9999997 4.76276e-7 -1.19341e-6 -1 -4.26543e-5 4.26506e-4 -1 5.7305e-5 1.89471e-4 -1 2.43242e-4 -5.93137e-5 -1 -1.39875e-6 2.7314e-5 -1 9.22134e-6 -6.63244e-6 -1 6.80661e-6 -4.20226e-5 -1 1.86127e-6 3.28759e-6 -1 4.50913e-7 0 -1 4.18219e-6 -1.30036e-5 -1 3.30287e-5 -5.87213e-4 -0.9999999 1.41454e-4 -1.9202e-4 -1 1.72344e-4 -3.6839e-4 -1 3.14483e-4 0.004220724 -0.9999911 -2.46097e-4 9.17515e-6 -1 0 0 -1 -1.35816e-6 -3.22056e-4 -1 1.41359e-4 -1.13386e-4 -1 -2.70128e-6 0 -1 -2.30371e-7 8.74119e-4 -0.9999997 -7.22461e-5 2.32499e-5 -1 0 -8.56009e-4 -0.9999997 -4.26057e-5 4.91678e-4 -0.9999999 0 -2.38447e-7 -1 -1.51801e-5 2.74808e-7 -1 0 0 -1 5.28095e-6 1.01186e-5 -1 5.21895e-6 1.37884e-5 -1 5.85633e-7 -3.31374e-7 -1 9.33338e-6 -4.3895e-4 -1 -0.2539659 -0.9672132 0 -0.8048954 -0.590359 -0.06016427 -0.9998677 0.0120182 -0.01097297 0.7949861 0.605589 0.03548604 1.72086e-4 -1 4.04639e-4 -0.9175263 -0.3838686 0.1038774 -0.9308632 -0.3569487 0.07798475 -0.7727768 -0.634678 0 -0.772783 0.6346705 0 -0.5622425 0.8029614 0.1978294 -0.3320969 0.9432453 0 -4.32125e-7 1 0 -0.9371311 0.3421964 0.06846237 -0.2873812 -0.9576532 -0.01768201 -0.3163668 0.948593 -0.009145915 -0.9623401 0.2718486 0 -1 -3.50106e-6 5.39723e-5 -0.5000153 -0.8660166 -2.47104e-4 -0.5000091 -0.8660201 -1.11662e-4 0.7193591 -0.6837257 0.1226444 0.8505179 -0.5246181 -0.03735333 0.9998702 -0.01180964 -0.01096385 -0.001152217 0.9999676 0.007972478 0.2880798 -0.9568946 -0.03691631 -0.5886632 -0.7877432 -0.1814839 0.7220872 -0.6686194 -0.1775905 -0.2471346 0.9450982 0.2138084 0.07696372 -0.9948274 0.0662955 -0.8870774 0.3698967 -0.2761707 -0.387337 0.9087038 0.1556519 0.8749291 0.4257423 0.2307437 0.994522 -0.1045273 0 0.2079107 -0.9781478 0 -0.8914534 -0.4277831 -0.1493744 0.01843327 0.9882964 0.1514283 0.5280261 0.8415395 0.1140176 0.5934101 0.8006158 0.08293831 0.9239337 -0.3677576 -0.1053606 0.07020497 -0.9908678 0.115119 0.7041002 -0.7005602 -0.1160108 -0.7071068 -0.7071068 0 0.3779135 -0.9248477 -0.04287409 0.963564 0.01746642 -0.266907 0.9504357 -0.3067997 0.05045723 0.3372592 0.902775 0.2669337 -0.4209732 0.9070732 0 0.9504437 0.3067754 -0.05045539 0.3267811 0.9451001 0 -0.4209753 0.9070722 0 0.08789461 -0.9847207 0.1503323 0.9635667 -0.01747453 0.2668969 -0.7071082 0.7071054 0 -0.944715 -0.2281194 0.2355318 -0.1734352 -0.9513139 -0.2547982 0.7715353 -0.6276387 -0.103938 0.8095628 0.5870335 0 -0.9225985 -0.3857617 0 0.5447356 -0.7994878 0.253145 0.8519922 0.5165198 0.08553791 0.9930558 0.1168937 -0.01327472 0.7174707 -0.6530476 0.2424143 -0.253428 -0.9660099 -0.05098211 -0.2588196 0.9659258 0 0.3267828 0.9450995 0 -0.03152132 -0.9592556 -0.280776 -0.4772141 0.8689916 -0.1308445 0.2246301 0.9714576 -0.07623302 0.9166462 0.2799094 -0.2853254 -0.2239276 -0.9684363 -0.1094878 -0.9463869 -0.2890126 0.1443039 0.1568745 0.9762928 -0.1491402 -0.07106316 -0.9520584 -0.2975481 0.6728052 0.7209962 0.1658247 0.9338189 -0.2160521 -0.285138 0.2826796 -0.9258033 0.2509596 -0.6802447 -0.7290108 -0.07622629 -0.9714555 0.2246418 -0.07622444 0.04737943 0.9301111 -0.3642094 0.9398959 -0.2855925 -0.1871702 -0.5076606 -0.8161687 -0.2759521 0.9567809 0.256375 -0.1372678 -0.682228 -0.7311041 0.007197678 -0.9714576 0.224632 -0.07622766 -0.3683354 0.9285648 -0.04578703 0 0.9469295 -0.3214412 0.9393106 -0.1380746 -0.3140559 0.7070984 -0.7071153 0 0.2588223 -0.965925 0 -0.08575659 -0.9787364 -0.1863356 0.2180389 0.9431074 0.2510126 0.9081564 0.3603352 -0.2130975 0.3538134 -0.8921681 -0.2808065 -0.3330581 -0.9421362 -0.03810328 -0.9536609 -0.2910749 -0.07619935 -0.8436096 -0.4571648 -0.2816442 -0.6058515 0.7950387 -0.02928334 0.9430212 -0.2182767 0.2511304 0.3683184 -0.9296997 0 -0.9712451 0.2255727 -0.07615804 -0.2910394 0.9536719 -0.07619696 0.5689935 -0.7967899 -0.2034023 -0.2586266 0.9652071 -0.03856831 0.2241119 0.9693018 -0.1011334 0.3815245 0.8502898 -0.3625555 0.29028 -0.9506554 -0.1095078 -0.9820827 0.1443026 -0.121204 0.956784 -0.2563617 -0.1372702 0.2391541 -0.970273 -0.03709137 -0.5000033 0.8660236 0 -0.5103816 0.8599478 7.07029e-4 -0.5102649 0.8600173 0 0.3420199 -0.9396927 0 0.9471317 0.3208453 0 0.9595023 0.2817006 0 0.9704987 0.2411017 0.001534044 0.9799618 0.1991789 0.001642584 0.9997438 0.02257394 0.001686334 0.9977116 -0.06759393 0.0016824 0.9936832 -0.1122096 0.00167489 0.9877323 -0.1561479 0.001665353 0.9799618 -0.1991789 0.001652598 0.9705008 -0.2410928 0.001635491 0.9595012 -0.2817003 0.001605927 0.9471307 -0.3208448 0.001462638 0.9471307 -0.3208449 -0.001462638 0.9546458 -0.2977414 0.001239836 0.9799627 0.1991744 -0.001642525 0.9838744 0.1788522 -0.0017457 0.987733 0.1561434 -0.001665651 0.9838744 0.1788522 0.0017457 0.9909016 0.1345778 -0.001698017 0.9959363 0.09004551 0.001687943 0.9989793 0.04514038 -0.001684904 0.9997438 0.02257394 -0.001686334 0.9997437 -0.02257877 -0.001685798 0.9999986 9.66552e-6 0.001686334 0.9959443 -0.08995604 -0.001679718 0.9936827 -0.1122144 -0.00167489 0.9959447 -0.08995133 0.001679718 0.9909486 -0.1342318 -0.001668334 0.9877331 -0.1561433 -0.001665353 0.9840887 -0.1776702 -0.001650452 0.9755157 -0.219924 -0.001614689 0.9705007 -0.2410929 -0.001635491 0.9755147 -0.2199286 0.001614689 0.9654967 -0.260411 -0.001524806 0.9595012 -0.2817003 -0.001605868 0.3420201 0.9396927 0 0.3420201 0.9396927 0 0 0 -1 1.42479e-7 0 -1 -4.40538e-7 0 -1 1.55002e-7 0 -1 -1.55728e-7 0 -1 1.42807e-7 0 -1 -6.0189e-7 0 -1 -2.12751e-7 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.9996529 9.48694e-4 -0.02632939 -0.5151775 0.841011 0.1652051 2.71686e-4 0.9995831 -0.02887284 1.26199e-4 0.9996594 -0.02610152 -0.01350492 0.002102017 0.9999066 -1.52034e-5 -1.85854e-4 1 5.74058e-7 -3.53814e-5 1 4.04963e-5 -1.56737e-7 1 1.17882e-4 5.42447e-5 1 -2.09967e-4 -3.7075e-6 1 6.58954e-6 -5.21817e-4 1 -0.6697471 0.7394784 0.06790125 -0.4802477 0.8769502 0.01790803 1.08672e-4 0.9996559 0.02623319 0 0.9996481 0.02653026 0.5389839 0.8392794 -0.07145988 -0.999669 1.8269e-4 0.0257278 0.7436999 -0.2290766 -0.6280401 0.6856484 -0.1368522 -0.714953 0.002988576 -0.2863933 -0.9581075 -0.02163952 -0.9991831 -0.03413248 -0.02147787 -0.998832 -0.04328334 0.9360106 -0.3490993 -0.04487568 0.9957496 0.03738272 -0.08417505 -0.9987944 -0.004691779 -0.04886507 -0.7046484 -0.708631 -0.03623372 -0.9981349 -1.05193e-6 0.06104844 -9.60955e-5 0 1 0.9981347 0 0.06105071 0.9981348 2.77007e-6 0.06104874 0 0.9996573 0.02617931 0 0.9997569 0.0220524 -0.003869593 0.999656 0.02593988 0.2275843 0.9668258 0.115989 0.2074084 -0.9756042 -0.07195931 0.1953788 -0.9783818 -0.06779688 0.1614047 -0.9842473 -0.07215273 0.172146 -0.9824326 -0.07205528 0.2074154 -0.9759016 -0.06778776 0.1791834 -0.9814943 -0.06754529 0.1670059 -0.9836193 -0.06783837 0.1279198 -0.9891477 -0.07227313 0.1367799 -0.9882653 -0.06799185 0.09076523 -0.9932091 -0.07278388 0.07912898 -0.9943155 -0.07124245 0.09125024 -0.9935735 -0.06697154 0.1041841 -0.9921998 -0.06844961 0.04863524 -0.9961229 -0.07330644 0.03387552 -0.9970575 -0.06876617 -0.05786055 -0.9963064 -0.06344819 -0.1089748 -0.9916791 -0.06853485 -0.1368525 -0.9879668 -0.07206279 -0.1927748 -0.9786156 -0.07175952 -0.222854 -0.9724569 -0.06829208 -0.2493724 -0.9655655 -0.07413995 -0.2430165 -0.9675499 -0.06921052 -0.2895988 -0.9549448 -0.06490844 -0.2933363 -0.9534075 -0.07048344 -0.2542316 -0.9645155 -0.07124775 -0.1957059 -0.9779187 -0.0733093 -0.003721535 -0.9975719 -0.06954574 -0.05439525 -0.9956916 -0.07509654 -0.06074213 -0.9957688 -0.06895738 -0.02418231 -0.9971375 -0.07163864 -8.12782e-4 -0.9978629 -0.06533765 -0.085828 -0.9933708 -0.07647395 -0.0998013 -0.9925121 -0.07042294 -0.2151032 -0.9740449 -0.07047915 -0.1775734 -0.9816899 -0.06893986 0.2280815 -0.9709258 -0.07267779 -0.2334312 -0.9693556 -0.07654809 -0.00113511 -0.9972229 -0.07446736 -0.03000491 -0.9974685 -0.06446909 0.1128177 -0.9913626 -0.06687456 0.1478748 -0.9867087 -0.06737285 0.01757413 -0.8194653 -0.5728593 0.06739258 0.8753836 0.4787086 -0.2735229 0.00675261 0.9618418 -0.2380698 -0.8924847 0.3831368 -5.27803e-4 0.400545 0.9162771 6.14752e-4 0.3872248 0.9219852 7.49723e-4 0.5182972 0.8552004 0.004927337 0.1739974 0.9847339 -4.52886e-4 0.4895932 0.871951 0.02868396 0.553909 0.8320831 -4.04797e-4 0.5485213 0.8361365 0.01994007 0.4715573 0.88161 2.21305e-4 0.3986068 0.9171218 4.51619e-4 0.3220764 0.9467136 3.32657e-4 0.2631027 0.9647678 -2.46606e-4 0.2623877 0.9649626 -3.06432e-4 0.3439759 0.9389784 -2.64696e-4 0.3006329 0.9537399 -0.006661593 0.428777 0.9033859 0.04421919 0.5451623 0.8371635 -0.005097329 0.6575928 0.7533563 -4.75712e-4 0.4332302 0.9012832 -4.68859e-4 0.5849678 0.8110565 -9.99048e-4 0.504072 0.8636611 0.001033484 0.5537594 0.8326761 2.13215e-4 0.4945652 0.8691406 0.006585419 0.5842797 0.8115257 3.78761e-4 0.8035968 0.5951741 -4.32715e-4 0.8315659 0.5554261 -0.001136481 0.862014 0.5068833 -0.06278097 0.6080046 0.7914475 0.003287255 0.460985 0.8874018 5.04167e-5 0.4036586 0.9149098 0.002656102 0.4111257 0.9115749 -3.28783e-4 0.3851504 0.9228538 -2.12597e-4 0.4210749 0.9070259 0.008470237 0.5250629 0.8510214 0.003019154 0.5866941 0.8098031 5.41773e-4 0.06204009 0.9980736 -3.62974e-4 0.04949355 0.9987745 0 0.04761487 0.9988659 -3.53191e-4 0.04493486 0.9989899 1.96151e-4 0.02755737 0.9996203 -0.003887951 0.08364409 0.9964882 7.03875e-4 0.1001397 0.9949731 4.17542e-4 0.1305316 0.9914441 0 0.1355179 0.9907749 -3.33546e-4 0.1329181 0.991127 -0.002955853 0.1386916 0.9903312 4.22122e-5 0.1945722 0.9808883 0.02153617 0.2290473 0.973177 -4.08608e-4 0.130916 0.9913934 -5.49219e-4 0.09965163 0.9950222 6.95525e-4 0.09075295 0.9958732 6.79601e-4 0.1557509 0.9877962 -1.0739e-4 0.2456845 0.9693499 2.54361e-4 0.2250838 0.9743394 0.008904457 0.6302513 0.7763401 0.007523894 0.6323496 0.7746466 2.09819e-4 0.6213968 0.783496 -9.0769e-4 0.6262238 0.7796429 -0.002493143 0.6192478 0.7851917 -2.80497e-4 0.7228825 0.690971 -0.002583861 0.7377059 0.6751174 0.001106441 0.6710497 0.7414116 0.003480672 0.7601063 0.6497895 -0.001678049 0.7899 0.6132335 -0.01131135 0.9143105 0.4048562 -7.24533e-4 0.3687652 0.9295223 6.65387e-4 0.1144818 0.9934252 0.01063627 0.1527681 0.9882048 0.001056969 0.008097469 0.9999668 7.78292e-4 0.02383971 0.9997155 -5.06168e-4 0.02330207 0.9997285 5.88632e-4 0.1224206 0.9924782 -1.26142e-4 0.2260367 0.9741189 -0.07604795 0.4320981 0.8986145 0.03713297 0.2943469 0.954977 -3.42879e-4 0.4459455 0.8950601 0.002460241 0.8103404 0.5859545 -0.01004505 0.5745273 0.8184239 9.529e-4 0.6731748 0.7394829 -0.001019716 0.6197218 0.7848209 2.97794e-4 0.6123823 0.7905619 -7.40413e-5 -0.4314555 -0.9021342 4.72121e-4 -0.4085225 -0.9127482 -9.86292e-5 -0.4060137 -0.9138671 -2.42894e-5 -0.4055092 -0.9140911 -2.26181e-6 -0.4410628 -0.8974763 -0.01813638 -0.41474 -0.9097592 -6.11614e-4 -0.5202997 -0.8539835 -0.01068121 -0.497151 -0.8675984 7.6247e-4 -0.6580865 -0.7529419 7.64978e-4 -0.7056527 -0.7085576 -4.00957e-4 -0.6818252 -0.7315151 -0.005598127 -0.6547337 -0.755839 3.72945e-4 -0.5914357 -0.8063521 0.001051604 -0.6107014 -0.7918603 -0.006786286 -0.528321 -0.8490176 -0.005098283 -0.5761229 -0.8173472 -0.00200206 -0.6354992 -0.772099 -4.65237e-4 -0.572299 -0.8200449 -0.004060566 -0.5564494 -0.8308715 0.00278747 -0.4892153 -0.8721586 -0.001055598 -0.6704766 -0.7419299 -1.38417e-4 -0.720525 -0.693429 -6.16016e-4 -0.7382119 -0.6745687 3.34689e-4 -0.6621226 -0.7493956 -2.92057e-4 -0.6914308 -0.7224428 -6.25602e-4 -0.6959493 -0.7180908 -0.006673574 -0.4555038 -0.890209 0.006650507 -0.2953572 -0.9553638 -4.15228e-4 -0.2477939 -0.9688127 3.71516e-4 -0.2682174 -0.9633584 -3.49667e-4 -0.2883726 -0.9575182 3.81157e-4 -0.3099938 -0.9507386 -2.26766e-4 -0.3266871 -0.9451326 -7.9888e-5 -0.3187451 -0.9478405 2.81367e-4 -0.2460485 -0.9692575 -5.36504e-5 -0.1097069 -0.9939641 7.88507e-4 -0.1447393 -0.9894695 0.005102872 -0.1535112 -0.9881337 -0.001009404 -0.01719957 -0.9998516 -6.76424e-4 -0.01458615 -0.9998934 1.13405e-4 -0.02522796 -0.9996818 0 -0.02576225 -0.9996682 -0.001587808 -0.02142912 -0.9997691 1.53659e-4 -0.03354895 -0.9994372 -8.7412e-4 -0.01030772 -0.9999465 2.39874e-4 -0.1733162 -0.9848662 -3.82323e-5 -0.2123044 -0.9772037 2.50003e-4 -0.2312987 -0.9728828 -9.11577e-5 -0.4284812 -0.9035508 -2.37678e-4 -0.4597579 -0.8880443 3.8263e-4 -0.4825631 -0.8758612 1.4591e-4 -0.5537605 -0.832676 7.67928e-5 -0.404015 -0.9147525 2.67691e-4 -0.7379904 -0.6748111 -0.01351416 -0.8533717 -0.5211279 -0.007929861 -0.8687185 -0.495243 -0.01183027 -0.9164757 -0.3999155 -9.21288e-4 -0.6348953 -0.7725977 -8.76056e-6 -0.603307 -0.7975091 -9.16346e-4 -0.207157 -0.9783074 2.7025e-4 -0.3656853 -0.9307385 -4.88368e-4 -0.3768504 -0.9262741 -5.94728e-4 -0.5905494 -0.8070013 0.001268923 -0.804685 -0.5937007 -4.20718e-5 -0.3753091 -0.9268998 -2.77227e-4 -0.3981022 -0.9173411 3.2677e-4 -0.3662731 -0.9305074 -3.63893e-4 -0.2092849 -0.9778547 0.00219196 0.9974856 0.07083648 0.03151237 0.9970566 0.06989586 0.06655079 0.9953439 0.06972652 0.09945791 0.9927206 0.06792628 0.1158162 0.990758 0.070607 -0.05916905 0.9956688 0.07171273 -0.0146498 0.9972662 0.07242733 -0.04426807 0.9965373 0.0703839 -0.1096786 0.9915968 0.06860381 -0.1938101 0.9785281 0.07014721 -0.08115082 0.9943978 0.06773155 -0.1183415 0.9906349 0.06810116 -0.1508172 0.9861943 0.06837397 -0.217085 0.9738036 0.06768023 -0.2355556 0.9690607 0.07372272 -0.3426275 0.9335422 0.105382 0.1206243 0.9900938 0.07186114 0.1466544 0.986747 0.06944626 0.1398793 0.9876129 0.07109713 0.1625775 0.9841117 0.07136487 0.2039989 0.9765096 0.06937956 0.1770897 0.9816955 0.07009512 0.2013942 0.976919 0.07120287 0.2877659 0.95511 0.07039755 0.2882324 0.9549531 0.07061773 0.313197 0.9469801 0.07166826 0.2088895 0.9754533 0.06968557 -0.001910865 0.9975975 0.06925171 0.03403431 0.996936 0.07042992 0.4926105 -0.8445778 0.2098174 0.5710272 -0.8043022 0.1643957 -0.2872098 0.9402458 -0.1828894 0.3533131 -0.912539 0.2060162 0.2949533 -0.935985 0.1921836 0.3144479 -0.9299003 0.1908087 -0.3133951 0.9303706 -0.1902475 0.3174006 0.9285058 0.1927013 0.6541693 -0.04574203 0.7549639 0.8041479 -0.5822958 0.1194893 0.7961776 0.5925474 0.1224289 0.3092227 0.9315621 0.1912413 -0.3134141 -0.9303625 -0.1902561 0.3144484 0.9299002 0.1908083 0.3144471 -0.929901 0.1908065 0.3144438 -0.9299016 0.1908093 0.3143352 -0.9299339 0.1908307 0.5922995 -0.7631896 0.258308 -0.3144509 0.9298991 -0.1908094 -0.3144493 0.9298999 -0.1908087 -0.9997779 -0.02098482 -0.001949131 0.5972448 0.3804187 0.7061022 0.6324639 0.1990817 0.7485693 -0.9999414 -0.002574384 -0.01051717 -0.9999856 2.43801e-4 0.005376458 -0.9819498 -0.1867137 0.03021174 0.3144493 0.9298998 0.190809 0.3144482 0.9299002 0.1908088 0.3144514 0.9298991 0.190809 0.5075742 0.8581042 -0.07762527 -0.9929783 0.1182437 0.003564059 -0.9999963 5.89805e-4 0.002671301 -0.7768183 -0.007424771 0.6296811 -0.5676398 0.007762193 0.8232405 -0.09743291 0.007169246 0.9952163 0.5755174 -0.008633911 0.817744 0.6866344 0 0.7270029 -0.8784176 -1.06089e-5 0.4778939 -0.8680682 0.004067957 0.4964283 -0.06436896 0.4972326 0.8652263 -1 0 0 -0.9997584 0.02189016 -0.002034127 -0.3144494 -0.9298999 -0.1908085 -0.3144491 -0.9298999 -0.190809 -0.3144487 -0.9299 -0.1908089 -0.320806 -0.9465487 -0.03360474 -0.3201609 -0.9467929 -0.03286969 -0.3797084 -0.898732 -0.2193226 -0.4417214 -0.8639736 -0.2417271 -0.4665105 -0.8477676 -0.2523056 -0.3144485 -0.9298999 -0.1908095 -0.1538311 -0.7424657 -0.6519821 -0.05794775 -0.5417334 -0.8385506 -0.06373381 -0.5949386 -0.8012403 -0.3458971 -0.9237852 -0.1642443 0.0632376 0.9979963 -0.002151787 0.05946648 0.9982303 -2.7151e-4 -0.1107346 -0.005778729 0.9938333 -0.1174761 -0.006666243 0.9930533 -0.1017998 -0.009400308 0.9947605 -0.3618467 -0.04170864 0.9313042 -0.6805359 -0.1362403 0.7199372 -0.2686458 -0.06381237 0.9611231 -0.2067062 -0.05906909 0.9766184 -0.2721623 -0.06664669 0.9599406 -0.2733577 -0.06122106 0.9599624 -0.2889809 -0.05338466 0.9558452 -0.40378 -0.09812635 0.9095785 -0.7226758 -0.1770957 0.6681144 -0.9723196 0.2086946 0.1050776 -0.9839568 0.1459266 0.1026381 -0.9707205 0.01945221 0.2394232 -0.9526327 -0.01338833 0.3038286 -0.9342298 -0.0410425 0.3543024 -0.8546425 -0.1134876 0.5066624 -0.7580352 -0.1301343 0.6390993 -0.7608558 -0.05707585 0.6464061 -0.8344337 -0.003483235 0.5510974 -0.9614187 0.2040312 0.1845144 -0.9596261 0.2648615 0.09468924 -0.7665562 -0.0612322 0.6392515 -0.7668082 -0.01560485 0.6416866 -0.865068 0.05293846 0.4988536 -0.9588225 0.2450805 0.1435102 -0.9479673 0.2540339 0.1918983 -0.7678787 0.09637123 0.6333047 -0.7498281 0.1160213 0.6513808 -0.5023955 0.1637624 0.8489881 -0.2876406 0.05393785 0.9562184 -0.2466478 0.03977257 0.9682888 -0.1238953 0.03349226 0.9917299 -0.2361868 0.04418462 0.9707026 -0.7990184 0.05375218 0.5988993 -0.4232766 0.08504343 0.9020004 -0.3500477 0.06492441 0.9344792 -0.3304724 0.04901593 0.942542 -0.1682718 0.02095437 0.985518 -0.1171837 0.01424431 0.9930081 0.01254713 0.9939652 -0.1089766 -0.1173918 0.0181083 0.9929206 -0.1059304 9.26247e-4 0.9943732 -0.8236017 0.2596356 0.5042516 -0.7956303 -0.1908052 0.5749487 -0.5849926 0.11277 0.8031604 -0.8545463 -0.2085126 0.4756819 -0.9762867 -0.1690016 0.1352875 -0.95929 -0.2666156 0.09316027 -0.5336619 -0.1156975 0.8377465 -0.3818058 -0.1090215 0.9177901 -0.409159 -0.1203018 0.904498 -0.2173711 -0.05988997 0.9742501 -0.1201154 -0.03332829 0.9922003 -0.09621578 -0.03618937 0.9947024 -0.1441849 -0.0181545 0.9893843 -0.1614224 -0.008557021 0.9868484 -0.1585221 -2.84245e-4 0.9873555 -0.1654406 0.02315634 0.9859479 -0.09803164 0.03326386 0.9946272 -0.2690142 0.06653285 0.9608355 -0.2863562 0.06324017 0.9560339 -0.5751252 0.1510271 0.8040036 -0.3506348 0.08742684 0.9324226 -0.2453935 0.05937862 0.9676035 -0.8198606 0.2192127 0.528937 -0.9879856 0.1215323 0.09546983 -0.9970816 0 0.07634413 -0.9907055 -0.01940137 0.1346337 -0.9913779 -0.0335052 0.1266784 -0.9938349 -0.04539215 0.1011524 -0.9779762 -0.124616 0.1674322 -0.9888488 -0.1082155 0.1023112 -0.9880488 -0.1185123 0.09856218 -0.9587664 -0.2464878 0.1414598 -0.9627205 -0.2003484 0.1817407 -0.9420041 -0.2617703 0.2100113 -0.1116368 0.004440486 0.9937393 -0.1039119 0.005231201 0.9945728 -0.1115973 0.004525005 0.9937433 -0.1608315 0.0435093 0.9860224 -0.1045688 -0.02257299 0.9942615 -0.9733551 -0.2039797 0.1047486 -0.9839168 0.02162104 0.1773142 -0.9866315 0.0459913 0.1563436 -0.8056936 0.0284866 0.5916472 -0.2290022 -0.03165501 0.9729112 -0.9395504 -0.1062226 0.3255178 -0.8644273 -0.06012928 0.4991494 -0.8381272 -0.1230351 0.5314181 -0.8300068 -0.1220173 0.5442431 -0.796652 -0.134114 0.5893719 -0.9029383 -0.0685513 0.4242681 -0.9812855 -0.09188526 0.1692217 -0.9276797 -0.04325473 0.3708631 -0.9695471 -0.04701721 0.2403494 -0.9763203 -0.0379157 0.2129817 -0.8833734 -0.007373929 0.468612 -0.8555548 0.001689553 0.5177097 -0.9782564 -0.02746522 0.2055728 -0.8446315 0.05710583 0.5322939 -0.9626418 0.1443559 0.2290903 -0.9756345 0.01294779 0.21902 -0.9701775 0.04850393 0.2374935 -0.9775173 0.07374984 0.1975372 -0.474682 0.0693776 0.8774188 -0.8589602 0.1434227 0.491546 -0.8991503 0.2124716 0.3826022 -0.9303033 0.1401352 0.338966 -0.9624429 0.1334893 0.2363986 -0.2022212 -0.02622318 0.9789887 -0.14474 -0.02924233 0.9890375 -0.555657 -0.09943079 0.8254447 -0.3490449 -0.07150673 0.9343738 -0.9535434 -0.1588048 0.2560002 -0.966032 -0.1870388 0.1783217 -0.9640256 -0.2096381 0.1634218 -0.8935096 -0.2009672 0.4015629 -0.176474 -0.04451125 0.9832984 -0.3567676 0.08178985 0.930606 -0.6300099 0.1329724 0.7651183 -0.9469946 0.1795609 0.2663819 -0.9218977 0.1718556 0.3472325 -0.8693754 0.1592822 0.4677776 -0.9726673 0.1623455 0.1660191 -0.457273 -0.1178502 0.8814833 -0.133324 0.03225743 0.9905474 -0.117229 0.03690296 0.9924191 -0.539013 0.1033188 0.8359368 0.1835886 0.9830014 0.001855015 -0.2240304 -0.5044509 0.8338704 0.06684494 -0.2929211 -0.9537972 -0.6587128 -0.4418947 0.6089553 -0.2064421 -0.9630602 0.1729071 -0.2836591 -0.5582863 0.7796499 0.1733605 -0.03721207 0.9841552 0.03395795 -0.5761666 0.8166267 -0.2945137 -0.6650571 0.686266 -0.1425496 -0.9874631 0.06779581 -0.7255201 0.2016512 0.657995 -0.6993718 0.01812535 0.7145283 -0.7115699 0.01135706 0.7025236 -0.705062 0.02333569 0.7087616 -0.4530344 -0.007675945 0.8914601 -0.4122322 0.5436058 0.7311342 -0.2126824 0.9151489 0.3424453 0.09228205 0.5563803 0.8257874 -0.6203824 0.1519146 0.7694465 -0.285509 -0.09312093 0.9538413 -0.4623048 0.4524275 0.7626165 -0.3833425 0.478925 0.7897338 -0.2065517 0.96457 0.1641378 -0.371653 0.7754019 0.5105156 -0.245063 0.7531718 0.6104724 -0.208278 0.2840451 0.935916 -0.4788897 0.1262654 0.8687472 -0.3302229 0.8729191 0.3591175 -0.1960719 0.5313436 0.824154 -0.5194866 0.4598966 0.720159 -0.419183 0.02196073 0.9076362 -0.6960963 -0.02120673 0.7176352 0.9054308 -0.2789141 0.3200032 0.3755135 -0.6549036 0.6558132 -0.8137634 -0.3792158 0.4404368 -0.4367375 -0.5800095 0.6876404 -0.9197463 -0.3919884 0.02029514 -0.9996657 0.02453339 -0.00816518 -0.9184636 -0.1962668 0.3433716 -0.8743845 -0.3649135 0.3198279 -0.6904405 -0.7217686 0.04839581 -0.003778517 -0.693051 0.7208788 -0.002347826 -0.7662051 0.6425918 -3.25363e-4 -0.8026455 0.5964564 0.005289316 -0.6109938 0.7916177 -0.007039904 -0.549628 0.8353798 -1.80585e-4 -0.4382012 0.898877 0.008728802 -0.4034095 0.914978 0.003485202 -0.3974086 0.9176352 3.99355e-4 -0.3830407 0.9237315 -0.001538157 -0.4336231 0.9010931 -4.07956e-4 -0.439627 0.8981805 5.10857e-4 -0.466407 0.8845702 6.99448e-5 -0.7206951 0.6932523 3.01604e-4 -0.7313711 0.6819797 0.006813526 -0.7478946 0.6637825 3.53218e-4 -0.3059123 0.9520596 2.95006e-5 -0.2859659 0.9582399 -8.57217e-4 -0.319523 0.9475782 -8.20644e-5 -0.3312497 0.9435432 -7.70014e-4 -0.3500313 0.9367377 1.78133e-4 -0.2645987 0.9643587 -4.04406e-5 -0.22596 0.9741366 1.82524e-4 -0.2259656 0.9741352 3.98398e-4 -0.1917353 0.9814467 3.69105e-4 -0.1896581 0.9818502 5.13806e-4 -0.1533902 0.9881656 7.22131e-4 -0.1551203 0.9878954 -1.89728e-4 -0.16933 0.9855594 4.2612e-4 -0.1225517 0.992462 0 -0.09560555 0.9954193 3.73086e-5 -0.07719886 0.9970158 5.42246e-4 -0.0916211 0.9957939 7.51495e-4 -0.0633161 0.9979932 5.3931e-4 -0.06206876 0.9980717 6.25042e-4 -0.01429843 0.9998977 -4.09154e-4 -0.02346569 0.9997246 3.69016e-4 -0.03735965 0.9993019 3.69799e-4 -0.02635568 0.9996526 -6.11792e-5 -0.02316141 0.9997318 -0.001371562 -0.01411515 0.9998995 -3.61752e-4 -0.03815478 0.9992719 -1.16817e-4 -0.1341295 0.9909638 -0.001035571 -0.1719216 0.9851102 -3.03612e-4 -0.2378318 0.9713064 5.05351e-5 -0.3890405 0.9212207 -5.33279e-5 -0.4149877 0.9098271 -0.00480324 -0.4309208 0.902377 0.003472089 -0.703698 0.7104907 0.005523085 -0.7387727 0.6739321 -0.0351125 -0.9081809 0.4171026 0.005122959 -0.6251128 0.7805176 -0.006941437 -0.594033 0.8044108 0.005701422 -0.5556727 0.8313817 -9.08085e-5 -0.5213267 0.8533572 -1.05008e-4 -0.5209785 0.8535699 -0.002169072 -0.6890913 0.7246714 -0.006623983 -0.706233 0.7079485 -0.01453149 -0.7371462 0.6755771 -5.5614e-4 -0.6604982 0.7508274 0.001242041 -0.6047327 0.7964277 -0.003040015 -0.5746732 0.8183773 -0.005517423 -0.5768561 0.8168273 3.0579e-4 -0.4494953 0.8932827 1.32295e-5 -0.4433494 0.8963488 1.07055e-4 -0.4194722 0.9077682 0.00367254 -0.3648064 0.9310762 0.001734018 -0.2984676 0.9544183 5.57975e-4 -0.5081381 0.8612755 0.01474702 -0.5338632 0.8454423 0.003729224 -0.5181145 0.8553032 0.00159806 -0.5525867 0.833454 0.00256592 -0.6838048 0.7296605 0 -0.04818761 0.9988384 1.20473e-4 -0.3877748 0.9217543 -1.0293e-4 -0.3612489 0.9324695 1.28736e-4 -0.3525585 0.9357898 -0.1735228 -0.9824714 0.06811565 -0.1752913 -0.9821238 0.06860011 0.2294291 -0.9701982 0.07796156 0.2409079 -0.9678243 0.07265949 -0.1429015 -0.9874042 0.06791335 -0.1262595 -0.9893987 0.07175487 -0.1093731 -0.9916818 0.06785953 -0.07369166 -0.9949633 0.06795328 0.01942682 -0.9979569 0.06086659 0.08454489 -0.9941778 0.06680393 0.0868541 -0.9938326 0.06894361 0.1254313 -0.9893809 0.07343417 0.1416797 -0.9877089 0.06601572 0.1816706 -0.9810222 0.06775963 -0.04973036 -0.9958851 0.07576239 0.04446387 -0.996104 0.07615691 0.1659345 -0.983406 0.07333916 0.1008486 -0.9926178 0.06737649 0.09964811 -0.9924392 0.07165646 0.272527 -0.9592536 0.07457643 0.3132974 -0.9469873 0.07113361 0.2891775 -0.9546903 0.07030481 0.288712 -0.9549351 0.06888014 0.2890457 -0.954735 0.07024174 0.0761789 -0.9944505 0.07256072 0.06172233 -0.9957769 0.06796288 0.06100189 -0.9955612 0.07167112 0.02491766 -0.9972368 0.0699858 -0.007170438 -0.9975537 0.06953686 -0.05916267 -0.995532 0.07359188 -0.07871615 -0.9947052 0.06607168 -0.09797441 -0.9924821 0.0733515 -0.1264899 -0.9896352 0.06799018 -0.1534743 -0.9855944 0.07105946 -0.1628894 -0.9841026 0.07077705 -0.185124 -0.9803556 0.06806004 -0.1708521 -0.9825104 0.07404679 -0.2164469 -0.9736182 0.0722391 -0.2334998 -0.9701768 0.0650767 -0.2308251 -0.9705023 0.06960576 -0.005497872 -0.9974969 0.07049703 -0.07795321 -0.9943524 0.07202035 -0.09581547 -0.9930852 0.06783264 -0.01609516 -0.9970558 0.07497143 -0.03926116 -0.9970266 0.06630802 -0.7479072 0.6615531 0.05461025 -0.7123427 0.5906285 0.3791121 -0.3877934 0.5852057 0.7121451 0.7994417 0.5996243 0.03665554 0.2735788 0.9594027 0.06856507 -0.03136515 0.9427266 0.3320888 -0.874076 0.3036981 0.3791554 0.6136642 0.6403971 0.4618526 0.9995748 0.02662009 0.01190161 0.9997695 -0.01221448 0.01766008 0.9986258 0.04861742 0.01956832 0.999904 -0.01051127 0.009025633 9.4917e-6 -0.9253163 0.3791965 9.76406e-6 -0.9253201 0.3791871 -1.60417e-7 -0.9253162 0.3791965 -0.01956444 -0.9243028 0.3811583 -0.999923 -0.008971393 0.008579611 0 0.04523527 -0.9989764 -0.001072645 0.09234225 -0.9957268 -5.24199e-4 0.1294133 -0.9915907 7.80323e-4 0.1445971 -0.9894904 -8.67011e-4 0.1746991 -0.9846215 0 0.1841052 -0.9829066 -3.19084e-4 0.2058463 -0.9785842 -0.00531727 0.2555168 -0.9667901 5.16188e-4 0.2509009 -0.9680128 3.11012e-4 0.2683139 -0.9633316 0.001878321 0.1941783 -0.9809645 -2.36856e-4 0.204993 -0.9787635 -1.97119e-4 0.2052541 -0.9787088 2.56553e-4 0.09787923 -0.9951983 5.13484e-5 0.1437256 -0.9896177 5.91971e-4 0.06733506 -0.9977303 -8.96774e-4 0.04740977 -0.9988752 0 0.0257591 -0.9996682 -9.70232e-4 0.01689219 -0.999857 -0.001263082 0.08187407 -0.9966419 -2.70092e-4 0.3485832 -0.9372778 5.32403e-4 0.3570173 -0.9340976 2.15128e-4 0.3102828 -0.9506443 3.96864e-4 0.2988724 -0.954293 4.39786e-4 0.2995877 -0.9540687 -4.29371e-4 0.3335816 -0.9427212 5.18214e-4 0.3526136 -0.9357689 -0.010854 0.26521 -0.9641296 -0.0138778 0.260113 -0.9654785 -2.17822e-4 0.2736147 -0.9618394 -0.002304136 0.5603977 -0.8282206 3.69598e-5 0.6006924 -0.7994803 3.43356e-4 0.5997992 -0.8001506 2.48251e-4 0.6704877 -0.7419207 -1.43799e-4 0.6428512 -0.765991 -1.24887e-4 0.5791674 -0.8152087 -5.21866e-5 0.6104251 -0.7920742 4.46271e-4 0.6757889 -0.7370952 -8.84292e-4 0.7019678 -0.7122082 -3.31249e-4 0.6957843 -0.7182508 -1.47439e-4 0.7182696 -0.6957649 -0.002187788 0.8234202 -0.567428 6.60358e-4 0.4885106 -0.8725578 -7.46104e-4 0.4369975 -0.8994624 -0.006519854 0.4699026 -0.8826943 0.003910362 0.5182503 -0.8552201 -6.19509e-4 0.4622488 -0.8867501 4.8703e-4 0.4813684 -0.8765183 -3.42609e-4 0.3773716 -0.9260619 2.88454e-4 0.5729803 -0.8195692 -0.005290746 0.5580245 -0.8298076 7.69868e-4 0.4286101 -0.9034894 4.36799e-4 0.2096844 -0.977769 -4.03443e-7 0.1837977 -0.9829641 -0.001297891 0.162486 -0.9867101 0.001281738 0.7594487 -0.6505659 -0.002674341 0.672931 -0.7397006 4.44603e-5 0.6402437 -0.7681719 4.52127e-4 0.703489 -0.7107061 4.25235e-4 0.7543378 -0.6564864 -0.002397954 0.8084795 -0.5885195 -4.17065e-4 0.8592862 -0.5114951 0.005819439 0.8863778 -0.462926 -8.19971e-5 0.7353252 -0.6777145 5.72563e-4 0.7554709 -0.655182 4.95687e-4 0.00879693 -0.9999613 -0.01843541 0.01720994 -0.999682 -7.85746e-5 0.6699417 -0.7424136 2.68649e-4 0.3960876 -0.9182127 -0.9999457 0.007678389 0.007060229 -4.63888e-6 0.9253176 0.3791931 -3.93789e-6 0.9253181 0.3791919 -7.20196e-4 0.9252909 0.3792574 0.9994646 0.03049284 0.011864 0.999931 0.004242718 0.01095646 1 -3.99911e-5 2.28081e-5 0.1434689 0.9873126 -0.06804776 -0.1167274 0.8874792 0.44582 0.4572918 0.7583069 0.4646018 -0.001026928 0.9253201 0.3791858 -9.63924e-4 0.9252741 0.3792981 -0.3246759 0.338943 0.8830081 -0.9906409 -0.04514241 -0.1288133 -0.9800874 0.004374265 -0.1985184 0 0.7553452 -0.6553272 -0.6221222 -0.5015463 -0.6011783 0.4344703 -0.5769849 -0.6916098 -0.4985188 0.8510445 0.1649313 0 1 0 -1.3205e-7 0.726815 -0.6868333 -0.5816273 -0.5501704 -0.5991846 1.41904e-7 -0.6763399 -0.7365897 -0.5935906 -0.8047672 0 -0.583945 0.8114461 0.0237379 0 1 0 -4.54839e-7 0.702068 -0.7121099 0 0.702068 -0.7121099 -0.104931 0.4597972 0.8818027 -0.5730657 0.8042791 -0.1572612 0 1 0 0 0.6763388 -0.7365908 0 -0.7268161 -0.6868322 0.5489868 -0.6074954 -0.5740757 -0.3717229 -0.9283438 0 -0.6926944 0.6827187 -0.2325292 0 -0.755347 -0.6553251 0.5261471 0.544777 -0.6529834 0.6741361 -0.5579051 -0.4840274 0 0.6406166 -0.767861 -1.37248e-7 0.6406166 -0.7678609 0 -1 0 0 -1 0 0.09841763 -0.1208721 -0.9877774 0.09924358 0.1004518 -0.9899799 -0.6855246 0.3766002 -0.6230798 0.1035452 -0.02194237 -0.9943827 0.1030437 -0.009469449 -0.9946318 0.1172077 -0.01656776 -0.9929692 0.1441478 -0.02634894 -0.9892054 0.1855602 -0.03218412 -0.9821058 0.3919564 -0.06503546 -0.9176822 0.5488422 -0.1380089 -0.824455 0.4814902 -0.1305826 -0.8666692 0.3956016 -0.1088914 -0.9119442 0.2189933 -0.07573372 -0.9727829 0.1356205 -0.01932597 -0.9905724 0.1618469 -0.02224427 -0.9865652 0.1464596 -0.01770234 -0.9890583 0.1453503 -0.005601108 -0.9893644 0.1019766 0.01292216 -0.9947029 0.1047756 0.004776775 -0.9944845 0.1090625 0.002135157 -0.9940327 0.118349 -0.002999365 -0.9929676 0.1168826 0.005554139 -0.9931303 0.1117461 0.01428675 -0.9936342 0.1170989 0.01944041 -0.9929299 0.1345986 0.02563303 -0.9905686 0.3812717 0.1054747 -0.9184264 0.5020439 0.1113043 -0.8576499 0.5098487 0.138673 -0.8490136 0.5212084 0.137359 -0.842303 0.2229526 0.03005486 -0.9743659 0.4827159 0.1243468 -0.8669044 0.1441815 0.01913768 -0.9893662 0.149824 -0.007299602 -0.9886857 0.1660738 -0.002185881 -0.986111 0.1098643 0.02870637 -0.993532 0.1384023 0.01368349 -0.9902817 0.1705296 0.02208393 -0.985105 0.7122298 0.1070765 -0.6937315 0.8558808 0.03317612 -0.516108 0.9008542 -0.2126507 -0.3784725 0.8981674 -0.2770176 -0.3414038 0.8420823 -0.1927202 -0.5037424 0.7488496 0.02664858 -0.662204 0.6032823 0.1411865 -0.7849313 0.4719099 0.08932119 -0.8771104 0.104961 0.004211187 -0.9944674 0.1177142 -0.03088748 -0.9925671 0.1227002 -0.006238877 -0.9924243 0.1202128 -0.009388804 -0.9927037 0.212143 -0.00614506 -0.9772193 0.2348234 -0.0418201 -0.971138 0.3026016 -0.03967332 -0.9522911 0.5837838 -0.07493704 -0.8084435 0.6540808 -0.1078007 -0.7487038 0.8276476 0.06550902 -0.557412 0.3881675 -0.1143274 -0.91447 0.3764843 -0.07926356 -0.923026 0.5390337 -0.09941363 -0.8363968 0.1929319 -0.05201554 -0.9798325 0.1251934 -0.03514176 -0.9915099 0.1202028 -0.03990155 -0.9919472 0.1058155 -0.0279361 -0.9939934 0.1029111 0.01674264 -0.9945496 0.1019464 0.02928757 -0.9943587 0.1410149 0.04904651 -0.9887918 0.1699189 0.06104272 -0.9835656 0.2577884 0.05912142 -0.9643909 0.1288042 0.03115272 -0.9911806 0.8323591 0.2211232 -0.5082154 0.8709127 0.2647773 -0.4140099 0.9020792 0.1018386 -0.4193829 0.8867425 0.1767749 -0.4271281 0.8863236 0.156674 -0.4357566 0.8466157 0.257467 -0.4657819 0.9283788 0.2533431 -0.2719013 0.9591009 0.2231318 -0.1741774 0.9752403 0.212567 -0.061006 0.9793324 0.1813514 -0.08955305 0.9859682 0.1523354 -0.06826877 0.9785742 0.1516383 -0.139278 0.9317755 0.1563367 -0.3276482 0.958595 0.1767735 -0.2232641 0.9428793 0.2743543 -0.1889665 0.9635231 0.2521457 -0.08969914 0.951237 0.2952718 -0.08923417 0.9606788 0.2720135 -0.05572235 0.9900653 0.1041978 -0.09441268 0.9156267 -0.1449341 -0.374996 0.9778348 0.1059076 -0.1806175 0.9886203 0.1009528 -0.1115283 0.9959356 0.007898449 -0.08972251 0.9939303 -0.06042307 -0.09193223 0.9778803 -0.06660288 -0.198278 0.9906738 -0.01620393 -0.1352884 0.9931414 -0.02565932 -0.1140691 0.9893093 -0.1098262 -0.09594446 0.9293167 -0.220175 -0.2964685 0.9179592 -0.2089161 -0.337202 0.9526759 -0.1630038 -0.2565903 0.9790104 -0.1128661 -0.1697056 0.9858858 -0.134936 -0.09910422 0.9756686 -0.1835286 -0.119951 0.9603475 -0.2090389 -0.1844874 0.9683018 -0.2067743 -0.1401285 0.9595546 -0.2716979 -0.07372307 0.9552476 -0.2820305 -0.08922415 0.9554404 -0.2610505 -0.1377916 0.8508961 -0.2393397 -0.4676458 0.8404179 -0.2517159 -0.4799342 0.6977576 -0.09350466 -0.7102052 0.1145831 -0.007619798 -0.9933845 0.1413396 0.1389828 -0.9801566 0.06614977 0.04141563 -0.9969499 0.1209575 -0.01909673 -0.992474 0.2350099 -0.1091511 -0.9658449 0.9854273 -0.1522511 -0.07584697 0.7934853 0.01159954 -0.6084791 0.8145503 0.01120042 -0.5799847 0.9767348 -0.1747995 -0.1242359 0.9576276 -0.1599236 -0.2395285 0.8660314 -0.1691793 -0.4704979 0.8361539 -0.1321557 -0.532336 0.7711642 -0.02932953 -0.6359604 0.8106754 -0.05321067 -0.5830729 0.8830401 -0.1697075 -0.4375382 0.8088091 -0.1350107 -0.5723637 0.4223088 -0.09498906 -0.9014614 0.3234842 -0.1083619 -0.9400084 0.4609842 -0.1043002 -0.8812576 0.2623529 -0.04307693 -0.9640101 0.1567428 -0.03905165 -0.9868672 0.9682676 -0.113959 -0.2224213 0.7870252 -0.07844448 -0.6119133 0.8963818 -0.0393958 -0.4415287 0.8844563 0.04010975 -0.4648963 0.9574384 0.01238089 -0.2883722 0.9480329 0.01036685 -0.3180037 0.9154143 0.03496348 -0.4009914 0.9508841 -0.1068748 -0.2905122 0.9269909 -0.08746236 -0.364744 0.9548546 -0.2211969 -0.1983048 0.963344 -0.240094 -0.1196798 0.8049084 -0.1925066 -0.5613055 0.1431948 -0.0319128 -0.9891799 0.1421392 0.01395922 -0.9897482 0.1529827 0.03279006 -0.9876848 0.7060955 0.0828067 -0.7032583 0.8974952 0.1029587 -0.4288378 0.9689396 0.130397 -0.2101258 0.925309 0.05736398 -0.3748505 0.9513886 0.07153338 -0.2995709 0.9524093 0.07106262 -0.2964233 0.960734 0.07861912 -0.2660999 0.9858855 0.04640895 -0.1608605 0.9889301 0.06690019 -0.1324456 0.3348929 0.05681359 -0.9405419 0.5257856 0.08815312 -0.846037 0.7461625 0.1331814 -0.6523069 0.9497076 -0.04422473 -0.3099995 0.9934684 0.01754504 -0.1127511 0.991941 0.05498766 -0.1141466 0.9908252 0.005781114 -0.1350263 0.154758 -0.05204755 -0.9865806 0.09402775 0.02162778 -0.9953347 0.1032461 0.02152633 -0.9944229 0.9551654 0.2547612 -0.1508502 0.9232354 0.2559784 -0.2865508 0.944454 0.2024267 -0.2589015 0.2615374 0.05885028 -0.9633976 0.2082809 0.05253064 -0.9766574 0.1609046 0.04004168 -0.9861574 0.954995 0.2220911 -0.1966217 0.5806683 0.090034 -0.8091467 -0.9060715 0.2308071 0.3546303 0.2033761 -0.9598444 -0.1932274 0.5206621 -0.1665104 -0.8373682 0.07348632 0.7167661 -0.6934307 1.52418e-5 -0.9999921 -0.004003882 -7.45697e-5 1 -7.67796e-5 6.9598e-4 0.999987 -0.005067467 -0.1521404 0.5260175 -0.836755 0.03405857 -0.6617478 -0.7489526 0.08004426 0.6616736 -0.7455072 0.06804907 0.7280657 -0.6821215 4.52627e-4 -0.9999981 -0.001922309 -0.7120477 0.5157969 -0.4763841 -1.19666e-4 0.9999998 -7.34053e-4 -1.93799e-4 0.9999991 0.001430392 -0.007299244 0.9994847 0.03125822 0.07742518 0.6824065 -0.7268609 0.3123397 -0.9345586 -0.1704234 4.63767e-5 0.9999322 -0.01164895 0.003399729 0.9998761 -0.01537489 -0.505993 -0.8509785 0.1407361 -0.7443696 0.5227186 -0.415547 7.66736e-6 -1 3.61892e-4 0.4718925 0.8816562 0 0.8196222 -0.5173381 0.2461318 0 -1 0 0.5564318 0.7899535 -0.2575989 0.6217889 -0.5912694 -0.5135945 -0.3970131 -0.9149224 -0.07278472 -0.001639306 0.9920767 -0.1256236 -0.8419494 -0.3998817 -0.3622375 -0.9733631 -0.2067161 0.09916013 0.002869904 -0.9996467 -0.02642756 0.001883566 -0.9990711 -0.04305183 0.06115639 -0.6002281 0.7974874 0.0329197 0.7564843 0.6531828 0.7428371 -0.2741881 -0.6107487 0.3132079 0.8134368 0.4901239 0.932703 0.1387891 -0.3328705 0.596409 0.684764 -0.4188013 0.69681 -0.5386471 -0.4736193 0 -1 0 0 -1 0 0 -1 0 0.6306526 0.7760654 0 0.3393875 0.3151057 -0.8862983 0.1781052 -0.4173529 -0.8911202 0.4977166 -0.2433282 -0.832508 0.3663966 -0.2929892 -0.8831257 0.4721271 -0.7957281 -0.3793584 0.4110139 -0.9045825 -0.1131294 0.4525231 -0.8895607 -0.06248849 0.6846957 -0.5784244 -0.4434152 0.9261751 -0.3257316 -0.1899963 0.8261928 -0.5153524 -0.2276348 0.806588 -0.3174385 -0.4986467 0.8878252 -0.4509469 -0.09172552 0.8908186 -0.4457398 -0.08808165 0.4606547 -0.7220602 -0.5161652 0.6738768 -0.6303362 -0.3854432 0.6001749 -0.7205962 -0.3471761 0.1901697 -0.4004699 -0.8963589 0.6940461 -0.7134673 -0.09625196 -0.5482515 -0.8359352 -0.025155 0.2524676 -0.9660999 -0.05395513 0.9407804 -0.3390022 0.003147602 0.8441405 0.5361219 -5.32037e-4 0.284758 0.9568007 -0.0586968 0.08455991 0.2888098 0.9536449 0.3993198 0.5574733 -0.7278512 0.2079591 -0.1016724 -0.972839 0.3569378 0.2652819 -0.8956679 0.3226734 0.3303643 -0.8869845 0.568404 0.6942574 -0.4415016 0.8474094 0.4839543 -0.2183701 0.8146708 0.4738602 -0.3343176 0.7054269 0.5808503 -0.4061846 0.5349134 0.8162729 -0.2180966 0.7811162 0.6191979 -0.08032083 0.9088192 0.4076727 -0.0886051 0.8121438 0.5522987 -0.1881185 0.8764401 0.4698539 -0.1053106 0.4893148 0.8570475 -0.1613715 0.5133693 0.8412047 -0.1697841 0.3755029 0.9216791 -0.09749466 0.4135584 0.9050279 -0.099469 0.3647366 0.928723 -0.06663942 0.7809733 0.3618115 -0.5090907 0.4494622 0.3818159 -0.8075892 0.3119049 -0.07341527 -0.9472727 0.4318661 0.3487221 -0.8317961 0.5638762 0.7151799 -0.4129911 0.7599325 0.5499266 -0.3465307 0.6941645 0.6761203 -0.246976 0.5460098 0.8307781 -0.1080796 -0.717331 0.6905748 0.09242731 -0.9690222 -0.09642982 -0.2273707 -0.9117127 -0.3867263 0.1386463 -0.2333471 -0.9402427 -0.2479779 -0.8279267 -0.5608365 0 7.5227e-4 -0.9999995 -6.39401e-4 0.02509796 -0.999659 0.007216513 1.70121e-4 -1 3.17332e-4 -0.7258284 0.6260363 -0.2850471 -0.7843769 -0.5321816 -0.3186469 0.01868194 -0.9994858 0.0260607 -0.003213763 -0.9999683 0.0072968 0.0014894 -0.9999986 7.97179e-4 -6.05783e-4 -0.9999989 -0.001383483 1.59398e-4 -0.9999997 -7.67339e-4 -0.4819157 -0.8484625 -0.2187892 -0.2272558 0.7665599 -0.6006171 -0.3841535 0.6547552 -0.6509391 0.802043 -0.5091307 -0.3122707 0.9479039 -0.2972658 -0.1145054 -0.4583557 0.8810361 -0.1169846 -0.2478528 0.9687403 -0.01055216 0.826803 0.5596396 0.05657118 -0.02801322 0.09501564 0.9950816 0.4828673 -0.7270786 -0.4880532 0.9300915 -0.3458961 -0.1236356 0.5525426 -0.8334841 0.001038432 0.7807374 -0.6030277 -0.1637281 -0.8687183 0.4145573 -0.2710548 0.6876585 -0.7242041 -0.05152034 -0.140891 -0.9899491 0.01227957 -0.4230317 -0.7037853 0.5707281 -0.123978 0.6633913 0.7379305 -0.3988852 -0.3979822 0.8261361 0.2281172 -0.1642441 0.9596804 0.2380662 0.9712463 0.002248704 -0.583996 0.7785555 0.2297825 0.8788382 0.3119411 0.3610212 0.09462112 -0.9524631 0.2895877 -0.2824971 0.6240108 0.7285643 -0.009391903 -3.71435e-4 0.9999558 -0.0075832 -0.00825721 0.9999372 0 0.04615294 0.9989344 -0.02396404 0.006207644 0.9996936 -0.01013582 0.01395237 0.9998514 -0.01357185 0.01552224 0.9997874 0.9791424 -0.1947681 0.05784159 0.8763749 -0.4814243 0.01406234 0.5547537 -0.8302479 0.05419319 0.2031987 -0.9791328 -0.003061771 0.9782782 0.2065494 0.01758468 0.9632853 0.2630634 0.05365818 0.115267 0.6097149 0.7841947 -0.4213673 -0.9067211 0.01751255 0.05944997 0.1506509 0.9867979 0.1402444 0.02364611 0.9898345 0.1210048 -0.01546937 0.9925314 0.1265832 -0.08458089 0.9883435 -0.03261715 -0.1832217 0.9825305 -0.1127794 -0.1289525 0.9852167 -0.124095 -0.05152761 0.9909316 0.02841448 -0.1591522 0.9868451 -0.7881387 -0.6118375 0.06702584 -0.9896275 -0.06538349 0.1279152 -0.9895908 0.1359069 0.04732221 -0.4530537 0.8877776 0.08120065 -0.2941772 0.9539223 0.05909323 0.2275037 0.9727514 0.04468721 0.8359616 -0.5458101 0.05709362 -0.6448878 -0.2086046 0.7352577 -0.7706512 0.4529448 0.448261 -0.3725314 -0.6787635 0.6328511 -0.379698 -0.8050978 0.4556831 0.01276224 -0.5906823 0.8068033 0.2307719 -0.6042738 0.7626255 0.3354814 -0.5535182 0.7622795 -0.3220407 -0.1237611 0.9386017 -0.291583 0.9262582 0.2388 0.1294164 -0.5539927 0.8224011 0.3254088 -0.1405758 0.9350655 -3.74187e-4 -4.1997e-4 -1 0.003942489 0.02855575 -0.9995845 0.02706027 0.03353726 -0.9990711 0.02919679 0.03068226 -0.9991027 0.005076885 -0.001704633 -0.9999858 -7.98769e-5 0.003184556 -0.9999949 -0.568789 0.8075835 0.1558458 -0.2235892 0.9732624 -0.05261337 0.08908694 -0.9874767 0.1302055 -0.9470242 -0.2843167 0.1493629 -0.9716695 0.2290845 0.05812615 -0.2935021 0.9545428 0.05200606 0.6632092 -0.7451438 0.07010185 0.6148249 0.7881571 0.02826374 0.7327293 -0.6801324 0.02297389 0.2200785 0.04189366 0.9745822 0.1631744 0.1676694 0.9722455 -0.1478003 0.04733926 0.9878837 0.001834809 -0.002567708 0.9999951 0.02016431 8.97101e-4 0.9997963 4.42876e-5 -4.40209e-5 1 0.00484699 0.001318037 0.9999874 0.001316368 -0.002463281 0.9999962 -0.8840043 -0.461479 0.07465761 0.8774801 0.4794379 0.01296132 0.9062741 0.4221581 0.0212078 0.853372 0.5210974 0.01461857 0.8847199 0.4660334 0.009137809 -0.7828685 0.5984898 0.1700792 -0.886744 0.4621784 0.008726179 -0.8867228 0.4622201 0.008681595 0.6912656 0.5707493 0.4431673 -0.8608676 -0.5084632 0.01929217 -0.885321 -0.4639502 0.03093749 -0.9352819 0.3177525 0.1558243 -0.9883207 0.1154114 0.09951084 -0.6431656 -0.7608027 0.08670294 -0.3562489 -0.9304887 0.08530825 -0.3126761 -0.9455929 0.08993202 0.08042633 -0.9925326 0.09171015 0.8247317 -0.5592649 0.08390778 0.9616134 -0.2604069 0.08653426 0.9946974 0.05697119 0.08562421 0.9193733 0.3796092 0.1031972 -0.9350886 0.3362667 0.1119552 -0.7981076 -0.5923841 0.1100257 0.4607886 -0.8826649 0.09260988 0.7672995 -0.6346901 0.09176039 0.2597231 0.9582685 0.1194382 0.4327721 -0.3365742 -0.836317 -0.929404 -0.1109211 -0.3520013 0.02676367 -0.534767 0.8445757 -0.009375929 -0.4010313 0.9160165 -0.002334415 -0.3880215 0.9216474 0.03741526 -0.3030733 0.9522325 0.01334142 -0.2892822 0.9571509 0.9622495 0.2720621 -0.007633566 0.7070492 -0.7070457 -0.01295655 0.008544087 -0.9993301 0.03558909 -0.4804781 -0.8763071 0.03502756 -0.9992341 -0.0314784 0.02324301 -0.7423009 0.6700668 9.62769e-6 0.3350865 0.9421072 0.01229459 0.7367294 -0.6758289 -0.02202433 -0.968946 -0.2459506 -0.02553641 -0.7731055 0.6342271 -0.007999598 -0.06416958 0.5510166 -0.8320235 -0.177407 0.7515967 -0.6353182 -0.322525 0.007249414 -0.9465333 -0.2788132 0.180824 -0.9431681 0.01213705 -0.1722664 -0.9849757 -0.0869168 0.05999249 -0.9944076 0.860894 0.5087278 -0.007603526 -0.8397735 0.5419669 0.03243893 0.7914384 0.6082231 0.06074613 0.675616 -0.7372167 0.007389664 -0.2743464 -0.4580519 -0.845531 -0.8063876 -0.1594159 -0.569496 0.1278595 0.7883915 -0.6017397 0.4143893 -0.7529522 0.5112187 0.2538067 -0.8442664 0.4720131 0.08057188 -0.6924723 0.7169312 0.161619 0.8680333 -0.4694651 0.3473363 -0.429437 0.8336315 0.6758269 -0.7291852 0.1074575 0.7444819 -0.6627109 0.08100104 0.8694804 -0.4850374 0.09350275 0.9204276 -0.3820853 0.08260774 0.7679185 0.6339309 0.09183102 0.5984954 0.7968763 0.08241134 0.3010596 0.950056 0.08220052 -0.3566288 0.9303419 0.08532285 -0.6420168 0.7617741 0.08668822 -0.6560269 0.7495071 0.08870106 0.08088541 0.9924727 0.09195506 -0.3123133 0.9457241 0.08981335 0.2582084 -0.9614717 0.0943436 0.1838403 -0.9744005 0.1294081 -0.4194505 -0.7264434 0.5443726 0.6852322 0.628996 -0.3671799 0.9600496 -0.01089221 -0.2796182 0.1428917 0.2810208 0.9490045 0.4857288 -0.8672586 0.1092253 0.6578151 -0.6986303 -0.2814161 -0.1049138 0.1493107 -0.9832088 0.3682264 -0.929568 0.01768738 0.9657865 -0.2587702 0.01716387 0.6822203 0.7310728 0.01039725 -0.9740282 0.2261806 0.01056593 -0.7600958 -0.6489778 0.03289699 -0.2586746 -0.9653764 0.0337041 0.2586687 -0.9653781 0.03370189 0.2584758 0.9646605 0.05119067 -0.2587888 0.9657784 0.01733833 -0.9657771 0.2587939 0.01732957 -0.9646531 -0.2584957 0.05122923 -6.47092e-4 3.35508e-4 -0.9999998 -8.87658e-4 2.38763e-4 -0.9999997 -5.43602e-4 5.40851e-4 -0.9999997 -0.02689802 -0.1795911 -0.9833736 -0.01887756 0.07048052 -0.9973346 -0.2136685 0.9687344 -0.1260933 -0.3053591 0.9477572 -0.09226232 -0.2893286 0.9535133 -0.08427047 -0.2472199 0.9661002 -0.07438337 -0.1909293 0.9787641 -0.07461196 -0.06192767 0.9957869 -0.06762832 -0.023561 0.9972949 -0.06962817 0.01876038 0.9971585 -0.07295984 0.04779303 0.9965473 -0.06789326 0.06724929 0.9950232 -0.07352924 0.08589941 0.994062 -0.06679862 0.04736387 0.9964094 -0.07017874 0.00978583 0.9973714 -0.07179552 -0.09927362 0.9925986 -0.06994867 -0.1081871 0.9919595 -0.06566607 -0.1649906 0.984137 -0.06521123 -0.1347134 0.9881753 -0.07322555 -0.2218428 0.9728938 -0.06529426 -0.3026003 0.9509279 -0.06457024 -0.2973415 0.9522509 -0.06932693 -0.08144468 0.9939677 -0.0734505 -0.05584257 0.9962218 -0.0665121 -0.006260514 0.9973012 -0.07315206 0.1126889 0.9910164 -0.07202744 0.1426875 0.9870383 -0.07345497 0.1972194 0.9768124 -0.08331853 0.2575824 0.9579645 -0.126314 0.1429394 0.9871279 -0.07174301 0.1270195 0.9896442 -0.0668618 0.1496126 0.9861077 -0.07216578 0.1722272 0.9824952 -0.07099986 0.2254587 0.9719774 -0.0665453 0.2274281 0.9713394 -0.06910991 0.01991826 0.9976482 -0.06558471 0.06692421 0.9955674 -0.06608206 -0.1761014 0.981849 -0.07043385 -0.2933377 0.953407 -0.07048493 0.1116316 0.9915364 -0.06628817 -0.031865 0.9973458 -0.06546854 -0.1089813 0.9912527 -0.07443928 -0.2497708 0.9661506 -0.06455641 0.2413951 0.843602 0.47965 0.009491026 0.3806698 0.9246624 -0.01549279 0.3310451 0.9434878 0.02184963 -0.9662199 -0.2567914 0.1517886 0.528685 0.8351362 0.09880089 -0.05511605 0.9935798 0.007423639 -0.1180359 0.9929817 0.01967453 -0.002021491 0.9998044 3.16502e-4 0.003736674 0.999993 -0.1391596 -0.01804339 0.9901056 -0.09879535 0.04797601 0.9939506 -0.109695 0.005741536 0.9939488 -0.1094455 -0.03964298 0.993202 -0.07805031 -0.07147651 0.9943839 -0.05094659 -0.09774577 0.9939066 0.006407618 0.0122919 0.9999039 0.02067744 0.009519338 0.9997409 0.001663863 0.002277672 0.9999961 -0.09532457 0.02386522 0.9951602 0.4663531 0.8560085 0.2230793 -0.2022522 -0.2472665 -0.9476041 -0.5793671 -0.7919427 0.1927708 -0.5466821 0.4981293 -0.6730571 -0.2817443 -0.6326794 0.7213439 -0.2769262 -0.6438112 0.7133156 0.9989354 0.03016966 0.03489947 0.9989358 0.03015738 0.03489804 -0.1476514 -0.6967304 0.7019729 0.5730268 -0.8187819 0.0351659 0.8196046 -0.5716653 0.03804469 0.9585357 -0.2824653 0.0377202 0.596166 -0.8019804 0.03759807 -0.6055493 -0.3666802 0.7062972 0.6466961 0.7505286 -0.1359816 -0.4194668 0.6194202 0.6636009 0.9989351 -0.03018277 0.03489941 0.9989403 -0.02997833 0.03492254 -0.5070118 -0.8440333 0.1747771 -0.7935987 -0.581354 0.1795235 -0.7935407 -0.5814623 0.1794288 -0.9505707 -0.25572 0.1761329 -0.6794064 -0.729398 0.07990998 -0.6831232 -0.7185543 0.1304701 -0.3585047 -0.9292308 0.08946889 -0.8469097 -0.5228002 0.09707766 -0.6633467 -0.7451032 0.069229 0.7015821 -0.7058475 -0.09778469 0.6296076 -0.09182852 -0.7714673 -0.7031876 -0.6478034 -0.2930496 0.2277525 -0.7936009 -0.5642045 0.3675335 -0.8413377 0.3963207 0.4938195 -0.8442552 0.208268 -0.552887 -0.7055343 0.4433254 -0.8506003 0.4610989 0.2527195 -0.9099724 0.2575735 0.3249709 -0.9332792 0.09912228 0.3452025 -0.9876248 0.1394417 0.0717861 -0.9440616 -0.3105387 0.1109659 -0.9171159 0.3971515 0.03419435 -0.9835476 0.17711 0.03558355 -0.9926546 -0.1159007 0.03469771 -0.9461467 -0.3219325 0.0341438 -0.8494731 -0.5264385 0.0354706 -0.7125452 -0.7008053 0.03393173 -0.5489913 -0.8350693 0.03560942 -0.3556404 -0.9340023 0.03405255 -0.2365677 -0.9708654 0.03815913 -0.08202475 -0.996028 0.03464359 0.1331662 -0.9904148 0.03667908 0.1348145 -0.9901884 0.03677088 0.4299196 -0.9021655 0.03559142 0.4875194 -0.8722981 0.03769719 0.8645079 -0.5014017 0.03496485 0.9262512 -0.3753762 0.03393441 0.772592 -0.6335222 0.041848 -0.3902699 0.9091741 0.1452308 -0.2541621 0.9640026 0.07810693 0.2817536 -0.8919093 -0.353713 -0.571177 -0.8176579 -0.0720601 -0.9107798 0.1717917 0.3754568 0.09454751 0.6540191 -0.7505465 -0.8130371 0.3507094 0.4647297 0.6478455 0.5966331 -0.47363 -0.5187827 0.6673007 0.5343915 0.6044163 -0.2485536 -0.756903 0.02957612 0.9988874 0.03673255 -0.7323656 -2.42019e-4 0.6809117 -0.7309933 0 0.6823846 -0.7348402 0 0.6782404 -0.3661485 0 0.9305564 -0.3424167 -0.007368266 0.9395194 0.3424166 -0.00736916 0.9395194 0.3661469 0 0.9305571 0.8782844 8.06607e-4 0.4781379 0.6072317 0.01262438 0.7944245 0.740864 0.002931892 0.6716488 0.9073321 -0.001624524 0.4204114 0.9713859 -0.002836167 0.2374898 -0.9230493 1.84228e-4 0.3846817 -0.9500472 0.3097525 0.03825736 -0.2219774 -0.326798 0.9186562 -0.9947057 0.08306288 0.06050664 -0.8828991 -0.4675008 0.04395592 -0.8475232 -0.5283467 0.05053997 0.5111215 -0.8488246 0.1350989 0.6112476 -0.04561668 0.7901237 -0.3651214 -0.01986074 0.9307481 -0.3039994 0.06648313 0.9503496 0.3388668 0.8429755 0.4178058 0.3385061 0.842711 0.4186308 0.48665 -0.8105953 -0.3257412 -0.1333199 0.4997793 0.8558309 -0.2721204 0.757032 0.5940145 -0.3375651 0.9326828 0.1270929 -0.2841117 0.9587341 0.01046168 -0.3291834 0.9305267 0.160494 -0.2054262 0.618723 0.7582756 -0.2966274 0.8500049 0.4353207 -0.3345195 0.9174451 0.2153863 -0.3334327 0.9187275 0.2115714 -0.3597195 0.9218324 0.144316 -0.3133201 0.8458751 0.4316549 -0.3022565 0.8188464 0.4879874 -0.270519 0.7645373 0.5850659 -0.2212772 0.541799 0.8108577 -0.338634 0.9207119 0.1939502 -0.1367307 0.4958381 0.8575834 -0.3356267 0.9305266 0.1465435 -0.2348081 0.9118256 0.3368076 -0.07042759 0.8143144 0.5761353 -0.2492101 0.9343234 0.2548218 0.4442474 -0.08896356 0.8914763 -0.4309015 -0.8952642 0.1132522 0.8191468 -0.240328 0.5208082 -0.03200781 -0.620859 0.7832686 -0.4469819 0.8897924 0.09206974 0.09008395 -0.05082607 0.9946365 0.1533793 0.1032075 -0.982763 -0.8412376 0.536017 -0.07074707 -0.9726483 0.2313939 0.02030831 -0.9652343 0.1934549 0.1757782 -0.9846973 0.172515 -0.02469563 0.2093262 -0.3691979 0.9054698 0.0476281 -0.1317821 0.9901339 -0.3420724 0.939486 0.01877886 -0.3406985 0.9400073 0.01763468 -0.4985371 -0.8657121 0.04475909 -0.259934 0.08411598 0.9619558 -0.5761978 0.6740751 0.4621894 -0.966777 -0.2555865 0.004223406 -0.9526703 -0.2961636 0.06860363 0.2208785 0.9710232 0.09125137 0.7014644 0.7124469 0.01916491 -0.325519 0.5827282 0.7446243 -0.03504699 0.07393455 0.9966471 0.4999649 -0.8658679 0.01755052 -0.5149005 0.8561714 0.04299104 -0.5222288 0.4770531 0.7068928 0.9943987 0.003186106 0.1056467 0.05471116 0.1727262 0.9834493 -0.5462906 -0.8371993 -0.02576732 -0.3428492 -0.9392192 0.01793986 0.3197224 0.9435981 0.08602595 0.9425149 -0.3308173 0.04717695 -0.503645 0.8610315 0.07047343 0.8486695 0.5269502 0.04564571 0.1416186 0.3339256 -0.9319002 0.2792898 0.7729745 -0.5696557 0.3198418 0.8874006 -0.3319962 0.3297692 0.934107 -0.1367352 0.2184076 0.5861798 -0.7801868 0.2793007 0.7601013 -0.5867173 0.2977386 0.818257 -0.4917389 0.3391482 0.9322326 -0.1261785 0.3135622 0.8531666 -0.4168758 0.3482928 0.9304454 -0.1138572 0.309999 0.8550682 -0.4156429 0.3102978 0.8513105 -0.4230671 0.2966637 0.8177564 -0.4932194 0.338814 0.926276 -0.1649787 0.3180205 0.8819104 -0.3479903 0.3211832 0.8797746 -0.3504828 0.3354755 0.9162006 -0.2191635 0.07538819 0.6247158 -0.7772046 0.07862848 0.6726564 -0.7357656 0.05023562 0.7814334 -0.6219633 0.2386005 0.896429 -0.3734769 0.09154057 0.9502891 -0.2976089 0.2598517 0.9509667 -0.167749 -0.1503181 -0.4353678 0.8876144 -0.2217726 -0.5177425 0.8262928 -0.3146619 -0.8502894 0.4218956 -0.31626 -0.9371945 0.1471263 -0.09029471 -0.325171 0.9413346 -0.1705575 -0.3642133 0.9155647 -0.2108737 -0.506884 0.8358236 -0.2790471 -0.7462666 0.6043336 -0.3010736 -0.808759 0.5052363 -0.3350851 -0.9320561 0.1378027 -0.3543213 -0.9191843 0.1719208 -0.3747888 -0.924376 0.07115244 -0.3401641 -0.9345971 0.1040041 -0.3604486 -0.921683 0.1434485 -0.3140372 -0.8834184 0.3477824 -0.2254976 -0.4133638 0.8822025 -0.3016293 -0.8518263 0.4282662 -0.3397818 -0.9197976 0.1962668 -0.3276538 -0.9086102 0.2589797 -0.3323526 -0.8823828 0.3330804 -0.3292347 -0.9408634 0.07987892 -0.2843106 -0.799197 0.529577 -0.04603403 -0.7532457 0.6561265 -0.08251821 -0.8517954 0.5173349 -0.1287769 -0.8880054 0.4414327 -0.2015277 -0.9602835 0.192983 0.798688 -0.4390267 -0.4115252 0.8778844 -0.02165818 -0.4783828 0.8446311 0.08895009 -0.5279076 0.6267003 0.07814067 -0.7753328 0.8437836 0.4920765 -0.2142194 0.8269431 0.2321431 -0.5121276 0.5777336 0.743032 -0.3378274 0.4095007 0.7046195 -0.5795002 0.1449018 0.7794254 -0.6095077 -0.8463753 0.3443202 -0.406316 0.2224593 -0.9746838 -0.02243626 0.3753153 -0.9267986 -0.01352179 0.6233466 -0.7816416 -0.02180612 0.5848934 -0.8109735 -0.01489663 0.3718515 -0.9280597 -0.0207774 -0.03502821 -0.9992005 -0.01927363 -0.7031521 -0.7108268 -0.01739436 -0.6394535 -0.7682273 -0.03043407 -0.7700026 -0.6368564 -0.03885895 -0.970366 -0.2393774 -0.03298997 -0.7975498 0.6028318 -0.02254736 -0.8512868 0.5244065 -0.01757323 -0.6919099 0.7217841 -0.01698535 0.163179 0.9865389 -0.01066696 0.3652935 0.9306369 -0.02181106 0.603359 0.7973394 -0.01441681 0.8333296 -0.5525607 -0.01544511 0.987065 0.1590638 -0.02003324 0.6290364 0.7770821 -0.02136754 -0.2293702 0.973082 -0.02237808 -0.4124386 0.9107373 -0.02125883 -0.02719628 0.9993948 -0.02169007 -0.9007257 0.4337679 -0.02321201 -0.8527886 0.5215064 -0.0279811 -0.6233227 -0.7816178 -0.02329403 -0.3149482 -0.9489437 -0.01770639 -0.2224726 -0.9747278 -0.02029341 -0.9732322 0.2263697 -0.03969746 -0.05244535 -0.9976423 -0.0442664 -0.8065845 -0.5905032 -0.02697294 -0.9990246 0.0245763 0.03668785 -0.9989344 0.03045725 0.03467738 -0.9989351 0.03017741 0.03489947 8.61974e-5 0.9993907 0.03490185 -0.4703072 0.1109779 0.8754971 -2.2705e-4 0.9993956 0.03476291 -0.02386254 0.1353299 0.9905132 -0.02725547 0.1505453 0.9882273 -0.1070026 0.6141225 0.7819233 -0.1704084 0.9664308 0.1922828 -0.0786761 0.4376184 0.8957121 -6.3995e-7 1.02785e-6 1 -0.01296192 -0.01876568 0.99974 2.63842e-5 -4.19174e-5 1 -1.60353e-5 0 1 -3.61313e-5 -6.22154e-5 1 1.69748e-7 0 1 -0.01148092 -0.08086061 0.9966593 -3.13413e-5 0.1016706 0.9948181 -0.1704059 -0.9664207 0.1923355 -0.1733816 -0.9711403 0.1637847 -0.154366 -0.8651082 0.4772412 -0.1324299 -0.7546142 0.6426661 -0.1043349 -0.5973919 0.7951335 -0.02211946 -0.1254448 0.9918541 -0.0786758 -0.437618 0.8957123 -0.7914528 0.554584 -0.2569811 -0.4930182 -0.7084409 -0.5050194 0.9637743 0.1558707 -0.2164339 0.3925257 0.8868377 -0.2438085 -0.1752321 0.9611696 0.2131823 0.1637192 -0.8612891 0.4810168 0.8123123 0.5049057 0.2919234 0.1735422 0.9842079 -0.03489911 0.2037271 0.9429207 0.2634309 0.2525148 0.8700992 -0.4232774 0.3380852 0.003906071 -0.9411074 0.2668119 0.9176665 -0.2944482 0.5146928 0.4610311 -0.7228705 0.2876427 0.8461863 -0.4485871 0.2186535 0.9285678 -0.2999206 -0.9942394 0.1012557 0.03514939 -0.9741278 -0.2233083 0.03476136 -0.9241232 -0.3805 0.03487187 -0.6349355 -0.7717215 0.03609561 -0.9463661 0.3209782 0.03693747 -0.6981253 0.7151055 0.03528934 -0.4723173 0.8806215 0.03771227 -0.3128338 0.9491336 0.0357837 -0.07969909 0.9959803 0.04088252 0.3698844 0.9282318 0.03964054 0.03151953 0.9988313 0.03664422 0.8103414 0.5849109 0.03501486 0.8954774 0.4436464 0.03603076 0.9840548 -0.1749595 0.03201919 0.8553437 -0.06073784 -0.5144881 0.7837868 0.4686954 -0.4074347 0.378592 0.9255594 0.002842605 0.610778 0.6492733 -0.4532048 0.1120486 -0.2951115 -0.94887 0.244327 -0.6639353 -0.7067491 0.2592913 -0.7145652 -0.649742 0.3102259 -0.8507802 -0.424185 0.3362364 -0.9264988 -0.1689527 0.3380339 -0.933358 -0.120731 0.3212467 -0.9330215 -0.1620849 0.3392674 -0.9320454 -0.1272361 0.313496 -0.8658595 -0.3898815 0.3002385 -0.8316383 -0.4671559 -0.5584282 -0.819723 -0.1273269 -0.322526 -0.6178762 -0.7170816 0.626514 0.749501 0.2138425 -0.2718825 0.7907604 -0.5484321 0.04024857 -0.8475261 0.5292255 0.8191346 -0.5319483 -0.214592 -0.8380545 -0.4293878 -0.3365868 0.6277864 0.7782971 0.01175194 -0.3268747 0.9388056 0.1086139 -0.0232191 0.1491682 -0.9885392 0.01080858 -0.01075792 -0.9998838 -6.25066e-4 1.67183e-4 -0.9999998 0.956349 0.2920425 0.01039379 0.7069959 -0.7070053 0.01733076 0.2584869 -0.964658 0.05118364 -0.25879 -0.9657782 0.01733106 -0.7061816 -0.7061784 0.05118304 -0.965781 -0.2587788 0.01733738 -0.7069988 0.707002 0.01734495 -0.258485 0.9646579 0.05119413 0.225274 0.97424 0.01040053 0.7310782 -0.6822147 0.010387 -0.7310889 0.6822031 0.01039522 6.99325e-6 2.22624e-6 1 -1.68352e-6 1.08053e-6 1 0.001379072 -0.006176292 0.99998 0.007604837 0.002327322 0.9999685 0.008247554 -0.008380889 0.9999309 -9.03169e-4 -0.003349483 0.999994 -2.84115e-4 2.56857e-4 1 -3.55279e-6 5.70072e-6 1 0 5.98702e-6 1 0.573898 0.008485019 0.8188828 0.3983528 -0.006703138 0.9172079 0.08725899 0.006322979 0.9961656 -0.09742337 -0.007169067 0.9952172 -0.3907352 0.006894528 0.9204773 -0.9168316 3.74528e-4 0.3992741 -0.5170525 -0.003402411 0.855947 -0.4798094 -0.06345969 0.8750748 0.7223194 0 0.6915596 0.7024366 -0.003110527 0.7117395 0.8883665 -0.003979682 0.4591179 0.8756518 0.4563074 0.1581689 0.9605668 0.2544046 0.1122049 0.7769778 -0.6209381 0.1036415 0 -0.9936628 0.1124019 -0.4038323 -0.9070007 0.1194533 -0.737938 -0.6644468 0.1181441 -0.9258333 -0.3621454 0.10809 -0.9620119 -0.2407022 0.1288239 -0.8321173 0.5279784 0.1697635 -0.5466741 0.6356168 -0.5451043 0.8608563 0.1143824 0.4958256 0.4332182 -0.5528537 0.711811 0.7133936 0.7006205 0.01415717 -0.4367557 -0.1786482 0.8816629 -0.2172896 -0.8714281 0.4397708 0.09130924 -0.7894571 0.6069762 0.5827193 -0.5220899 -0.6227844 8.6236e-7 0 1 8.47021e-7 0 1 3.40918e-6 7.89693e-6 1 -0.00143361 0.009696662 0.999952 -0.003660082 -0.003603398 0.9999869 -0.007004976 0.003145396 0.9999706 0.7960888 0.5967959 0.1003869 0.2505049 0.9603129 0.1226642 -0.9736498 0.2022598 0.1053425 -0.9873824 0.1037627 0.1196219 -0.4036681 -0.9066514 0.1226184 -0.1496255 -0.9833377 0.1032437 0.3020006 -0.9484147 0.09646451 0.9862594 0.04336255 0.1594122 -0.9452373 -0.3071346 0.1104307 0.7217012 -0.6753091 0.1520038 -0.7567336 0.6467581 0.09517508 -0.3784697 0.9179046 0.1192141 -0.3648701 0.8268418 -0.4280216 -0.9445496 0.09328693 -0.3148389 -0.3396433 -0.9190564 -0.1999444 0.6245021 -0.7713245 0.1227019 0.9005149 -0.309141 -0.3057854 -0.9834347 0.1590985 -0.08685654 -0.7779229 0.6210277 0.09571063 0.6351358 0.7610518 -0.13192 0.2895371 0.9544063 0.07264286 -0.3093113 0.934865 -0.1742243 0.1431325 0.04804551 -0.9885367 0.1904445 -0.05102926 -0.9803709 0.1956604 -0.05706721 -0.9790099 -0.01444113 -0.08073997 -0.9966306 0.003150522 8.43935e-4 -0.9999947 -0.03000885 0.1119977 -0.9932553 7.94771e-4 0.0029729 -0.9999953 0.003174304 0.003170132 -0.9999899 0.04971218 -0.0497055 -0.997526 0.2584688 0.9646624 0.05118978 0.706996 0.707005 0.01733815 0.9657787 -0.2587876 0.01733875 0.7061855 -0.7061741 0.0511887 0.2920296 -0.956353 0.01038885 -0.9742381 0.2252825 0.01039409 -0.2920197 0.9563559 0.01039731 0.9463226 0.3212661 0.03551965 0.596194 0.8019927 0.03688323 0.3154255 0.9482164 0.03731673 8.77082e-7 1.12586e-6 1 0.004803299 -0.004933714 0.9999763 0.009598731 -0.007907688 0.9999227 0 5.25799e-6 1 0 1.22195e-6 1 -0.4274323 -0.3490724 0.8339365 -0.3772863 -0.6308798 0.6779719 -0.4389187 -0.7339968 0.5182656 -0.2286072 -0.1054474 0.9677911 -0.1614238 -0.3713203 0.9143652 -0.3984185 -0.5305898 0.7481558 0.9594741 -0.2498095 0.1304023 0.9062343 -0.4084079 0.1092827 0.7377173 -0.6642495 0.1206055 0.4039141 -0.9072 0.1176504 -0.737778 -0.6642979 0.119966 -0.9608087 -0.2445929 0.1304651 -0.7648081 0.6334695 0.1174101 -0.3229551 -0.5566385 0.7654107 0.7576966 0.6408509 0.1233134 -0.1822159 0.001897692 0.9832567 0.03592932 -0.2762933 -0.9604016 0.6331249 -0.0750063 -0.770407 5.44988e-7 0 1 0.005913138 1.50699e-4 0.9999825 -0.002429962 9.10485e-4 0.9999967 2.2451e-6 0 1 5.29881e-7 0 1 3.28383e-4 -8.54441e-6 1 0.001618325 0.001128971 0.9999981 -3.15437e-5 2.0389e-5 1 1.98134e-4 5.60294e-5 1 1.07244e-6 2.19757e-7 1 1.60829e-6 0 1 1.07229e-6 -1.46954e-7 1 1.07244e-6 -2.19757e-7 1 -7.82774e-7 0 1 -1.6315e-6 -8.26335e-6 1 1.17381e-6 1.97815e-7 1 1.76104e-6 0 1 2.05455e-6 0 1 8.80464e-7 0 1 1.46727e-6 -1.97815e-7 1 1.46699e-6 -2.75844e-7 1 -0.009464144 -0.001337707 0.9999544 -3.16355e-4 0.001217007 0.9999992 -1.26759e-4 -2.91273e-4 1 -7.4917e-6 -5.64438e-6 1 6.98581e-4 -1.89751e-5 0.9999998 -0.002434432 0.002429068 0.9999941 6.09994e-7 0 1 -0.00150758 -0.004234611 0.99999 -6.47204e-7 0 1 -6.3692e-7 0 1 9.22262e-7 0 1 -1.17199e-6 0 1 -0.02372217 -0.006671428 0.9996963 0.001095294 -0.006682217 0.9999772 4.20229e-4 -5.76516e-6 1 9.22813e-5 6.08917e-4 0.9999998 3.53485e-4 -5.74876e-4 0.9999998 -0.002074122 0.002448618 0.9999949 3.9606e-5 -2.81005e-6 1 0.004383027 7.07039e-4 0.9999902 -0.001224637 -0.001649916 0.9999979 0.005891382 -0.001671731 0.9999814 -0.001835584 0.001053929 0.9999978 -6.81725e-7 0 1 -8.2173e-7 0 1 0.2581176 -0.8113542 -0.5244803 -0.01459127 -0.5936118 -0.8046193 -0.1785072 -0.7580006 -0.6273519 -0.06790655 -0.7050573 -0.7058916 -0.1456876 -0.4032817 -0.9034042 -0.6892023 -0.08888179 -0.7190968 -0.3985742 0.9170679 -0.0111916 -0.6233258 0.7816196 -0.02314609 -0.7381326 0.6745249 -0.01328825 -0.8821951 0.4685028 -0.04729676 -0.7147297 0.6974105 -0.05272793 0.1311115 0.5417655 -0.8302409 -0.900743 0.433778 -0.02233463 -0.7963588 0.6035861 -0.03868484 -0.9407969 -0.3385226 -0.01743048 0.8866492 -0.4620239 -0.01968067 0.1680189 -0.9857231 -0.01093113 0.001364827 -0.9999071 -0.01356792 0.004505038 -0.9997767 -0.02064716 0.3713876 -0.9283731 -0.01395821 0.8976711 -0.4401536 -0.02125203 0.9885395 -0.1503064 -0.01406157 0.9997549 0 -0.02214175 0.9705681 0.2404641 -0.01321309 0.809845 0.5864671 -0.01440954 0.7677713 0.6403675 -0.0213769 -0.2406265 0.9703276 -0.02373445 -0.0971269 0.994199 -0.04620164 0.2224931 0.9748185 -0.01502561 -0.2711579 0.9623048 0.02104741 0.2215226 0.975046 -0.01459306 0.5240741 0.8515354 -0.01529014 -0.6336033 -0.7735652 -0.01198464 -0.9960426 -0.08734488 -0.01643294 -0.9995703 0.02158051 -0.01984256 -0.9911052 -0.1311405 -0.02264648 -0.6233243 -0.7816253 -0.02299726 -0.9989356 -0.03016138 0.03490209 -0.9989351 -0.030182 0.03489941 -0.001570403 -0.9993502 0.03601133 -0.188018 -0.6753133 0.7131628 -0.1735414 -0.9842035 0.03502893 -0.789563 -0.5203251 0.3253496 0.466543 -0.2085089 -0.8595706 0.4744904 -0.2351483 -0.8482713 -7.30978e-7 0 -1 8.1776e-7 0 -1 8.64255e-4 0.001475274 -0.9999986 0 -0.001138329 -0.9999994 -0.003564 0.004948616 -0.9999814 -0.2286747 -0.8725 -0.4318009 0.08815282 -0.3393576 -0.9365178 0.1943229 -0.01715821 -0.9807876 -0.8621519 -0.479348 -0.1640726 -0.9788138 -0.03914982 -0.2009748 0.4884073 -0.8670872 -0.09807294 -0.2135503 0.7349272 0.6436446 -0.861281 0.4439836 0.2471309 0.9879697 -0.1082844 -0.1104105 0.7152103 -0.6955655 0.06828415 -0.0504058 0.05040287 -0.9974562 0.09481239 0.1128613 -0.9890769 0.2734905 -0.07327842 -0.9590795 0.05895555 -0.2200118 -0.9737141 0.07722735 -0.2210885 -0.9721912 9.23173e-4 0.003452122 -0.9999936 0.00235027 0.001781165 -0.9999957 -0.01264804 0.04722231 -0.9988044 0.09423118 0.09423035 -0.9910808 -0.6822149 -0.7310779 0.01039201 -0.7069971 -0.707004 0.01733642 -0.9646596 -0.2584783 0.05119454 -0.9653773 0.2586688 0.03372019 -0.2584857 0.9646575 0.05119651 0.2587789 0.9657809 0.01734244 0.9657835 -0.2587703 0.01733046 0.7061743 -0.706186 0.05117887 0.9423223 -0.3330862 0.03289806 -1.7541e-6 -5.62924e-6 1 0.05815941 -0.06857442 0.9959494 0.003054261 -6.76454e-4 0.9999952 0.08637183 -0.02681475 0.9959021 0.01907998 -0.08031147 0.9965873 0.001200795 0.004076123 0.9999911 0.0082466 -0.002911269 0.9999617 0.001760601 0.006084382 0.99998 0.006329417 9.20364e-4 0.9999796 0.2433931 -0.9219751 -0.3012007 0.2402818 -0.8956609 -0.3742409 0.06136888 -0.8625222 -0.5022844 0.07505863 -0.8177785 -0.5706177 0.150583 -0.7343147 -0.6618963 0.1007038 -0.7435471 -0.6610571 0.149387 -0.7477523 -0.6469544 0.07646429 -0.6502434 -0.7558683 0.06312394 -0.3252077 -0.9435334 -0.965676 0.001071333 -0.2597476 -0.3532912 0.01855713 -0.9353294 -0.3492366 -0.01215946 -0.9369558 0.5217751 -0.005634963 -0.8530646 0.9641959 0.0017367 -0.2651855 -0.9539111 0.2679856 0.1350458 0.2940796 -0.9442026 0.1483199 0.8210217 0.5632001 0.0934295 0.305245 0.9473525 0.09668993 -0.1422591 0.984612 0.1014968 -0.8557996 0.5089131 0.09281468 -0.9945743 0.03671938 0.09733241 -0.2891195 -0.9426396 0.1668552 0.8622498 -0.4769689 0.1703705 -0.7380098 0.6645005 0.1173917 -0.3722474 0.8125283 0.4485864 -0.4869085 0.6748866 0.5544801 -0.3859775 0.6600705 0.6444598 -0.2827639 0.4132739 0.865592 -0.4349532 0.5403697 0.7202892 -0.4313667 0.3555787 0.8291481 -0.4598357 0.2870206 0.8403396 0.4491449 -0.3074089 -0.8389093 -0.1624879 0.3078279 0.9374645 -0.7725804 0.6327942 0.0518769 -0.5159692 0.8415291 0.1600145 -0.523669 0.8255023 0.2105154 -0.3731242 0.9251951 0.06922769 -0.4511864 0.8916782 0.03661978 -0.8902673 0.4057863 0.206789 -0.6873086 -0.4066818 0.6018446 0.1459754 0.7816621 0.6063792 0.5679489 -0.08276784 0.8188917 7.54218e-4 0.4446855 0.8956866 -0.1073327 0.07025122 -0.9917382 -0.4854536 0.6696195 0.5620896 -0.2868402 0.5209049 0.8039781 0.1991922 0.4193595 -0.8856976 -0.9664077 -3.24629e-5 -0.2570143 -0.965911 0.001082539 -0.2588722 -0.01810216 0.9982008 -0.05716264 0.008612155 0.9989315 -0.0454083 0.08524906 0.9935395 -0.07491236 0.9659264 0 -0.2588171 0.8327938 -0.01955372 -0.553238 -0.5953877 -0.05732226 -0.8013911 0.4215816 0.02654188 -0.9064019 -0.4080556 -0.01813459 -0.912777 0.00174117 -0.9986372 -0.05216157 -3.8598e-4 -0.9985401 -0.05401444 1.47302e-4 0.9986448 0.05204325 5.72655e-7 0.9986296 0.0523352 -5.67331e-7 0.9986295 0.05233627 -0.307761 -0.006026268 -0.9514447 -0.05892997 -0.9937232 0.09508794 -0.06031173 -0.9894315 0.1318629 -0.001990258 -0.995166 0.09818804 0.0953598 -0.9902377 0.1016657 0.07374441 -0.9896037 0.1234757 -0.9659413 0.001306891 0.2587582 -0.2292804 0.03864371 0.972593 0.3560187 -0.02734702 0.9340786 7.01291e-4 -0.9986535 0.05187165 1.53669e-4 -0.9986075 0.05275434 -1.54629e-4 -0.9986074 0.05275756 -7.24301e-4 -0.9986544 0.05185502 0.9616952 0.004949986 0.2740766 0.9659265 0 0.2588168 0.7581348 0.05742609 0.6495645 -0.7686711 0.03901845 0.6384533 -0.9650725 5.82765e-4 0.2619828 -0.9659156 -2.21232e-6 -0.2588573 0.01578181 0.9995914 0.02383297 -0.001888513 0.9999662 0.008011341 0.002847969 0.9999855 -0.004570245 -0.003626406 0.999993 -9.69107e-4 0.1814137 0.978242 -0.1006565 0.006355524 0.9999564 -0.006848335 -0.3001779 0.001615881 -0.9538819 -0.302086 0 -0.9532807 -0.280754 0 -0.9597799 -0.2841612 -3.6248e-7 -0.9587766 -0.3484814 1.01984e-4 -0.9373158 -0.3311879 1.06788e-4 -0.9435649 -0.3360095 7.85156e-4 -0.9418584 -0.3510857 -2.52433e-4 -0.9363433 -0.3558823 -0.01903355 -0.934337 -0.3012215 0.00211209 -0.953552 -0.2995752 0.003777444 -0.9540653 -0.2926996 0.002694368 -0.9562007 -0.3366574 0.002433121 -0.9416241 0.003555893 0.9999132 0.01268881 0.008697926 0.9999516 -0.004606246 -0.003299891 0.9999809 0.005243957 0.001244246 0.99996 -0.008862674 0.9521834 0.01230406 0.3052792 0.9579599 0.007393181 0.2868069 0.850403 -0.03373861 0.5250491 -0.242815 0.03964602 0.9692621 -0.6111593 -0.008273482 0.7914645 0.07826888 -0.009149789 0.9968904 -0.9973092 0.00398457 0.0732038 -0.9651019 -0.02029716 0.261087 -0.06421005 -0.0590375 -0.9961887 -0.2722436 0.001712024 -0.9622269 -0.05361706 5.86191e-5 -0.9985616 -0.1044151 -0.1539995 -0.9825384 -0.2732949 -0.03434211 -0.9613171 -0.295122 0.01424288 -0.9553534 -0.04355347 0.1866793 -0.981455 -0.05994653 0.1383227 -0.9885714 -0.0542981 0.05597442 -0.9969547 -0.2808668 0.01339316 -0.9596534 0.9660242 1.64065e-4 -0.2584518 -0.6370043 -0.01218003 -0.770764 -0.7928334 0.001842081 -0.6094357 -8.29602e-4 0.9985993 -0.05290424 -0.001171171 0.9986475 -0.05197954 0.003413677 0.9986712 -0.05142164 1.34285e-4 -0.9986305 -0.05231761 1.88608e-5 -0.998633 -0.05227208 -0.004536747 -0.9987068 -0.05063843 0.9936925 0.007170975 0.1119101 0.825708 8.36852e-5 0.5640977 -0.9611887 0.01598143 0.2754284 -0.9357109 0.03213191 0.3513016 -0.08481442 0.9886768 0.1237931 -0.08386111 0.9883549 0.1269729 -0.06101322 0.9883184 0.1396577 0.3291334 0 0.9442834 0.2506449 -0.07355344 0.9652809 0.1231768 -0.05394405 0.9909176 0.2627178 -0.04757744 0.9636991 0.08963537 -0.1475197 0.9849892 0.7362321 0.005011856 0.6767107 0.4271875 3.4725e-5 0.9041631 0.8133473 0.006860673 0.581738 0.4599286 0.006533265 0.8879319 0.7690091 -0.01372987 0.6390904 0.5168566 -0.008605778 0.8560287 0.7695173 0.02192521 0.6382497 0.9873703 -0.002344787 0.158412 0.1400768 0.1101635 0.9839932 0.08467704 0.1219379 0.9889191 0.2653396 0.02924668 0.9637113 0.03477323 0.2226102 0.9742872 0.1088363 0.1377542 0.9844687 0.275266 0.007967114 0.9613351 0.07076913 0.03109461 0.997008 0.09837353 0.3153584 -0.9438601 0 0 1 0.5972415 -0.3804132 0.706108 -0.3570777 0.9105616 -0.2082621 -0.4664899 0.8477829 -0.2522926 -0.4466448 0.860845 -0.2438324 0.0280736 0.1821503 -0.9828699 0.06205755 0.04574447 -0.9970237 0.03666257 0.1063768 -0.9936497 0.03292202 0.2150022 -0.9760586 -0.3797323 0.8481503 -0.369384 -0.1083685 0.7292886 -0.6755697 -0.392189 0.8336833 -0.3887931 -0.4565055 0.8491274 -0.2656794 -0.4459235 -0.842262 -0.3028978 -0.4671321 -0.8573763 -0.2160866 -0.1871727 -0.7625179 -0.6193004 -0.09779834 -0.7447919 -0.6600914 0.04408043 -0.1392264 -0.9892791 0.1023621 -0.1101095 -0.9886344 0.02380394 -0.2637004 -0.9643109 0.07614529 -0.1205917 -0.9897776 0.08622509 -0.07652723 -0.9933322 0.02506184 -0.2190276 -0.9753968 0.2384756 0.8945781 0.3779674 -0.4829572 -0.8365097 -0.2588513 -0.02180838 -0.03777432 0.9990483 0.03311753 0.03976285 0.9986603 0.4806189 0.8383437 0.2572653 0.4829625 0.8365166 0.2588191 0.476467 0.8394576 0.2613241 0.6614974 0.7477844 0.05691856 0.6649761 0.7445228 0.05909883 -0.07715773 0.08077764 0.9937413 -0.1442018 0.02186816 0.9893068 -0.03736555 0.1613144 0.9861955 -0.09366422 0.1006032 0.990508 -0.08027672 0.1201323 0.9895069 -0.02348035 0.2749713 0.9611657 -0.04703557 0.2888347 0.956223 -0.04621726 0.2897208 0.9559947 -0.07136529 -0.0811609 0.9941428 -0.01271355 -0.1552271 0.9877971 -0.07927751 -0.07615578 0.9939393 -0.08733153 -0.1097912 0.9901107 -0.04710912 -0.2886977 0.9562607 -0.0234493 -0.2750343 0.9611484 -0.02666538 -0.08439415 0.9960756 -0.04994863 -0.1334033 0.9898024 -0.02536219 -0.1922945 0.9810094 0.2403112 -0.7184832 0.6527116 0.6003589 -0.7996617 -0.01051563 0.3189088 -0.8042373 0.5014976 0.03311777 -0.03976303 0.9986602 0.4829632 -0.836516 0.2588197 0.4829636 -0.8365157 0.2588198 -0.4829639 0.8365159 -0.2588191 -0.2546671 0.9488986 -0.1863766 -0.1178377 0.9672426 -0.2248465 -2.58152e-4 0.004967331 0.9999876 5.01e-4 -0.00231564 0.9999972 -0.002636849 -0.001587212 0.9999954 -0.6798949 -0.7314189 -0.052625 -0.9608165 -0.2473324 -0.1251336 -0.7152253 -0.6979998 0.03534215 -0.3484299 -0.9293211 -0.1223064 -0.8373911 0.5268596 0.1455862 0.9738624 -0.1480352 -0.1722722 -0.7672758 -0.6351783 0.08852428 -0.8771894 -0.4801445 -2.80555e-4 -0.7700664 -0.6350088 0.06133383 -0.4353886 -0.7077431 -0.5563602 -0.3113876 -0.946617 -0.08339118 -0.347591 0.9343571 -0.07846939 0.5429841 0.8392857 0.02771025 0.9973478 -0.07024765 0.01904624 0.7906548 -0.6024034 -0.1094313 0.5408936 -0.8406375 -0.02762287 0.004407167 -0.002294719 0.9999877 -0.6280776 0.3270253 0.7060971 -0.9323501 0.361557 2.19049e-6 -9.0992e-6 -1.09027e-5 1 -1.38203e-7 0 1 -1.24053e-7 -2.75805e-6 1 -5.16085e-7 -2.41141e-6 1 -1.39635e-7 -9.90949e-7 1 -2.52779e-7 -8.83354e-7 1 0 -7.92716e-7 1 -3.11795e-7 -2.63388e-6 1 -5.63538e-7 -2.59234e-6 1 0.9809724 0.1941474 -2.34532e-7 0.3569129 -0.1587842 0.9205438 -0.06764221 0.3370336 0.9390596 -0.4387957 -0.8476156 0.2983389 -0.9632624 0.2554333 0.082942 -0.9872804 -0.1314183 0.0894801 0.212537 -0.9721328 0.0989238 0.9978244 0.004966795 0.06574165 -0.009799897 0.9956191 0.09298735 -0.3884039 0.9167719 0.09312212 0.9607438 0.2543365 0.1108347 0.4049174 0.9094485 0.0945807 -0.81773 -0.5679246 0.09369933 0.003122508 2.47762e-6 0.9999951 0.7948666 -0.3636878 0.4857144 0.9813553 -0.1922029 2.20143e-4 0.9809723 -0.1941482 0 -1.20414e-4 -5.84077e-4 0.9999999 -1.06895e-4 -6.09681e-4 0.9999999 -1.44343e-4 5.85786e-4 0.9999998 9.74686e-7 1.04188e-5 1 1.60135e-7 1.59985e-5 1 -3.77009e-7 1.62245e-5 1 -5.14981e-6 -5.25306e-6 1 -3.19983e-6 -0.002663791 0.9999965 2.33106e-5 8.78077e-5 1 0 0 1 1.19426e-7 0 1 0 0 1 2.7426e-6 -8.69133e-6 1 -2.1515e-6 1.57748e-5 1 1.35704e-7 0 1 3.89473e-5 -1.76655e-4 1 4.11366e-5 -1.56985e-4 1 -0.9323584 -0.3615356 1.18884e-5 -0.9323356 -0.3615943 4.79848e-6 -0.8026457 -0.3112391 0.5088127 -0.628076 -0.3270289 0.7060967 -0.6280779 -0.3270243 0.7060973 0.5882109 0.8078969 -0.03620493 0.04175281 0.1147155 0.9925206 0.04205691 0.115344 0.9924349 -0.5145182 0.4591193 0.7242103 -7.48349e-4 0.00433278 0.9999904 -0.9366429 0.3502845 0.001026749 0.3343613 -0.9375395 0.09603208 0.1879076 -0.9821866 -7.0407e-4 0.7925298 -0.5688862 -0.2196934 0.3360289 0.9343636 0.1185297 -0.0859068 0.9897469 -0.1141105 0.05950695 -0.998228 -2.07714e-4 0.919471 -0.04191744 0.3909168 -0.06792694 -0.9976903 -3.30416e-4 -0.06754648 -0.9977161 -5.15819e-4 0.4719849 -0.8294943 0.2986125 0.7869267 0.5907189 -0.178319 0.1809297 0.887819 0.4231334 0.7461466 0.09963142 -0.6582848 0.702642 -9.94201e-4 -0.7115429 0.3201215 -0.01508992 -0.9472563 0.204268 -0.9361978 -0.2860216 0.2691371 -0.9145944 -0.3017984 0.2401928 -0.8768573 -0.4164477 0.5691574 -0.7163313 -0.403645 -0.2064461 -0.1724579 0.9631398 -0.01598155 0.06101387 0.998009 -0.6546977 -0.2711233 0.7055941 -0.5150678 -0.4577044 0.7247151 0.04237329 -0.1164196 0.9922958 0.6753244 0.2129864 0.7060976 -0.02288562 0.08541452 -0.9960827 0.03455883 0.05339097 -0.9979755 -0.05904483 -0.03512114 -0.9976373 -0.03782987 0.02545338 -0.99896 0.005481779 -0.01084107 -0.9999262 0.6529164 0.1013392 -0.7506203 0.9677473 0.2519016 0.003274977 0.9610213 -0.02550917 -0.2752951 -0.2984691 0.9473962 0.1155709 -0.2977868 0.947645 0.1152918 -0.5477464 0.7881385 0.2807344 -0.7464089 -0.5003371 0.4387901 -0.5610965 -0.7714638 0.3000242 -0.3273315 -0.9363124 0.1271741 -0.8472635 4.34738e-4 0.5311728 0.8489003 -0.03976607 -0.527055 0.20193 -0.0419293 -0.978502 0.1285733 -0.004116833 -0.9916915 -0.07176321 0 -0.9974218 0.1050255 0.003960013 -0.9944617 0.3514713 -0.03253358 -0.9356333 0.6293735 -0.0573095 -0.7749869 -0.998229 -0.03376531 0.04897838 -0.02536243 0 0.9996784 0.2091034 0.03728169 0.9771826 -0.2781693 -0.06828016 0.9581022 -0.7945637 -0.0870285 0.6009116 -0.3387112 -0.05909764 0.9390327 -0.6585475 -0.6877097 0.3055662 -0.1455345 -0.9654932 -0.215969 -0.06489169 0.9944354 -0.08298957 0.8464345 -0.02491706 -0.5319096 0.7708563 0.4522866 -0.4485729 0.02397531 0.1359652 -0.9904235 0.07787233 0.4448089 -0.8922338 0.164533 0.9237521 -0.3458481 0.097539 0.5384619 -0.8369858 0.1436168 -0.7934938 -0.5913897 0.1471667 -0.8091298 -0.5689033 0.1633462 -0.9191088 -0.3585488 0.1734896 -0.9597054 -0.2210588 0.1733279 -0.98418 -0.03670483 0.8501113 -0.05393153 -0.5238344 0.7216938 -0.5613455 -0.4050301 0.3291409 -0.9344171 -0.1361288 0.7673494 -0.4558599 -0.4509622 0.587597 -0.7413669 -0.324199 0.3686383 -0.9294057 0.01763135 0.7061832 -0.7061765 0.0511862 0.9657794 -0.2587853 0.0173341 -0.9563893 -0.2919094 0.01041507 -0.3331209 -0.9423098 0.0329073 0.2586672 -0.9653783 0.03370839 0.9653762 0.2586748 0.03370642 -0.9646615 0.2584714 0.05119377 -0.258779 -0.9657813 0.0173254 -0.3889389 -0.2965456 0.8722313 -0.5246409 -0.8437297 0.113456 -0.6853847 -0.7252126 0.06568539 -0.8617208 -0.4975057 0.0996263 -0.9766336 -0.2018411 0.07380467 -0.9465168 0.307541 0.09759408 -0.8714661 0.4868037 0.05974143 0.3222514 0.9397375 0.1142262 0.7561419 0.6462939 0.1027311 0.9769471 0.2117291 0.02730023 0.7734978 -0.6312175 0.05714738 0.2185611 -0.9695213 0.110723 -0.157008 -0.9856935 0.06129395 -0.3187312 0.6402685 0.698904 -0.3277904 0.7556861 0.5670027 -0.1867257 0.1203494 0.9750126 -0.2438053 0.4019055 0.8826273 -0.7212061 0.6927206 0 -0.7882319 0.5719413 -0.2270989 -0.6725014 -0.7400959 0 0.2329516 -0.9693461 0.07811427 0.9800344 -0.1083452 -0.1667153 0.2804423 0.9598709 0 -0.7546696 -0.6139175 0.2314719 -0.2559623 -0.6534351 0.7123945 -0.2760983 -0.6187065 0.735508 -0.07901227 -0.1035249 0.9914836 -0.1027545 0.03612357 0.9940507 -0.1016195 0.03301733 0.9942753 0.07112067 -0.06592082 0.9952871 0.04505515 0.1012005 0.9938453 0.03503298 0.09911435 0.9944593 0 0.113725 0.9935123 -0.04405546 0.09894841 0.9941169 0.09590953 0.02926039 0.9949599 -0.1130602 -0.0145837 0.9934811 5.13171e-5 -1.26487e-5 -1 -0.01120561 -0.003000855 -0.9999327 -0.003379702 -0.01262068 -0.9999147 0.0179587 0.004812121 -0.9998272 0.009936392 0.01209217 -0.9998776 0.01336652 0.02532166 -0.99959 0.001034379 -0.002953767 -0.9999952 0.001666963 5.37608e-4 -0.9999985 -6.45387e-4 0.00106275 -0.9999992 -9.04754e-4 0.001158595 -0.999999 0.001940488 3.49931e-4 -0.9999982 1.83089e-5 -4.17534e-5 -1 0.252433 -0.1443381 -0.9567884 0.2955002 0.1345798 -0.945816 0.3670947 0.1536249 -0.9174099 0.2586794 0.9653748 0.03371185 0.7067062 0.7067035 0.03371155 0.7067047 0.7067049 0.03371268 0.9826174 0.1827024 0.03290808 0.9657799 0.2587834 0.01733797 0.9646587 -0.2584829 0.05118846 0.7067136 -0.7066963 0.03371065 0.2587819 -0.9657802 0.01733791 -0.258472 -0.9646616 0.05118846 -0.9646579 -0.2584859 0.05118846 -0.965786 0.2587599 0.01733905 -0.706179 0.7061806 0.05118834 0.2586792 0.965375 0.03371196 0.7839698 -0.6205486 0.01763224 -0.9742363 0.2252899 0.01039415 -0.3493533 -0.9358305 0.04662042 -0.9644678 -0.2550076 0.06908822 0.2614001 0.9627553 0.06908184 0.682285 0.7310777 -0.003551542 0.989214 -0.1454132 0.01762515 0.2584855 -0.9646539 0.05126589 -0.06157904 -0.09474545 0.9935951 -0.06814873 -0.07273745 0.9950202 -0.1013736 0.01489472 0.994737 -0.08276814 0.07452625 0.9937783 0.1050283 -0.0605852 0.992622 0.09109699 -0.02135342 0.9956132 0.02699619 0.1007463 0.9945458 -0.07644975 0.07644635 0.9941385 -0.02620822 0.09780681 0.9948603 0.03046709 -0.09827595 0.9946928 0.02460587 -0.1106467 0.9935552 0.107428 -0.9941746 -0.008726418 -0.9980581 0.06173187 -0.008333206 0.1053297 0.9943991 -0.008726477 0.1053321 0.9943989 -0.008726119 0.9979535 0.06329315 -0.009109139 0.998435 -0.05340582 -0.01659494 0.9980725 -0.06138736 -0.009107887 0.001606523 -0.001100301 -0.9999982 -1.39345e-4 0.001331388 -0.9999991 0.8147679 0.5796886 -0.01069742 -0.5735564 0.8191196 -0.008728921 -0.8191179 -0.5735589 -0.008723974 -0.4999795 -0.8659933 -0.008727192 -0.8656519 0.5005743 -0.008502185 -0.8659927 0.4999807 -0.008725583 -3.63811e-6 0 -1 -0.8659892 0.4999867 -0.008724629 0.49998 0.8659931 -0.008723914 0.8659875 -0.4999895 -0.00872761 0.8193771 0.5731906 -0.008604824 0.5735564 -0.8191196 -0.00872302 0.5735552 -0.8191205 -0.008727014 -0.5735554 0.8191203 -0.008727669 -0.8191233 -0.5735513 -0.008725464 0.9484987 -0.3166608 -0.008727073 0.948499 -0.3166604 -0.008725941 0.9484989 -0.3166604 -0.008726119 -0.3166601 -0.948499 -0.008727371 -0.9485261 0.316576 -0.00883615 -5.82094e-6 0 -1 1.63714e-6 0 -1 0.9888493 -0.148668 -0.0086658 0.7494999 -0.6617386 -0.01876175 -0.8701225 0.4843872 -0.09086292 -0.9887985 0.1490005 -0.008744001 0.1471441 0.9890767 -0.008725106 6.86696e-5 -0.004546463 -0.9999897 -0.02201211 0.2125847 -0.9768947 -0.3481108 3.72083e-4 0.9374534 -0.32839 -2.95699e-4 0.9445422 -0.3149524 -0.003724157 0.9491003 -0.3019146 -4.15666e-4 0.9533349 -0.3527211 -3.50888e-4 0.9357284 -0.4186628 2.4285e-4 0.9081419 -0.4708715 -4.72533e-4 0.8822018 -0.7678537 8.25168e-4 0.6406248 -0.8726184 -8.10031e-4 0.4884021 -0.8448583 6.2264e-4 0.5349899 -0.6092803 3.73091e-4 0.7929549 -0.5582097 -3.82394e-4 0.8296998 -0.5087438 -3.04765e-4 0.8609179 -0.4654338 5.8051e-4 0.8850826 -0.4586456 -3.80723e-4 0.8886193 -0.3225759 0.001000583 0.9465432 -0.3094021 0.001379668 0.9509304 -0.08489155 -0.003715217 0.9963833 -0.09112471 -8.75529e-4 0.9958391 -0.1266822 -3.92405e-4 0.9919433 -0.1312654 4.42395e-4 0.9913472 -0.1382665 3.12446e-4 0.9903951 -0.1312628 -4.48306e-4 0.9913475 -0.1185164 -5.77143e-4 0.9929519 -0.1186352 3.93998e-4 0.9929379 -0.1766708 -3.57526e-4 0.98427 -0.1894624 4.94115e-4 0.9818879 -0.2016136 0.00127083 0.9794644 -0.2870142 -0.001074969 0.9579257 -0.2859625 0.00102961 0.9582403 -0.2788609 3.62225e-4 0.9603315 -0.2382258 2.75747e-4 0.9712098 -0.8233851 8.9849e-4 0.5674822 -0.8722772 8.42757e-4 0.4890111 -0.9111886 7.38653e-4 0.411989 -0.9394536 -4.1215e-4 0.3426759 -0.9212797 -4.84005e-4 0.3889007 -0.9649364 0.001609802 0.2624794 -0.9743286 -7.65591e-4 0.2251297 -0.981119 -8.56286e-4 0.1934038 -0.9743266 7.66087e-4 0.2251382 -0.7103667 -6.69206e-4 0.7038315 -0.6301116 -0.003819942 0.7764952 -0.6127669 -6.68838e-4 0.7902635 -0.6667653 8.15224e-4 0.7452673 -0.6686611 3.30804e-4 0.7435673 -0.1896355 -4.60339e-4 0.9818544 -0.1810887 6.40275e-4 0.9834666 -0.1821871 -5.18144e-4 0.9832638 -0.1696247 7.66631e-4 0.9855085 -0.2044439 -3.87638e-4 0.9788783 -0.1050941 -4.54444e-4 0.9944623 -0.1984855 6.62273e-4 0.9801036 -0.2165964 -4.48364e-4 0.9762611 -4.28839e-4 -0.04999691 -0.9987494 -1.34744e-4 -0.06867945 -0.9976388 0.001776456 -0.08409011 -0.9964566 -2.41722e-4 -0.1218445 -0.9925492 3.11483e-4 -0.11797 -0.9930171 0.003992676 -0.1285493 -0.9916952 6.59052e-4 -0.1715689 -0.9851719 0.001609742 -0.2460117 -0.9692655 -3.26413e-4 -0.2705761 -0.9626986 -0.001187562 -0.2763898 -0.961045 -2.48855e-4 -0.1723853 -0.9850296 2.23577e-4 -0.144482 -0.9895074 0.01164096 -0.2122076 -0.9771553 0.005221724 -0.2482396 -0.9686846 0.02881449 -0.1246151 -0.9917867 2.16206e-5 -0.2845984 -0.9586469 0.009311914 -0.3045496 -0.952451 -0.0024423 -0.3248128 -0.9457753 -0.004311382 -0.3737629 -0.9275143 -0.004871606 -0.4456866 -0.8951758 0.02216422 -0.6392405 -0.7686874 -0.002011954 -0.6447281 -0.7644094 0.001125693 -0.3663625 -0.9304715 0.004245698 -0.4750602 -0.8799431 0.02704948 -0.5531466 -0.8326447 0.1713255 -0.510464 -0.8426591 -6.00677e-4 -0.5773482 -0.8164979 0.008150279 -0.801417 -0.5980505 -0.005381464 -0.776421 -0.6301916 -3.24728e-5 -0.7461568 -0.6657704 -0.002479255 -0.730202 -0.683227 0.002475559 -0.6945484 -0.7194418 -0.001164197 -0.6729274 -0.7397077 -2.23456e-4 -0.6640552 -0.7476836 -3.46482e-4 -0.639348 -0.7689175 7.48517e-5 -0.6340634 -0.7732811 -0.008400619 -0.578989 -0.8152922 0.02302032 -0.5792936 -0.8147939 -0.002816021 -0.4570426 -0.8894404 -0.003615856 -0.5960866 -0.8029121 0.001007616 -0.4269592 -0.9042704 0.01614105 -0.4680244 -0.8835681 3.40497e-6 -0.4942206 -0.8693366 0.001023113 -0.4953984 -0.8686654 -9.9359e-4 -0.550328 -0.8349481 -0.001113355 -0.5674369 -0.8234162 -4.02935e-4 -0.5021225 -0.8647965 2.94892e-6 -0.5377381 -0.8431119 0.002558708 -0.5945179 -0.8040783 -0.01618802 -0.5612223 -0.8275068 3.82999e-4 -0.5886148 -0.8084136 6.36835e-5 -0.6311205 -0.7756849 -3.54436e-5 -0.6832096 -0.7302224 -7.8091e-4 -0.7636056 -0.6456826 -0.002066612 -0.7688763 -0.6393943 5.69739e-4 -0.8131295 -0.5820826 0.005384385 -0.5604234 -0.8281888 9.89267e-4 -0.5841324 -0.8116579 -6.1516e-4 -0.5896764 -0.8076395 3.9699e-5 -0.6455062 -0.7637552 7.36799e-4 -0.6012108 -0.7990902 0.001171112 -0.3277265 -0.944772 -1.52646e-5 -0.1739299 -0.9847581 -2.90307e-4 -0.15053 -0.9886054 -0.001208961 -0.1447304 -0.9894704 6.07137e-5 -0.1293569 -0.9915982 -0.001259446 -0.1055613 -0.9944121 3.39603e-4 -0.09725463 -0.9952595 -6.04371e-4 -0.07646298 -0.9970723 -0.01439416 -0.4852231 -0.874272 0.003169834 -0.7390197 -0.6736764 0.01001203 -0.402024 -0.9155745 0.003968179 -0.3789876 -0.9253933 0.003221571 -0.4140924 -0.9102293 0.02726686 -0.6093244 -0.7924521 -0.004214107 -0.5324125 -0.8464747 4.92719e-4 -0.3782387 -0.9257079 0.001663386 -0.4806619 -0.8769044 -0.007480859 -0.626235 -0.7795985 0.02511912 -0.5878546 -0.8085765 -0.0717594 -0.4731777 -0.8780396 -0.02188462 -0.2494989 -0.9681279 0.04289025 -0.4625663 -0.8855468 0.009412288 -0.3509174 -0.9363591 3.77464e-4 -0.2751733 -0.9613946 -0.01046365 -0.6715283 -0.740905 3.32306e-4 -0.1427016 -0.9897658 0.001941442 -0.1353263 -0.9907992 6.68348e-5 -0.1744555 -0.9846651 -6.56387e-4 -0.1914229 -0.9815075 -4.14626e-5 -0.2372267 -0.9714543 0.002253115 -0.2444655 -0.9696554 2.15403e-4 -0.168828 -0.9856456 0.001010894 -0.1208925 -0.9926651 -0.01447468 -0.132906 -0.991023 0.009433865 -0.1896801 -0.9818007 1.67152e-4 -0.3830254 -0.9237378 -3.87927e-4 -0.363923 -0.931429 1.57864e-4 -0.2638495 -0.9645639 1.00282e-4 -0.2376049 -0.9713619 -1.08445e-4 -0.216392 -0.9763066 5.58018e-4 -0.2839586 -0.9588364 -3.62918e-5 -0.2397838 -0.9708263 -1.60943e-4 -0.4336367 -0.9010878 0.0285778 0.4473897 0.8938824 0.01637506 0.5135906 0.8578791 -0.001319229 0.6057138 0.7956815 -0.007707297 0.8059334 0.591956 0.002813518 0.7601616 0.649728 2.62913e-4 0.7108818 0.7033115 -0.01371783 0.6371082 0.7706524 4.80183e-4 0.4176696 0.9085988 1.5178e-5 0.4023434 0.9154889 -6.94165e-4 0.4189726 0.9079986 -6.45571e-4 0.4765843 0.8791285 6.54303e-4 0.6371291 0.7707569 -1.28296e-4 0.6037759 0.7971542 7.04032e-5 0.5744514 0.8185387 -2.99917e-4 0.5634097 0.8261776 -5.80166e-4 0.5326653 0.8463258 3.01947e-4 0.3627982 0.9318678 5.02954e-4 0.2771361 0.9608306 -4.48309e-4 0.313549 0.949572 -3.59928e-4 0.1773659 0.9841449 -0.009043395 0.1730912 0.9848643 -0.01199871 0.2127097 0.9770419 -0.008146882 0.2670565 0.9636465 -0.005413651 0.3106569 0.9505068 0.005081832 0.262245 0.964988 0.01082116 0.2563458 0.9665247 0.1194217 0.299319 0.9466503 -0.01858007 0.3459432 0.9380715 1.07546e-4 0.5996955 0.8002283 -0.002135574 0.3980095 0.9173788 0.02708506 0.3870354 0.921667 -0.02223163 0.4868088 0.8732256 0.05951821 0.4751058 0.8779135 -0.04848355 0.595403 0.801963 0.09149366 0.6080265 0.7886272 -6.53997e-4 -0.6553069 -0.7553626 0.003724992 0.6164476 0.7873872 -3.25049e-4 0.6736245 0.7390738 -0.01155519 0.5994227 0.8003493 -0.01029384 0.4394557 0.8982053 0.01015698 0.5073823 0.8616612 0.006887197 0.3637952 0.9314535 -0.00162357 0.2226067 0.9749071 0 0.01853269 0.9998283 1.98553e-4 0.0359534 0.9993535 -1.06448e-4 0.051113 0.9986929 -6.70645e-5 0.07634013 0.9970819 -5.14655e-5 0.07671016 0.9970535 1.33874e-4 0.1132328 0.9935685 2.10576e-4 0.1454444 0.9893665 7.19034e-4 0.1058907 0.9943776 -6.08098e-4 0.2626662 0.9648866 -6.16152e-4 0.5883545 0.808603 -6.95483e-4 0.8157161 0.5784522 7.1659e-4 0.8662239 0.4996557 0.01569664 0.8915752 0.4526005 -0.03735482 0.9573571 0.2864826 -0.001008808 0.7342075 0.6789245 -2.83844e-4 0.01739871 0.9998486 -7.21894e-7 -0.999962 -0.008725821 1.68797e-6 -0.999962 -0.008727252 -0.2706557 -0.1356466 -0.9530717 5.86003e-4 0 -0.9999999 0.006199538 -0.001872003 -0.9999791 -1.01065e-6 -0.999962 -0.008725821 2.24259e-6 -0.999962 -0.008727073 0.9999619 0 -0.008726179 0.999962 1.30666e-6 -0.008724272 2.09699e-7 0.9999619 -0.008726179 0.007759928 -0.02928817 -0.9995409 0.001901388 0 -0.9999982 -0.006472289 0.001872062 -0.9999773 0.001901388 0.001871943 -0.9999966 0.008134484 -0.02928733 -0.999538 -0.999962 -3.37116e-6 -0.00872606 -0.9999619 2.2138e-7 -0.008728325 0.4207023 -0.2116145 -0.8821728 4.21728e-7 -0.999962 -0.008726656 -0.9999617 0 -0.008746683 -0.9999619 -1.08218e-4 -0.00872749 -4.76493e-6 0.999962 -0.008725702 -0.9999231 0.007648646 -0.009764194 -0.9999217 0.007646441 -0.00989902 -2.44462e-5 0.999962 -0.008727908 -3.06836e-6 0.9999619 -0.008736848 -0.9999619 9.32718e-6 -0.008732855 -0.999962 0 -0.008726537 1.78566e-4 0.9999613 -0.008792281 -1.44454e-5 -0.9999616 -0.008771598 0.9999558 -0.002811729 -0.008967936 0.9999617 0 -0.008758902 -1.43794e-7 0.999962 -0.008725941 -2.03022e-6 0.9999619 -0.008726894 0.999962 0 -0.008726537 -0.5197011 -0.8537048 0.03315383 -0.5877259 0.8076317 -0.04805493 -0.4354146 0.8983163 -0.05866879 0.5233754 -0.8460115 -0.1017 -0.9986854 0.04483729 -0.02483946 -0.1268879 -0.9893455 -0.07138001 -0.2593703 -0.9654163 -0.02642667 -0.999962 -1.59291e-6 -0.008726418 -0.9992201 -0.03933829 0.003410696 -0.9998294 0.01654577 0.008209586 -0.01045781 -0.9996122 -0.02580916 0.9988674 -0.04583561 -0.01277124 0.9777622 0.2038536 -0.04924106 -0.3312345 -6.17965e-7 -0.9435485 0.4647545 -0.6391315 -0.6127921 0.2321934 0.9685999 0.08888572 0.197772 0.9761939 0.08906137 0.1682967 0.9820234 0.08547663 0.1386768 0.9863595 0.08867758 0.1210321 0.9886863 0.08860433 0.1389333 0.9865915 0.08564358 0.1268575 0.9882053 0.08577579 0.07729822 0.9933255 0.08561289 0.0657826 0.9941439 0.08573532 0.04411196 0.995085 0.08865684 0.02380406 0.9957701 0.0887438 0.03307342 0.9957662 0.0857672 0.008588492 0.9960209 0.08870589 -0.01043933 0.9960024 0.08871442 0.008672416 0.9963192 0.08528208 -0.001428306 0.9963046 0.08587807 -0.04680758 0.9949584 0.08869659 -0.2622804 0.9610579 0.08704525 -0.2712768 0.9583241 0.08957564 -0.2356504 0.9679161 0.08721983 -0.07765626 0.9929958 0.08904451 -0.07909315 0.993242 0.08493924 -0.1256678 0.9884008 0.08527308 -0.1684867 0.9816649 0.08914178 -0.2693921 0.9592735 0.08498501 -0.3078013 0.9473887 0.08782446 0.2354867 0.967969 0.08707505 0.01185405 0.7532535 0.6576235 0.1045063 0.904346 0.4138076 0.1000924 0.9059711 0.4113367 0.09566366 0.8950817 0.4355195 0.08542585 0.8985333 0.430512 0.1137009 0.9818568 0.1517544 -0.02388137 0.9670071 -0.2536278 -0.2425984 0.8624302 -0.4442524 -0.1304313 0.9201291 0.3692564 0.372061 -0.8336744 -0.4081149 -0.9355133 -0.3531838 -0.008725762 -0.9355121 -0.3531872 -0.008725702 -0.1883217 0.05881434 -0.9803448 -0.2508599 0.08417141 -0.9643571 0.06009465 0.04074245 -0.997361 -0.2439832 -0.2706385 -0.9312502 0.3469353 -0.9378377 -0.009820401 0.3571531 -0.9340053 -0.008709132 0.9355334 0.3531325 -0.008648335 0.9354499 0.353352 -0.008718907 0.9355034 0.3532099 -0.008727192 0.9355131 0.3531846 -0.008721053 -0.9317472 -0.3628928 -0.0124883 -0.9355126 -0.3531861 -0.008712351 -0.9355146 -0.3531801 -0.008726358 0.3537964 -0.9352802 -0.008902251 0.02137368 -0.211426 -0.9771603 0.8347919 -0.1433056 -0.5315882 -5.82098e-4 0.00154221 -0.9999987 0.00576508 0.003938972 -0.9999757 -0.5832098 -0.7218542 -0.3725492 0.4513309 -0.03001147 -0.891852 0.9598863 0.2802329 -0.009371221 0.9355638 0.352927 -0.01276475 0.5270593 0.1989876 -0.8262038 -0.5270593 -0.1989876 -0.8262038 -0.979489 -0.2014192 -0.005626261 -0.935335 -0.3535131 -0.01330119 -0.3531684 0.9350389 -0.03121787 0.9354693 0.3531779 -0.01275795 -0.3532035 0.9355059 -0.008726656 -0.3543643 0.9345437 -0.03246623 -0.3528697 0.9351122 -0.03237545 0.9355072 0.3532 -0.008732795 0.9355109 0.35319 -0.008727252 -0.3529366 0.9355977 -0.009642302 0.04892045 0.01864075 -0.9986288 -0.9355424 -0.3531065 -0.008728861 -0.9354088 -0.3534603 -0.008744001 -0.05712682 0.9959167 -0.06990337 -0.3531777 0.9355154 -0.008743762 0.9355148 0.3531798 -0.008726656 0.9354512 0.3533468 -0.00878483 0.9355313 0.3531364 -0.008728802 -0.3531926 0.9355099 -0.008726775 -0.9352693 -0.3536851 -0.01335126 0.3534286 -0.9354209 -0.008732318 0.3531884 -0.9355115 -0.008726596 -0.3531872 0.935512 -0.008726596 -0.353186 0.9355124 -0.008726716 -0.3531863 0.9355124 -0.008726835 0.3531863 -0.9355124 -0.008726477 0.3531867 -0.9355123 -0.008726358 0.3531873 -0.935512 -0.008726596 -0.9355094 -0.3531941 -0.008726298 0.3531919 -0.9355102 -0.008726775 0.3531871 -0.9355121 -0.008726477 0.3531878 -0.9355118 -0.008726418 0.3532548 -0.9354861 -0.008768737 -0.9355113 -0.3531893 -0.008729457 -0.3191171 0.943699 0.08715927 -0.3191145 0.9436993 0.08716446 -0.3349501 0.9329711 0.1318079 -0.904805 0.1403709 0.4020248 -0.6250557 0.7261999 0.2862504 -0.3774845 0.9081155 0.1811956 -0.957126 0.2151218 0.1939914 -0.7938567 0.542925 0.273905 -0.3557064 0.9277481 0.1129446 -0.8702827 0.1160742 0.4786803 -0.8184809 0.1894425 0.5424028 -0.3452686 0.4910026 0.7998163 -0.3464529 0.9133457 0.2139393 -0.371439 0.8345229 0.4069457 -0.5067899 0.4990661 0.7029204 -0.5629547 0.6496146 0.5109627 -0.1900342 0.119624 0.9744625 -0.1411617 0.3225024 0.9359838 -0.367462 0.9259139 0.08749473 -0.4571903 0.8850567 0.08747416 -0.1176519 0.05252271 0.991665 -0.03541904 0.168358 0.9850894 -0.159477 0.04287904 0.9862701 -0.08605581 0.002682209 0.9962868 -0.104735 0.002001941 0.9944982 0.3821868 -0.7978202 -0.4662792 0.398072 -0.6680237 -0.6287155 0.5413507 -0.5792013 -0.6094797 0.5406872 -0.6096888 -0.5796008 0.3524687 -0.4356294 -0.8282468 0.3742355 -0.1525155 -0.9147059 0.5663454 -0.3458369 -0.7480974 0.3398932 -0.9296695 -0.1420823 0.3512285 -0.9168311 -0.1898931 0.3401625 -0.7650431 -0.5468075 0.08914083 -0.05380105 -0.9945649 0.09591186 -0.08660638 -0.9916151 0.1505618 -0.03902226 -0.9878302 0.01989454 -0.2656221 -0.963872 0.01841014 -0.2040706 -0.9787831 0.435966 -0.8782147 -0.1966536 0.4553754 -0.8769819 -0.1534146 0.3829683 -0.9026798 -0.1962255 0.03836542 -0.7846369 -0.6187673 0.3231741 -0.8016023 -0.5029833 -0.4980959 0.8627303 0.08716022 -0.4966952 0.8638259 0.08425557 -0.4951431 0.8646845 0.08458214 0.1922963 0.006507217 -0.9813154 0.09585094 -6.83256e-4 -0.9953955 0.1225666 2.22745e-4 -0.9924603 0.04336166 0.008378446 -0.9990243 0.1808367 3.18056e-6 -0.9835132 0.1889467 -1.26319e-5 -0.9819874 0.1893278 -3.03799e-4 -0.9819139 0.1857716 -5.3578e-6 -0.982593 0.1845736 -5.65038e-4 -0.9828186 0.2069687 3.16405e-4 -0.9783475 0.2297444 8.7128e-4 -0.9732506 0.1194343 0.002519786 -0.9928389 0.1269509 1.43494e-4 -0.9919091 0.1227192 8.95392e-4 -0.9924411 0.1247665 0.002400875 -0.9921833 0.119489 9.67863e-5 -0.9928356 0.3731035 -0.05412626 -0.9262096 0.01481264 0.08950734 -0.9958761 0.1235864 -0.001437246 -0.9923329 0.1173122 2.15555e-5 -0.9930951 0.1336736 7.56334e-5 -0.9910255 0.395591 0 -0.9184268 0.4028083 0.002571761 -0.9152808 0.3582671 0.01047086 -0.9335605 0.3388435 -0.001601934 -0.9408414 0.391565 -0.001470804 -0.9201493 0.415891 0.001481235 -0.9094133 0.390458 -8.23073e-4 -0.9206205 0.4264562 6.35048e-4 -0.9045081 0.4909324 0.00188291 -0.8711957 0.5571684 7.29324e-4 -0.8303993 -0.4120961 0.01183068 0.9110637 0.3170269 0.009434223 -0.9483698 0.2984159 5.85832e-7 -0.954436 0.2989087 -1.24287e-4 -0.9542818 0.2761278 2.97303e-4 -0.9611209 0.2431421 0 -0.9699907 0.2309275 0.002651929 -0.9729673 0.2515767 0 -0.9678374 0.2605921 0.002418935 -0.965446 0.2493519 4.37566e-4 -0.9684129 0.2825315 -0.001440227 -0.959257 0.2991605 -0.02907633 -0.9537597 0.3056846 -9.65938e-4 -0.9521324 -0.2995226 0.002471327 0.9540861 0.298041 -5.02789e-5 -0.9545531 0.5811609 -1.50045e-5 -0.8137887 0.1899433 -2.97373e-5 -0.9817951 0.16861 1.04266e-6 -0.9856829 0.1449933 4.54068e-4 -0.9894325 0.1614208 -2.6378e-4 -0.9868857 0.1719815 -4.89572e-4 -0.9851002 0.1802967 2.35944e-5 -0.9836123 0.1710363 -0.003485679 -0.9852586 0.194759 -0.03641259 -0.9801751 0.1735816 -2.15457e-4 -0.9848195 0.3007855 0.001256346 -0.953691 0.3082091 6.24477e-5 -0.9513186 0.2332596 -0.001710176 -0.972413 0.239575 -1.71883e-6 -0.970878 0.2604628 -1.70829e-5 -0.9654839 0.2349752 2.81865e-4 -0.9720013 0.2143374 -0.003673791 -0.9767528 0.09386581 -3.12412e-4 -0.9955849 0.194046 2.1224e-4 -0.9809925 0.5131511 0.03533941 -0.8575705 0.6041483 -0.001975238 -0.7968695 0.6971415 -0.001022636 -0.7169329 0.6383692 -5.21773e-4 -0.7697303 0.767385 0.001414537 -0.6411852 0.8018425 0.00193119 -0.5975325 0.9435399 0.00136429 -0.3312565 0.9199526 -0.00130546 -0.3920272 0.943666 -0.001347005 -0.3308972 0.9199452 0.00129956 -0.392045 0.9864273 0 -0.1641986 0.968369 -1.91724e-5 -0.2495226 0.8687136 0.001933276 -0.4953109 0.5148764 6.09677e-4 -0.8572642 0.2637594 -1.42059e-4 -0.9645886 0.2001072 2.13957e-4 -0.979774 0.2116337 -2.50048e-4 -0.9773491 0.2132894 -1.01484e-4 -0.976989 0.3538954 0 -0.935285 0.2377572 7.17629e-5 -0.9713247 -0.4468469 -0.1206067 0.8864435 -0.9094219 -0.3936583 -0.1341083 0.9569707 0.01364606 -0.2898636 -0.7322713 0.4450854 -0.5154395 -0.4038506 -0.7809982 0.4763889 -0.3368826 -0.7271236 0.598165 -0.3693807 -0.8477218 0.3806912 -0.4659977 -0.5186734 0.7168152 0.57897 0.2896977 0.7621477 0.5466572 -0.7627279 0.3455604 0.9695975 0.2046507 -0.1341598 0.005666732 -0.433323 0.9012209 -0.01139557 -0.6007295 0.7993711 0.004406213 0.683205 -0.7302134 -0.02105802 -0.8209398 0.5706264 0.0213235 -0.4636628 0.8857552 0.001587092 -0.4203549 0.9073585 -0.006758391 -0.3862252 0.9223798 -0.006644546 -0.4038713 0.9147918 0.6323904 -0.4246705 0.6478714 0.006576478 -0.3947724 0.9187555 0.002412199 -0.3274273 0.9448734 0.007561624 -0.3199514 0.9474038 -0.009073793 -0.3076893 0.9514437 -4.24435e-4 -0.2798699 0.9600378 0.02571129 -0.2396502 0.9705188 0.008229136 -0.2597264 0.9656473 -0.02149671 -0.3579015 0.9335119 4.03807e-4 -0.6050392 0.7961957 9.52661e-4 0.6273662 -0.778724 0.02565711 -0.547462 0.8364371 0.02770799 -0.4311637 0.9018482 -0.006870329 -0.4436139 0.8961918 0.006592392 -0.3594352 0.9331468 0.06442707 -0.3403084 0.9381042 -6.57315e-4 -0.2058556 0.9785822 4.73319e-4 -0.1777065 0.9840834 -3.14293e-4 -0.1773864 0.9841412 8.64046e-4 -0.1503958 0.9886256 -7.77483e-5 -0.1236461 0.9923264 1.86832e-4 -0.07653719 0.9970668 -4.91529e-5 -0.05649149 0.9984031 1.75914e-4 -0.04344934 0.9990557 9.12314e-4 -0.2220962 0.9750244 2.99421e-4 -0.3318892 0.9433184 -8.0526e-4 -0.3890982 0.9211961 4.96193e-4 -0.4466226 0.8947224 2.43896e-4 -0.5139966 0.8577922 2.86506e-4 -0.5146137 0.8574222 -6.28365e-5 -0.5535765 0.8327984 -2.32039e-6 -0.5761902 0.8173157 0.001924932 -0.58956 0.8077223 0.00237292 -0.2935019 0.9559556 -0.003365218 -0.7332793 0.6799193 0 -0.01733231 0.9998498 -0.007665634 -0.6656136 0.7462573 2.52385e-4 -0.7461748 0.6657501 -0.01275134 -0.6409585 0.7674698 4.62563e-4 -0.7106378 0.7035579 9.35247e-4 -0.6774382 0.7355791 2.07355e-4 -0.6345492 0.7728825 9.01809e-4 -0.6576847 0.7532929 -9.07534e-4 -0.7041352 0.7100654 -2.18194e-4 -0.7298679 0.6835883 0.01352584 -0.7530615 0.6578112 -0.743855 0.2528414 0.6186687 0.5845214 0.2443181 0.7737207 -0.4487208 -0.7457218 0.4924925 -0.4353446 -0.7995006 0.4138527 -0.3442451 -0.7377197 0.5807452 -0.4119108 -0.7354835 0.5379533 0.6113367 0.7913405 0.006925523 -0.7379015 0.6619932 -0.1314019 -0.623687 0.7374424 0.2592165 -0.6545452 -0.7560188 -0.002496242 -0.6544302 -0.7561194 -0.002169251 -0.6542198 -0.7563046 1.89203e-4 0.3414584 0.5617218 -0.7535747 -0.491176 -0.764854 0.4168268 -0.4185328 -0.6816977 0.6000987 -0.474483 -0.7611175 0.4422286 -0.4233531 -0.6832031 0.5949838 0.6624239 0.457516 0.5931895 0.6182937 -0.614458 0.4900553 0.09883415 -0.3690921 -0.9241227 -0.56412 -0.6754971 0.4748394 -0.4974706 -0.7266288 0.4738498 -0.5293161 -0.6699622 0.5205528 -6.12438e-4 -0.6239176 0.78149 -0.7524272 0.5336143 0.3861466 0.3754069 -0.1347182 0.9170173 0.5137278 0.1249394 0.8488075 0.4549311 -0.8765984 0.1568855 0.3742695 -0.8803279 0.2914537 0.222667 -0.04702526 0.9737598 -0.2491667 -0.6529315 0.7152597 -0.4547386 -0.6735666 0.5826843 -0.7690964 0.4840129 0.4173994 0.7259548 0.68317 0.07917326 0.5193104 0.1022794 0.8484432 0.8189545 0.4882103 0.301603 0.6976423 -0.6961197 -0.1694485 0.7363666 -0.5958912 -0.320434 -0.2256143 0.6440385 0.7309669 -0.4709321 -0.7894004 0.3937892 -0.4926213 -0.633474 0.5966866 -0.5465552 -0.5604608 0.6222227 -0.549546 -0.5222108 0.6521466 0.1573418 -0.2851728 0.9454734 0.4039161 -0.1653116 0.8997355 0.193616 -0.9132412 0.358474 0.2126697 -0.8937612 0.394921 0.8996231 0.3441445 -0.2687806 0.5359624 0.3192104 0.7815684 0.2545377 0.6115661 0.7491311 0.6121069 -0.2372314 0.7543518 0.7888643 -0.3292236 0.5189461 0.6237214 -0.2512803 0.7401554 -0.5608588 0.5606451 0.6091917 -0.6150745 0.559339 0.5557188 0.8541217 -0.3066196 -0.420072 0.2492802 0.893133 0.3743969 0.1739362 0.854265 0.4898748 0.5578002 0.4858046 -0.6729434 0.5473807 -0.2122861 0.8095116 0.645132 -0.178712 0.7428774 -0.4772678 0.6389246 0.6033165 -0.4608799 0.5834053 0.6687511 -0.5870689 0.6736357 0.4489602 -0.4943563 0.5907275 0.6376935 0.5636852 0.8251198 0.03790062 0.5797798 0.7994015 0.1575206 0.2713763 0.4487321 0.8514661 0.5131247 -0.1198149 0.8499103 0.1804774 0.2247131 0.9575657 0.5311143 0.005068898 0.8472851 -0.4940556 0.6553471 0.5713399 -0.4881477 0.650033 0.5823823 -0.4903354 0.6258528 0.6065308 -0.5295199 0.6518441 0.5428703 0.4216387 0.7593286 -0.4956217 0.6661784 0.5504271 0.5032261 -0.5407989 0.7547971 0.3712387 -0.2704665 0.724097 0.6344536 0.5143554 -0.178978 0.8386927 0.6921313 -0.411639 0.5928809 0.5922396 -0.09156942 0.8005419 -0.7041422 0.7099632 -0.01166474 -0.703464 0.7106831 0.008242368 -0.7048123 0.7093939 -2.20056e-6 -0.7049939 0.7092132 -5.2741e-4 -0.8459078 -0.533151 0.0137912 -0.930435 -0.3454402 0.1223188 0.6668055 -0.7452318 8.70532e-6 0.6667335 -0.7452962 2.92346e-4 -0.4191828 0.7362779 0.5312068 -0.3464175 0.7370506 0.5803029 -0.3793669 0.790849 0.4802485 -0.4092392 0.8018404 0.4354025 0.3630601 -0.5513827 -0.751109 0.08720123 0.8441871 0.5289085 0.6282817 -0.4795289 0.612629 0.511152 -0.2471002 0.8232043 -0.6518169 0.7583504 0.006293833 -0.6544312 0.7561209 -0.001040816 -0.6542409 0.7562864 1.55135e-4 0.6126742 -0.7903357 2.87443e-4 0.6123384 -0.7905958 1.97183e-6 0.6123357 -0.790598 -9.13416e-6 -0.3765864 0.7962219 0.4735119 0.5756684 -0.4509977 0.6820608 0.6003987 -0.5245406 0.6036378 -0.5931142 0.8033177 0.05381733 -0.6009661 0.799274 8.62306e-4 -0.5937148 0.8044553 0.01882869 0.6041306 -0.7967825 -0.0128048 0.5533714 -0.8329296 -0.00291419 0.5640895 0.8251428 0.03070122 0.5542407 0.8323565 1.19034e-4 -0.6014613 -0.7989011 -0.0011729 -0.6007914 -0.7994019 0.002541482 0.5772504 -0.8036857 0.1444689 0.7656387 0.6432704 7.82843e-4 0.7655867 0.6433325 7.31791e-4 -0.7907294 -0.6119467 0.01638573 -0.7933087 -0.6087815 0.006827533 0.6842458 0.6998493 0.2049846 0.216474 0.4684483 0.8565602 -0.8286473 -0.5533514 0.08453375 -0.8348766 -0.5504372 -2.38765e-4 -0.8353472 -0.5496789 -0.006946027 -0.8348444 -0.5504861 -3.47174e-4 -0.8352919 -0.5498057 -0.001095831 0.8093904 0.5872703 9.1074e-4 0.8086488 0.5881741 -0.01176989 0.8158923 0.5688479 0.1035948 0.6658399 0.7460349 0.009456396 0.6668332 0.7452067 -7.51268e-4 0.6662703 0.7457063 -0.0024513 -0.715365 -0.6979858 -0.03269076 -0.7047247 -0.7094808 3.68898e-4 -0.692573 -0.7180265 0.06914293 -0.706346 -0.7076427 -0.01780861 -0.5150238 -0.6182572 0.5937244 -0.7522479 -0.6588729 -0.003123104 0.7180215 0.6960205 8.41578e-4 0.7296501 0.6760726 0.1026481 0.5898389 0.7829765 0.1975809 0.5851424 0.7850605 0.2031953 0.7180208 -0.6960214 6.48432e-4 0.7178776 -0.6961693 3.30525e-4 0.7186009 -0.6953858 0.007168948 -0.7550275 0.6556743 -0.004980325 -0.7466557 0.6642268 0.03616702 -0.7400096 0.6712135 0.04310727 -0.7518445 0.6593405 8.60983e-6 -0.7513744 0.6597952 -0.01033848 -0.4668281 -0.8685743 -0.1662837 0.7266114 -0.6562896 0.2032729 -0.9139391 -0.2097502 0.3474481 0.6774554 0.5311026 0.5089051 0.9799328 -0.1616877 0.1165716 0.8100728 -0.5863212 -0.003086268 0.8131726 -0.581656 0.02065348 -0.8211324 0.5686062 0.04928332 -0.8231621 0.5657033 0.04882735 -0.8346655 0.5507571 4.85499e-4 -0.8347775 0.5505874 2.30536e-4 -0.8193572 0.5609249 0.1183936 0.2296931 -0.8022806 0.5509873 0.139618 -0.8713362 0.470404 0.7705734 -0.6372037 0.01371961 0.7650926 -0.6439072 -0.004114627 -0.7952978 0.6062062 -0.003948688 -0.78284 0.6155864 0.09063732 -0.7403984 -0.6634937 0.1076403 -0.05574393 0.9049061 -0.4219452 -0.2982785 -0.5161651 0.8028721 -0.7121708 -0.08458769 0.6968916 -0.9028508 -0.2743633 0.3310369 -0.09341841 0.4009918 0.9113061 -0.6182321 0.4684045 0.6311786 -0.937615 0.3066594 0.1638236 -0.4857289 -0.08453655 0.8700122 -0.1573253 -0.07636463 0.9845899 0.6849235 0.5772188 -0.4446328 0.2932317 0.09073787 -0.9517257 0.6502418 0.2238422 -0.726003 0.3817303 -0.006313323 -0.9242522 0.5419504 -0.1940534 -0.8176999 0.6273494 -0.2411859 -0.7404473 0.8243719 0.05524653 -0.563346 0.7342539 -0.4943794 -0.4652531 0.07153999 0.455145 -0.8875388 0.7594965 -0.6100134 -0.2259401 0.9926031 0.0462144 0.1122645 0.7799482 0.2488679 -0.574235 -0.006461381 0.02241063 -0.999728 -0.103007 -0.00204271 -0.9946786 -0.004843473 0.02129393 -0.9997615 -0.775311 -0.631402 0.01498186 -0.9981901 0.0593326 0.009810805 -0.9400209 0.3375552 0.0491659 0.6424917 0.7658482 -0.02609503 0.9924499 0.1208589 0.02088904 0.9434053 -0.331493 0.009944915 0.4588772 -0.8859424 -0.06736284 -0.9861516 0.1605705 -0.04149955 -0.7938362 0.6081272 -0.002311348 0.9418881 -0.3358383 0.007724344 0.7935473 -0.6073025 0.03829264 0.2264406 -0.9726072 0.0525344 -0.1673672 -0.9783982 -0.121348 -0.9813803 -0.1920192 0.00461626 -0.977977 0.207791 0.01959693 -0.08505237 0.2584378 0.9622765 -0.01965439 0.2194586 0.9754238 -0.01350188 0.02607029 0.999569 -0.02577632 0.02970778 0.9992262 0.03578585 0.07787454 0.9963208 -0.01486194 0.1269556 0.9917972 -0.008939802 -0.0522567 0.9985937 0.03083878 0.04402393 0.9985544 0.4738605 -0.8805944 0.003122091 0.05336177 -0.9774354 -0.2043833 -0.7996284 -0.5995335 -0.03396993 -0.468415 0.8833993 -0.01389878 0.06229925 0.9543634 -0.2920776 0.424853 0.9052488 -0.004961192 0.9382465 0.3386773 -0.07064861 0.06368368 -0.06643718 -0.9957563 0.343951 -0.06196498 -0.9369408 0.06155562 0.05945599 -0.9963313 -0.0598067 0.06187003 -0.9962908 0.3733839 0.01254057 -0.9275922 0.01534098 0.2145921 -0.9765834 -0.05548113 0.06183993 -0.9965429 -0.05808168 -0.05985277 -0.996516 0.00523436 -0.1907656 -0.9816217 -0.5534591 -0.8243411 -0.1189323 -0.837647 -0.5461688 -0.006880819 -0.9511036 -0.2802639 -0.1298242 -0.9096489 0.4149656 0.01850605 -0.4651299 0.8851401 0.01346111 -0.007091939 0.9346218 -0.3555724 -0.5931928 0.798906 -0.09935581 0.5270909 0.8450507 0.0898028 0.7751927 0.6299129 -0.04781454 -0.004528939 -0.114348 -0.9934304 0.1827288 -0.05145514 -0.9818159 0.1064735 0.08145308 -0.9909737 0.002408325 0.1581096 -0.9874187 0.5297322 -0.8473956 0.03611958 -0.3215171 -0.9456858 -0.04801344 -0.6717886 -0.7391983 0.04781031 -0.7830383 -0.6215705 -0.02239066 -0.998003 -0.04015678 -0.04876017 -0.8037329 0.5932871 -0.04498761 -0.4691717 0.8830413 0.01076883 0.4514473 0.8900486 0.06331706 0.6195129 0.766652 -0.1686668 0.8232098 -0.5621245 -0.07963472 -0.001978397 -0.9657827 -0.2593453 0.8432887 0.5298401 -0.09018629 -0.03094369 0.02346146 -0.9992458 0.3263387 0.0166065 -0.945107 -0.03483802 0.02172857 -0.9991568 -0.02783322 -0.09341049 -0.9952386 0.001601815 -0.1601226 -0.9870958 -0.8509019 -0.3204439 -0.4162712 0.8262374 -0.5632354 -0.009884297 0.2384908 -0.9692198 -0.06111878 -0.9954127 0.09201687 -0.02620446 -0.8580463 0.5135724 3.95012e-4 0.466829 0.8842982 -0.009345889 0.8027894 -0.5957261 -0.02529025 0.003112137 -0.9441838 -0.3294045 -0.5115575 0.8592046 -0.008741915 0.8620327 0.506692 -0.01276499 0.2551044 -0.02898007 -0.9664791 0.0506491 0.08181565 -0.9953597 0.007981419 0.2288317 -0.9734333 -0.1375172 -0.06206041 -0.9885534 -0.08711612 -0.06185495 -0.9942761 -0.2429138 -0.02327513 -0.9697687 0.7275606 0.4690678 -0.5006306 0.9284886 -0.2218778 -0.2977904 -0.2934316 -0.695591 -0.6557828 -0.4387199 0.8414061 -0.3155326 -0.7650979 -0.1215925 -0.6323294 -0.4292174 -0.1191241 -0.895311 -0.4036625 -0.06364816 -0.9126914 -0.5783324 -0.1253085 -0.80612 -0.9644411 -0.07726633 -0.2527515 -0.3516067 -0.01563698 -0.9360173 -0.1384615 0.007521808 -0.9903393 -0.7093568 -0.0119313 -0.7047487 -0.3052513 -0.02749437 -0.9518749 -0.1540162 -0.01573652 -0.9879431 -0.1828535 -0.4490626 -0.8745899 -0.1887032 -0.01670968 -0.9818921 -0.2218551 -0.06069689 -0.9731888 -0.2603092 -0.05980795 -0.9636712 -0.2690761 -0.06303977 -0.9610537 -0.2982304 -0.0800299 -0.951133 -0.3618253 -0.08622789 -0.9282497 -0.6847848 -0.09187209 -0.7229311 -0.39157 -0.1120547 -0.9132999 -0.4835122 -0.08210402 -0.8714787 -0.5530803 -0.1910431 -0.8109283 -0.5965159 -0.1476479 -0.7889037 -0.6945804 -0.1885482 -0.6942677 -0.8486186 -0.1238653 -0.5142996 -0.9129845 -0.1123567 -0.3922185 -0.862947 -0.2050389 -0.4618241 -0.8226136 -0.2067698 -0.5296728 -0.9671519 -0.2453019 -0.06666362 -0.9909953 -0.0640996 -0.1175574 -0.9970423 -0.06611454 -0.03918653 -0.9988492 -0.02844625 -0.03861391 -0.2027925 -0.00256747 -0.9792184 -0.2492485 -0.03138446 -0.967931 -0.3133066 -0.05354684 -0.9481412 -0.4213469 -0.05167013 -0.9054266 -0.3694817 -0.07986301 -0.9257998 -0.2011006 -0.04359704 -0.9786 -0.9922208 -0.1167739 -0.0431506 -0.9775693 -0.0195806 -0.2097024 -0.5820127 -0.03161215 -0.812565 -0.5048258 -0.02261549 -0.862925 -0.3884122 -0.02155083 -0.9212338 -0.1784712 -0.004496276 -0.9839349 -0.1947368 -0.01082986 -0.9807958 -0.4586749 -0.02865594 -0.8881421 -0.8991427 -0.03104019 -0.4365534 -0.6925582 -0.04961359 -0.7196538 -0.3683961 -0.05053377 -0.9282945 -0.3571016 -0.05709552 -0.9323189 -0.4563428 -0.05434358 -0.8881431 -0.77559 -0.0735439 -0.6269382 -0.9796088 -0.1978389 -0.03502202 -0.9369809 -0.217754 -0.273222 -0.9592704 -0.2453982 -0.1399287 -0.743547 -0.1742767 -0.6455737 -0.9018824 -0.2421895 -0.3577043 -0.9679131 -0.1722213 -0.1829864 -0.5525064 -0.09746056 -0.8277912 -0.5783941 -0.1109384 -0.8081788 -0.9862895 -0.1117652 -0.1214156 -0.9856797 -0.1139161 -0.1243329 0.3200275 0.9128337 -0.2536082 -0.2650531 0.9641315 -0.01404321 0.5370717 -0.8387945 -0.08931833 -0.9573181 -0.2867177 -0.03653949 -0.05844849 -0.9592543 -0.2764326 -0.07523649 -0.9605658 -0.2676804 0.1158679 0.8351204 -0.5377255 -0.9641446 0.2047827 -0.1687874 0.694227 -0.5178052 -0.4999266 -0.9466333 -0.06721794 -0.3152255 -0.926152 0.01284444 -0.3769319 -0.4402862 0.0131852 -0.8977607 -0.5208848 0.06690728 -0.851001 -0.7213626 0.1445494 -0.6773046 -0.9518607 0.2273113 -0.2056473 -0.9695772 0.2430545 -0.02906256 -0.1718353 0.009023666 -0.9850844 -0.9990679 0.02845007 -0.03246504 -0.9742998 0.002722382 -0.2252393 -0.9093353 0.191955 -0.369138 -0.8612021 0.1596917 -0.482524 -0.8100407 0.1162712 -0.5747305 -0.9805222 0.1932403 -0.03513634 -0.8196176 0.2209256 -0.5286011 -0.3775882 0.05053275 -0.9245939 -0.8179763 0.2238358 -0.5299174 -0.3376559 0.08176332 -0.9377118 -0.3104003 0.07993721 -0.947239 -0.3582289 0.1469132 -0.9220026 -0.3968369 0.113632 -0.9108283 -0.4344249 0.1169701 -0.8930807 -0.2206835 0.05360627 -0.9738712 -0.2128525 0.04437536 -0.9760761 -0.1880797 0.01112115 -0.9820908 -0.212436 0.003381013 -0.9771692 -0.1819381 0.02204483 -0.9830629 -0.1579115 0.01497679 -0.9873397 -0.1887819 0.008268296 -0.9819842 -0.2422717 0.01172494 -0.9701376 -0.3761431 0.09171253 -0.9220116 -0.3448466 0.0859754 -0.9347134 -0.3164946 0.04342705 -0.9475997 -0.2361391 0.03252708 -0.9711748 -0.1846519 0.02390331 -0.9825134 -0.996455 0.07488232 -0.03834354 -0.9662736 0.1366506 -0.2182707 -0.9669972 0.2393931 -0.08722043 -0.9911816 0.1090331 -0.0753057 -0.9617399 0.08179676 -0.2614682 -0.7747331 0.0712912 -0.6282565 -0.8271819 0.07464098 -0.556955 -0.3682662 0.02385097 -0.9294145 -0.3045108 0.02311593 -0.9522283 -0.2393198 0.008012413 -0.9709078 -0.5889623 0.02113562 -0.807884 -0.8924298 0.06635737 -0.4462799 -0.9879456 0.1495366 -0.04002851 -0.9967849 0.0750761 -0.02799332 -0.8789596 0.1606444 -0.4490251 -0.6319788 0.06564635 -0.7722004 -0.5118012 0.08646297 -0.854742 -0.5749075 0.06103283 -0.8159391 -0.466922 0.04895615 -0.8829424 -0.5333415 0.0305255 -0.8453491 -0.9743764 0.2094928 -0.0818752 -0.9497081 0.1880859 -0.2503566 -0.8529532 0.1705718 -0.4933317 -0.5878582 0.1318313 -0.7981498 -0.6254059 0.1125895 -0.7721341 -0.9659377 0.2506253 -0.06443017 -0.741259 0.1808955 -0.6463838 -0.503718 0.1132246 -0.8564161 -0.8584285 0.2136012 -0.4663424 -0.8885489 0.2351437 -0.3939397 -0.9099414 0.2218478 -0.3504142 -0.9842902 0.03111267 -0.1737954 -0.2195113 0.02635854 -0.9752538 -0.9849321 0.155641 0.07539719 -0.6084126 0.7849829 -0.116774 0.9781717 -0.2077623 -0.003889918 -0.8824126 -0.4532516 -0.1261392 0.3439521 -0.8996048 -0.2690877 0.2226009 -0.9121828 -0.3440515 0.285234 0.8914886 -0.3519796 0.9204184 0.3212303 -0.222803 0.06492137 0.9939328 -0.08878529 -0.09280157 0.9890531 -0.1147247 0.4775896 -0.5875261 0.6532391 0.9997178 -0.01641303 -0.01717174 -0.9993847 -0.01128709 -0.0332092 -0.7831307 -0.6198482 -0.04994672 8.60342e-4 0.06794661 -0.9976886 0.001079082 0.09038829 -0.9959061 2.74276e-4 0.103017 -0.9946796 -0.03739297 -0.3014465 -0.9527496 -8.69932e-6 0.1249132 -0.9921678 0.0014261 0.09931802 -0.9950547 -0.008185565 0.08746463 -0.9961341 -0.01168894 0.1501533 -0.9885937 0.004593968 0.1756211 -0.9844472 0.006702065 0.153293 -0.9881581 -0.001067042 0.1164709 -0.9931936 5.81831e-4 0.3093372 -0.9509523 -6.33326e-4 0.4485857 -0.8937396 -0.003050208 0.5822324 -0.8130168 1.80901e-5 0.6285172 -0.7777957 -4.22024e-5 0.6035846 -0.7972991 6.35232e-5 0.5595147 -0.8288204 -1.95882e-4 0.3744105 -0.9272631 3.44136e-4 0.4501919 -0.8929318 -4.15463e-4 0.414559 -0.9100223 -0.001516997 0.3829137 -0.923783 0.001013696 0.4126069 -0.9109086 -0.001499712 0.508004 -0.8613535 -3.97002e-4 0.5141214 -0.8577175 3.55013e-4 0.4855625 -0.8742019 -0.003681957 0.7464715 -0.6654072 -0.001020014 0.6843032 -0.729197 -0.00468707 0.6629198 -0.7486758 -4.39082e-4 0.5930609 -0.8051575 -8.87197e-4 0.5580247 -0.8298239 0.001791954 0.5395988 -0.8419205 6.70475e-4 0.5936028 -0.8047579 -0.001388013 0.5983325 -0.8012468 4.16614e-4 0.613503 -0.7896924 -4.01829e-5 0.6116529 -0.7911263 2.53294e-4 0.635277 -0.7722844 -8.78527e-4 0.6520555 -0.7581708 -3.69281e-4 0.6674259 -0.7446762 6.17618e-4 -0.6245989 0.7809455 -0.001314282 0.7017723 -0.7124001 -0.01753395 0.8625192 -0.5057206 0.01193434 0.7991311 -0.6010384 -0.01437723 0.6885195 -0.7250753 0.00557971 0.5825431 -0.8127807 3.68444e-4 0.3956912 -0.9183837 0.004193127 0.3544274 -0.9350742 0.00547105 0.3010736 -0.9535852 0.005419492 0.3009396 -0.9536279 0.03623658 0.2134004 -0.9762926 -0.01047158 0.288375 -0.9574603 0.006059587 0.3127364 -0.9498206 -0.005009829 0.4514093 -0.892303 0.004388213 0.208562 -0.9779993 -2.182e-4 0.1492255 -0.9888033 -0.001472473 0.1437909 -0.9896071 -0.002272427 0.1600388 -0.9871081 -5.358e-5 0.1744684 -0.9846628 1.90174e-4 0.1963997 -0.980524 -2.33425e-4 0.2174301 -0.9760759 0.002896785 0.3173958 -0.9482888 1.27749e-4 0.1453838 -0.9893754 0.001721918 0.07550507 -0.9971439 0.003096103 0.04441875 -0.9990082 -6.60791e-4 0.05056583 -0.9987205 8.06996e-4 0.7294365 -0.6840482 0.01281088 0.5755607 -0.8176588 0.01490962 0.4647569 -0.8853129 -0.007219195 0.4161641 -0.9092609 0.003242373 0.4604382 -0.8876859 0.004196047 0.3916716 -0.9200955 -0.0066697 0.3709731 -0.9286197 -0.002050817 0.6157115 -0.7879691 -0.006449282 0.6572824 -0.7536168 0.00940895 0.3509166 -0.9363595 2.85855e-4 0.2744507 -0.9616012 0.001177847 0.4271213 -0.9041937 2.14153e-4 0.1965935 -0.9804851 -0.03539311 0.5833724 -0.8114334 0.003219723 0.4140922 -0.9102293 0.005115509 0.3462021 -0.9381461 -0.004148721 0.4864732 -0.8736857 -0.005371153 0.329105 -0.9442781 -0.0383284 0.2613402 -0.9644856 -0.05054396 -0.04991263 -0.9974738 -0.01119446 0.3159724 -0.9487024 -0.003617703 0.2076318 -0.9782004 6.9803e-4 0.09260326 -0.9957029 -0.001820206 0.06522172 -0.9978691 -2.73314e-4 0.06959015 -0.9975757 -0.007856786 0.04086869 -0.9991337 5.12609e-4 0.06790488 -0.9976918 -5.44654e-4 0.06652724 -0.9977846 0.005575895 0.1404086 -0.9900779 -0.9426365 0.3266597 -0.06877529 0.9937814 -0.04396444 -0.1023027 -0.1424607 -0.9836412 -0.1102507 0.01582634 -0.9998736 -0.001559615 0.01303088 0.9996801 -0.02168029 0.5581741 0.5014005 -0.6610894 0.5099379 0.8596983 -0.02970486 0.9992524 -0.01742768 -0.03450858 -0.9999408 0.008816301 -0.006391525 0.7296537 0.6534807 -0.2014162 -0.4915724 0.8014464 -0.3406468 0.01969236 0.9770335 -0.212174 -0.6043843 -0.4742332 0.640174 -0.2174176 -0.9513986 -0.2181067 0.8736062 -0.3579328 -0.3296915 0.4110889 -0.6267579 0.6619521 0.5131593 0.5107375 0.6897933 -0.3541194 -0.8910092 -0.2840812 -0.9995198 -0.006758809 -0.03024184 -0.9993985 -0.02427977 -0.02476537 -0.0655201 -0.9977452 0.01454949 -0.3069769 0.8610032 -0.4055105 0.01981264 -0.1338302 -0.9908063 -0.002769589 -0.130638 -0.9914263 -0.6975805 0.7165064 -2.21153e-4 0.7156663 -0.6976342 -0.03359025 0.7017218 -0.7119462 -0.02681857 -0.9930863 0.11202 -0.03508937 -0.1612318 0.9129446 -0.3748819 0.3470411 0.3427312 -0.8729822 -0.8156391 0.5675205 -0.1124867 0.3966891 -0.9042939 -0.1577672 0.03581362 0.9993417 -0.00579214 0.9646945 -0.0649839 -0.2552289 0.9291257 0.04204672 -0.3673657 0.03071582 0.9319305 -0.361334 0.6916341 -0.7089556 -0.1379286 0.6943878 0.5918537 -0.4093103 -0.2279105 -0.004161477 -0.9736732 -0.1243587 0.2340475 -0.964239 0.003186345 0.7469171 -0.6649097 -0.002084434 0.6997503 -0.7143846 0.002516329 0.6629239 -0.7486826 -0.001431643 0.6311086 -0.7756932 0.001694083 0.5822344 -0.8130193 -6.14233e-4 0.5665674 -0.8240153 2.98833e-4 0.3768045 -0.9262928 -4.37987e-4 0.3310876 -0.9436 3.06148e-4 0.2838749 -0.9588613 -9.18517e-4 0.2773244 -0.9607759 0.004115462 0.2218731 -0.9750669 0.005529165 0.1482984 -0.9889273 0.003884732 0.1501623 -0.9886537 0.0180273 0.08745342 -0.9960055 -0.002387881 0.09875673 -0.9951089 -0.01464682 0.02296423 -0.999629 -9.31961e-5 0.8168482 -0.5768527 0.006550133 0.8678512 -0.4967811 -0.02590745 0.9377185 -0.3464289 0.002931356 -0.01628202 0.9998632 -0.006446838 -0.04344838 0.9990349 0.00657767 -0.05876779 0.99825 -0.005048155 -0.1503939 0.9886134 0.001105546 -0.2761791 0.9611056 -0.001468837 -0.2308227 0.9729948 -8.42637e-4 -0.3858208 0.9225735 -1.51327e-4 -0.4466218 0.8947229 -0.002969205 -0.7530256 0.6579847 -0.006320714 -0.8652288 0.5013376 -2.04128e-5 -0.9283173 0.371789 0.0022403 -0.7041693 0.7100286 0.01243305 -0.1162554 0.9931415 0.9952085 -0.01502263 0.09661495 0.9349945 -0.079521 0.3456324 0.8592569 -0.1686115 0.4829573 0.8309689 -0.2287667 0.5071058 0.7995266 -0.2475779 0.5472318 0.9510233 -0.2125663 0.224433 0.9882015 -0.1526795 0.01212006 0.9967859 -0.0569266 0.05636793 0.4474487 -0.06729501 0.8917741 0.4757983 -0.02382761 0.8792317 0.3879277 -0.08449435 0.9178087 0.3712592 -0.1006311 0.9230601 0.3424488 -0.01911896 0.939342 0.3078832 -0.01850378 0.9512443 0.1827169 -0.0049389 0.9831532 0.3163956 -0.07136553 0.9459391 0.2940827 -0.05644446 0.9541119 0.2444763 -0.04379945 0.9686655 0.3098607 -0.01771742 0.9506169 0.1539492 -0.009338259 0.9880347 0.203917 -0.03236973 0.9784529 0.2189723 -0.0319885 0.9752067 0.5412764 -0.1500673 0.827345 0.7189804 -0.0580058 0.6926056 0.7069657 -0.1924383 0.6805638 0.9062975 -0.2495114 0.341129 0.9619748 -0.2723823 0.02031141 0.9629786 -0.2307746 0.139339 0.9527208 -0.2734273 0.1325168 0.9653022 -0.2524726 0.06670308 0.2294595 -0.02172917 0.9730756 0.2647503 -0.009808242 0.9642672 0.9573435 -0.01904922 0.2883239 0.243291 -0.008826851 0.9699133 0.606828 -0.03286713 0.7941534 0.9944356 -0.08229309 0.06577104 0.9981215 -0.05721056 0.02192312 0.9795718 -0.1007065 0.1740617 0.9427188 -0.1436177 0.3010905 0.9097834 -0.1387128 0.3912198 0.7326284 -0.05396312 0.6784863 0.4776719 -0.02998083 0.8780267 0.3663703 -0.03531849 0.9297986 0.3556832 -0.0577045 0.9328235 0.2630885 -0.0279988 0.9643654 0.7043091 -0.1023962 0.7024698 0.6829942 -0.109187 0.7222169 0.9938644 -0.08696168 0.06834661 0.9775034 -0.1335186 0.1632784 0.5506786 -0.1339321 0.8239026 0.3556004 -0.05754268 0.932865 0.6792457 -0.1270763 0.7228257 0.9457011 -0.2076668 0.2500481 0.9878932 -0.1372655 0.0722872 0.3159474 -0.07442319 0.9458533 0.462056 -0.1016944 0.8810008 0.9126099 -0.2136507 0.3485637 0.9673629 -0.225257 0.116054 -8.48909e-5 0.999962 -0.008717358 0 0.9933712 0.1149513 0.9595025 0.2815169 -0.0101673 0.6995109 0.7145861 -0.007162749 0.4553753 0.8902871 -0.004724919 0.6826478 0.7307227 -0.006031274 -0.3851283 0.9228346 -0.007253289 -0.6353806 0.7721807 -0.005345523 -0.804991 0.5932676 -0.00480014 -0.9281559 0.3721158 -0.007523536 -0.9228283 0.3851503 -0.006888687 -0.9761056 -0.2172824 -0.002500295 -0.9268862 -0.3752554 -0.008090913 -0.8234273 -0.5674098 -0.003705978 -0.7145955 -0.6994894 -0.008242547 -0.3949847 -0.9186772 0.004422783 -0.09252005 0.9957028 -0.004031002 -0.9978809 -0.06502074 0.002466499 -0.3400607 0.9314846 -0.1292099 -0.3454312 0.9375305 -0.04139965 -0.3419934 0.9396302 -0.01165497 -0.3415088 0.939726 -0.0169363 -0.3118557 0.8384453 -0.4469403 -0.3130531 0.8838645 -0.3475359 -0.3241576 0.9049125 -0.275781 -0.270488 0.7368792 -0.6195526 -0.235227 0.6521658 -0.7206581 -0.3416978 0.9287498 -0.1437588 -0.3388461 0.9385362 -0.06582814 -0.09022539 0.8660205 -0.4918007 -0.06744968 0.5714723 -0.8178447 -0.2120397 0.929884 -0.3005913 0.01589423 0.9298413 -0.3676176 -0.234347 0.9298902 -0.2835239 -0.2588052 0.9632584 -0.0717855 -0.1456753 0.8208621 -0.5522357 0.6810659 0.730356 -0.05224472 0.3039706 0.9485447 -0.08868408 0.3037387 0.9486346 -0.08851718 -0.3078086 -0.9473851 0.08783662 -0.3008428 -0.9497107 0.08685231 -0.4860138 -0.8646081 0.12745 -0.6062929 0.5765411 -0.5477311 0.2733649 -0.9524278 0.1347337 0.1552201 -0.8887865 0.4312372 0.0797156 -0.7105956 0.6990705 0.08347928 -0.5661966 0.8200321 0.04731094 -0.531088 0.8459948 0.3399568 -0.9320747 0.1251646 0.3400597 -0.9364705 0.08592259 0.3414742 -0.9387096 0.04711478 0.3448539 -0.9360943 0.06930679 0.2992097 -0.8183871 0.4906284 0.3167293 -0.8634718 0.3925545 0.3398619 -0.9321429 0.1249146 0.3296585 -0.9104497 0.2498134 0.3410351 -0.9386721 0.05089098 0.3422487 -0.4570886 0.820936 0.4990674 -0.6671596 0.5530189 0.4076166 -0.9010856 0.1479646 0.3948948 -0.9184789 0.0213235 0.8672125 -0.4961436 0.04223901 0.8810648 -0.468187 0.06727218 0.3340726 -0.6789649 0.6537601 0.7375048 -0.4571036 0.4971348 0.4086959 -0.4855231 0.77281 0.5301865 -0.379939 0.75799 0.4540811 -0.6901039 0.5635309 0.4765564 -0.7840641 0.397665 0.5710929 -0.5534009 0.6063006 0.7565254 -0.6252724 0.1915828 0.7455518 -0.5379568 0.3933891 0.5398367 -0.7611765 0.3594257 0.9026783 -0.4155713 0.1116812 0.9637631 -0.2582287 0.06692367 0.9655548 0.2587107 0.02779895 0.7055132 0.7055292 0.06693118 -0.2582476 0.9637558 0.06695568 -0.9608575 0.257472 0.1022797 -0.9657912 -0.258798 0.01646226 -0.2574679 -0.9608597 0.102269 0.7430503 0.6641885 0.08203595 -0.9698801 0.2260913 0.09063917 -0.9534848 0.2907512 -0.0795651 -0.3812772 0.8863795 -0.2626006 -0.8840954 0.3952945 -0.2492342 -0.5462441 0.8367257 -0.03882831 -0.7310313 0.6609264 -0.1696162 -0.7798701 0.6239684 -0.04965859 0.999962 -2.09566e-6 -0.008725464 0.9972502 -0.0738545 -0.006132125 0.9995806 -0.01078957 0.02687269 0.9115968 -0.4110327 0.006573081 0.9608603 -0.2768911 -0.008882641 0.5062655 -0.8623405 -0.008006691 0.2709918 -0.9625343 -0.009555578 0.4297631 -0.9029106 0.007503151 -0.005432903 -0.9995499 0.02950716 0.002015769 0.4219563 -0.9066139 -0.002530038 0.4415656 -0.8972255 -0.2978168 0.2406076 -0.9238036 -0.3773429 0.6431565 -0.6663047 -0.589958 0.1375281 -0.7956354 0.004053413 -0.4227679 0.906229 0.1102294 -0.3223356 0.9401857 0.9261772 0.1678168 0.3376885 -0.7281771 0.07334864 0.681453 -0.4879216 0.1049087 -0.8665603 -0.5197865 0.1592137 -0.8393288 -0.7371465 0.09743875 -0.6686709 -0.3188572 -0.01047146 -0.947745 -0.4707794 0.3066052 -0.8272607 -0.6242488 0.5391878 -0.565323 -0.8520731 0.2007569 -0.4833922 -0.7068465 -0.70686 -0.02677667 -0.9160677 -0.3992687 -0.03747612 -0.9004312 -0.4349909 0.002575635 -0.5931659 -0.8049911 -0.01198023 -0.5049626 -0.8627946 -0.02446013 0.5180025 0.8545671 -0.03726243 0.7068734 0.7068948 -0.0250982 0.9656427 0.2587374 -0.02427202 0.9656411 -0.2587406 -0.02430194 0.7068793 -0.7068922 -0.02500545 0.2587412 -0.9656008 -0.02584779 -0.124082 -0.9916276 -0.03575527 -0.1105806 -0.9938665 -0.001181483 -0.9655542 -0.2587301 -0.02763783 -0.9989706 0.0227797 -0.03922712 -0.8613519 0.5080088 1.15135e-4 -0.7068365 0.7068575 -0.02710253 -0.5349874 0.8439748 -0.03866529 -0.5040501 0.8635396 -0.01526468 0.03884661 0.998537 -0.03761529 0.3410377 0.9398535 -0.01920139 0.9983894 -0.04392075 -0.0359134 0.9987818 -0.04928404 -0.0024935 0.8187288 -0.5730833 -0.03547811 -0.6221588 0.2051599 -0.7555316 -0.5600494 0.1839468 -0.8077798 -0.5550156 0.1773746 -0.8127091 -0.1545391 -0.01407998 -0.9878864 0.5409699 -0.2397511 0.8061457 -0.04587739 -0.04803496 -0.9977915 0.07852494 0.07170087 0.9943304 0.5692498 0.1125195 0.8144287 0.6058753 0.1210302 0.7862995 0.9589483 0.2049643 0.1959789 0.9749199 0.2064914 0.08302175 0.8868259 0.2809526 0.3668862 0.8537532 0.2394022 0.4623766 0.9324198 0.05396234 0.3573254 0.9909297 0.1168485 0.06636917 0.9881836 0.1526763 0.01353639 0.98322 0.1793861 0.03315162 0.9798642 0.179099 0.0882588 0.9224126 0.1466268 0.3572892 0.7487939 0.114382 0.6528588 0.7468971 0.115893 0.6547622 0.9151826 0.126915 0.3825357 0.8740841 0.007985353 0.4857093 0.9760897 0.06629574 0.2070117 0.9994012 0.03064978 0.01606136 0.99886 0.004923045 0.04748171 0.969512 0.2424386 0.03563725 0.9744683 0.2222731 0.03172081 0.9496818 0.2775178 0.1452187 0.9177255 0.2476426 0.310569 0.7930372 0.2468255 0.5569284 0.7599552 0.1707255 0.6271529 0.75168 0.2150155 0.6234947 0.610296 0.1507688 0.7776937 0.3690791 0.07599025 0.9262862 0.4833649 0.1060259 0.8689748 0.4232433 0.1105883 0.8992416 0.2695649 0.07022184 0.9604185 0.1665185 0.0105651 0.9859818 0.153779 0.003802716 0.988098 0.1528732 0.009691238 0.9881983 0.9413279 0.01197326 0.3372809 0.3700476 0.01936572 0.9288109 0.3683649 0.04545301 0.9285695 0.9704862 0.1167404 0.2110173 0.8975031 0.05363422 0.4377346 0.9905573 0.1259584 0.05413645 0.7527874 0.1162573 0.6479163 0.8933769 0.11536 0.4342463 0.7887823 0.08867168 0.6082432 0.7638497 0.04182052 0.6440378 0.6740029 0.09085911 0.7331199 0.5217829 0.04612398 0.8518305 0.6495244 0.1205955 0.7507163 0.1951263 0.01116323 0.9807146 0.2699359 0.0188992 0.9626929 0.2615966 0.02087748 0.9649516 0.521236 0.05187505 0.8518345 0.9909498 0.05057418 0.1243413 0.9550293 0.1556223 0.2523901 0.8999795 0.1823009 0.3959841 0.6497443 0.111414 0.7519437 0.5635653 0.1050958 0.819359 0.4934321 0.08181351 0.8659281 0.4326617 0.06683325 0.8990757 0.3186691 0.04597598 0.9467504 0.3570199 0.08949881 0.9297994 0.3702966 0.1021708 0.9232777 0.9625965 0.2630394 0.06495022 0.3141005 0.07847487 0.946141 0.4258037 0.02021551 0.9045898 0.4361484 0.01391172 0.8997673 -0.1959865 -0.9805812 -0.007063508 -0.003982961 -0.999985 -0.003752708 0.07183611 -0.997403 -0.005197882 0 -0.9935656 0.1132584 -0.9268836 0.375262 -0.008082449 -0.9228287 -0.385149 -0.0068928 -0.92816 -0.3721054 -0.007525444 -0.6351151 -0.7723991 -0.005348622 -0.3851283 -0.9228346 -0.007253348 -0.005326807 -0.9999518 -0.008246064 -0.1354711 -0.9907711 -0.004520952 0.3752656 -0.9268788 -0.008451104 0.447613 -0.8942155 -0.00462383 0.6842297 -0.7292408 -0.006136238 0.8543236 -0.5197266 -0.003953039 0.9557424 -0.2939859 -0.01135373 0.9608812 -0.2767895 -0.009739458 0.9186773 -0.3949666 0.005787134 0.08891516 -0.9960229 -0.00570923 -0.9920059 0 0.1261924 -0.3433213 -0.9387165 -0.03068804 -0.3419046 -0.939641 -0.01327317 -0.3408273 -0.9396805 -0.0289359 -0.3376993 -0.927428 -0.1607378 -0.3055956 -0.8576461 -0.4135876 -0.2899585 -0.7954571 -0.5321393 -0.2350244 -0.6789382 -0.6955621 -0.2159432 -0.5969828 -0.7726449 -0.3400719 -0.937314 -0.07611578 -0.3264512 -0.9018229 -0.2830992 -0.2770751 -0.955325 -0.1028767 -0.2346996 -0.6847384 -0.6899634 -0.234472 -0.6837772 -0.6909933 -0.2249166 -0.9728566 -0.05443012 -0.1203811 -0.723155 -0.6801142 -0.06751394 -0.9448694 -0.3204119 0.6740802 -0.7366157 -0.05489307 -0.6813386 0.7300935 0.05235773 0.05900508 0.5670738 0.8215509 0.2474895 0.9652 0.08448666 0.07198274 0.965729 0.249371 0.1788361 0.9388039 0.2943891 0.1818473 0.9408156 0.2860031 0.0936591 0.7143554 0.6934872 0.1200614 0.6045546 0.7874637 0.2630278 0.9057708 0.3322585 0.261294 0.9630172 0.06575137 0.3419893 0.9396101 0.01327097 0.3415167 0.9394388 0.02865564 0.3400928 0.9382169 0.06392252 0.3398818 0.9334409 0.1147547 0.3410163 0.9374079 0.07052981 0.3404032 0.9327474 0.118777 0.3425553 0.9376003 0.0596804 0.3425099 0.9388004 0.03661966 0.3403589 0.9397158 0.03301709 0.3382273 0.9221501 0.1877278 0.3357431 0.9184055 0.2093033 0.3337869 0.9230124 0.1914013 0.2814643 0.7770899 0.5629469 0.3024658 0.8380844 0.4540143 0.300768 0.8223509 0.4829882 0.2653053 0.7176266 0.643914 0.3188078 0.869284 0.3777657 0.3248388 0.903604 0.2792485 0.5658854 0.8013942 0.1937558 0.327978 0.4301617 0.8410657 0.819781 0.5485239 0.1645626 0.8148392 0.5795421 0.01296371 0.5044912 0.8613196 0.06014406 0.8004325 0.579629 0.1527687 0.5813654 0.7988631 0.1543768 0.5988851 0.5029368 0.6232106 -0.258714 0.9655478 0.0280103 -0.6619007 0.7450553 0.08234256 -0.7055484 0.7055338 0.06651014 -0.9637881 -0.2582407 0.06651639 -0.706825 -0.706826 0.0282039 -0.2582321 -0.9637597 0.06695866 0.7055032 -0.7055038 0.06730216 0.9655579 -0.2587111 0.02768725 0.7068301 0.7068318 0.02793121 0.975468 0.2044677 0.08157902 -0.9538604 -0.2889776 -0.08150088 -0.7791385 -0.4405665 -0.4459199 -0.59135 -0.6757368 -0.4400965 -0.5012505 -0.8009173 -0.3275356 -0.9294105 -0.3659487 -0.04772526 -0.7513653 -0.6506211 -0.1101936 -0.7807403 -0.6196151 0.08075761 -0.3874881 -0.9212988 -0.03257972 -0.07857531 -0.1817851 0.9801939 -0.844137 -0.4342715 -0.3143901 -0.3418657 -0.9303797 -0.1323686 -0.3843191 -0.9225797 -0.0338487 0.9995808 0.01079237 0.02686834 0.9562191 0.2924605 -0.01058816 0.8172389 0.5761958 -0.01091939 0.5761733 0.8172545 -0.01093709 0.4225978 0.9059875 -0.02445369 0.8535557 0.5209326 -0.008487284 -0.005435943 0.9995499 0.02950465 8.72558e-5 0.9999563 -0.009360551 -8.01761e-4 0.9999592 -0.008996009 0.07161754 0.9974294 -0.002357304 0 0.9932782 0.1157525 -0.1916742 -0.3704807 -0.9088482 -0.1876075 -0.378482 -0.9063966 -0.2454339 -0.4796932 -0.8424113 -0.002330124 -0.4267526 -0.9043655 -0.4327075 -0.1980125 -0.87952 -0.3625404 -0.4107914 -0.8365495 -0.3626067 -0.4109084 -0.8364632 -0.6920003 -0.3405875 -0.6365028 0.2582421 0.3151379 0.9132356 0.2252058 0.6307091 0.7426227 4.86738e-4 0.4416381 0.8971932 0.09339553 0.3724207 0.9233527 0.06373852 0.3415649 0.9376944 -0.5829426 0.808095 0.08462077 0.2099367 0.2373496 0.9484681 -0.4108872 -0.5809085 -0.70265 -0.5199123 -0.1767647 -0.8357306 0.8469092 0.4121842 0.3359304 -0.5345765 -0.192184 -0.8229783 -0.7700701 -0.364658 -0.5234659 0.7543023 0.4163615 0.5076133 0.5229534 0.1112926 0.8450643 0.5135669 0.8572738 -0.03648287 0.7068982 0.7068984 -0.02428251 0.8881902 0.4580877 -0.03569275 0.958341 0.2851196 -0.017017 0.8772391 0.4800452 -0.002878785 0.3248052 0.9454886 -0.02351611 -0.5000572 0.8658161 -0.01747405 -0.8581395 0.5134032 0.003753066 -0.8727298 -0.4882033 3.88573e-4 -0.5402165 -0.8406335 -0.03874957 -0.7068583 -0.7068365 -0.02708554 -0.9655927 -0.2587496 -0.02606695 -0.7068281 0.7068323 -0.02797001 0.06905347 0.9969514 -0.03632813 0.03047597 0.9995265 -0.004266202 0.9656226 0.2587332 -0.02510541 0.9992334 0.01548326 -0.03595769 0.9999718 -0.006700158 -0.00340873 0.8632977 -0.5033943 -0.03621393 0.9121386 -0.4096357 -0.01420456 0.7068844 -0.7068842 -0.02508479 0.5135056 -0.8572793 -0.03720635 0.3383359 -0.9408327 -0.01904851 0.5229381 -0.8523583 -0.004600346 -0.999185 0.01030266 -0.0390287 -0.9995939 0.02345639 -0.01618331 0.5390602 0.8422505 -0.005309879 -0.4856411 -0.8739709 -0.01810139 -0.5539624 -0.1708064 -0.8148319 -0.593809 -0.1842951 -0.7832153 -0.099626 -0.9916167 -0.08228588 -0.1223963 -0.9887385 -0.08611255 -0.09318131 -0.9917147 -0.08842694 -0.09303891 -0.9917343 -0.08835613 -0.2035027 -0.9750313 -0.08888638 -0.2044497 -0.9751343 -0.08551955 -0.2226203 -0.9711594 -0.08537954 -0.2218201 -0.9707201 -0.09218734 -0.1548324 -0.9842074 -0.08580625 -0.05387717 -0.9943653 -0.09129613 0.009449958 -0.9960759 -0.08799749 -0.02493977 -0.9959821 -0.08601069 0.0377202 -0.9952722 -0.08950155 0.157366 -0.9838719 -0.08504265 0.1711389 -0.9812121 -0.08907586 0.2058931 -0.974952 -0.08412289 0.1884675 -0.9783765 -0.0852034 0.1570407 -0.9835745 -0.0889917 0.1449781 -0.9857801 -0.0849654 0.1157615 -0.9896126 -0.08524227 0.08440804 -0.9924152 -0.08937317 0.2958257 -0.9509295 -0.09066611 0.3007147 -0.9498493 -0.08577418 0.2758498 -0.9571025 -0.08866679 -0.06263399 -0.9944213 -0.084872 -0.06229054 -0.9942401 -0.08721637 -0.06263136 -0.9942039 -0.08738374 -0.1795196 -0.9798734 -0.08729821 9.13012e-6 3.23205e-5 -1 -5.7443e-6 1.78558e-4 -1 -3.46961e-5 1.50671e-4 -1 9.74211e-4 0.005514323 -0.9999843 3.79488e-5 4.43938e-4 -1 1.64023e-5 4.29753e-4 -1 5.05501e-5 -1.54287e-4 -1 1.84869e-4 -0.001035332 -0.9999995 -3.85449e-6 4.37295e-4 -1 2.43879e-4 -2.21488e-4 -1 -8.12202e-4 0.001423418 -0.9999987 3.40929e-6 -1.8865e-5 -1 -3.55803e-7 0 -1 -2.38965e-5 -6.08543e-5 -1 -3.39267e-6 1.15163e-6 -1 6.31007e-7 -2.20254e-5 -1 1.04694e-4 -1.20523e-4 -1 -1.01529e-4 -8.86353e-4 -0.9999997 3.27328e-6 6.47671e-6 -1 -4.70559e-4 -0.001537799 -0.9999988 -2.022e-4 1.84303e-4 -1 -7.95768e-4 0.001786708 -0.9999982 0.001905083 -4.33957e-5 -0.9999982 0 -0.001422286 -0.9999991 2.75149e-4 0.002527058 -0.9999968 6.43127e-4 0.002396345 -0.999997 0.001045525 -0.001473486 -0.9999984 0.001906692 8.67275e-4 -0.9999978 0.001933097 4.40437e-5 -0.9999982 3.64144e-4 -3.64628e-4 -1 -2.12504e-4 -1.94202e-4 -1 0.002384841 8.16728e-4 -0.9999969 1.96544e-5 3.44322e-5 -1 -2.14641e-7 0 -1 -1.20402e-7 0 -1 0 0 -1 1.77615e-5 3.54982e-5 -1 -3.70376e-4 -0.001140296 -0.9999993 4.6028e-4 -4.77144e-4 -0.9999998 -3.45378e-4 -0.001456439 -0.9999989 0.001412153 -0.001320064 -0.9999982 5.25697e-5 -7.34152e-4 -0.9999998 3.04008e-6 7.89236e-6 -1 1.35061e-4 2.01875e-4 -1 1.78829e-4 2.53531e-4 -1 2.70418e-4 1.2177e-4 -1 6.07519e-5 -1.50397e-4 -1 -0.004849672 0.02164506 -0.999754 -0.006487667 -0.004878222 -0.9999671 -7.14366e-4 0.003212094 -0.9999946 -1.13876e-6 0 -1 -6.06028e-7 0 -1 1.15017e-6 0 -1 5.79836e-7 0 -1 -6.00691e-7 0 -1 -0.002980709 -3.21383e-4 -0.9999956 1.2949e-7 0 -1 -1.98011e-4 -1.93806e-4 -1 -2.85233e-4 -3.05518e-4 -1 2.01169e-4 7.75229e-5 -1 8.13974e-5 -2.57966e-4 -1 -1.31277e-4 7.81863e-4 -0.9999997 -7.01291e-4 -4.2253e-4 -0.9999997 -9.13734e-5 -4.85278e-4 -0.9999999 4.0793e-4 -2.8752e-4 -0.9999999 6.59294e-4 -0.001214265 -0.9999991 1.39152e-4 -0.00161761 -0.9999987 -0.09418928 0.3939931 -0.9142745 2.20026e-7 -0.06589835 -0.9978263 -1.66444e-4 6.69397e-4 -0.9999998 9.94859e-4 -1.20443e-4 -0.9999996 0.1121179 -0.8733557 -0.4740036 0.2427474 -0.9601321 0.1386368 0.1777104 -0.9797837 0.09188634 0.1590236 -0.9856609 0.05642873 -0.1366129 -0.9892376 0.05240082 -0.2049899 0.9676535 -0.1470575 -0.2159529 -0.9730807 0.08048886 -0.1793218 -0.9804152 0.08142328 -0.1135067 -0.989304 0.09161818 -0.2678104 -0.9594337 0.08811682 -0.2315034 -0.9689501 0.08684378 -0.1329001 -0.9868322 0.09219545 -0.1916064 -0.9777864 0.08497589 -0.1502511 -0.984322 0.09238493 -0.1096657 -0.9895482 0.09363585 -0.09043663 -0.9919369 0.08878421 -0.08227545 -0.9912725 0.1030035 -0.07466828 -0.9934875 0.08606642 0.03225517 -0.9958107 0.08556121 0.05551606 -0.9942587 0.09147614 0.08007806 -0.9926849 0.09035688 0.03745102 -0.995985 0.08131045 -0.04644322 -0.9940043 0.09898781 -0.1079581 -0.9899258 0.09160798 -0.01033008 -0.9946582 0.1027054 0.06603586 -0.9942723 0.08403605 0.1266672 -0.988201 0.08610618 0.1144754 -0.9888646 0.09509122 0.1224687 -0.989051 0.08233815 0.233521 -0.9683434 0.08819991 0.1809169 -0.9791293 0.09260076 0.02220511 -0.995338 0.09385704 -0.2672104 -0.9596337 0.08776021 -0.04678499 -0.9957718 0.07905542 -0.1604373 -0.9837588 0.08049041 0.1812264 -0.9800633 0.08144336 0.2003057 -0.9752938 0.09316444 0.01231008 -0.9964439 0.08335512 -0.06542396 -0.9943754 0.08329117 -0.1621958 -0.983101 0.08488225 0.2663688 0.9598653 -0.08778524 0.06480079 0.9944647 -0.08270961 0.04108047 0.9957323 -0.0826416 0.01513177 0.9964322 -0.08302986 0.04151248 0.9947044 -0.09402048 0.05470037 0.9949289 -0.08440589 0.09502482 0.9912956 -0.09112375 0.1380378 0.9867635 -0.08510845 0.1872146 0.9787894 -0.08319902 0.2553592 0.962682 -0.08963817 0.2516897 0.9645224 -0.07968032 0.2154698 0.9731881 -0.08048439 0.175618 0.9804001 -0.08929711 0.2214967 0.9715685 -0.0836296 -0.02297252 0.9962136 -0.08385002 -0.007690906 0.9956469 -0.09288835 -0.008935332 0.9958333 -0.09075391 -0.05910199 0.9944445 -0.08710461 -0.05387151 0.994327 -0.0917167 -0.0729143 0.9938808 -0.08297401 -0.09883946 0.9915725 -0.08375406 -0.1249255 0.9885699 -0.08440047 -0.09757381 0.9910032 -0.09160763 -0.09314346 0.9918285 -0.0871818 -0.09496599 0.9913762 -0.09030348 -0.1106316 0.9902368 -0.08480519 -0.1676373 0.9823758 -0.08267867 -0.1775519 0.9795717 -0.09441697 -0.1896302 0.9786595 -0.07915794 -0.220646 0.9716704 -0.08468872 -0.1934088 0.9769999 -0.08980071 -0.228899 0.9693847 -0.08887422 0.01683408 0.9956458 -0.09168434 -0.0292018 0.9953711 -0.09156215 -0.1291548 0.986668 -0.0990228 -0.5441732 0.8373396 -0.05232506 -0.5443376 0.8372308 -0.05235725 0.3787781 0.9056831 -0.1904348 0.292007 0.7822203 -0.5503304 0.4447311 0.8712341 -0.2077631 0.520456 0.8537981 -0.01242756 0.05865448 0.7805963 -0.6222773 0.3684923 0.924777 -0.09487271 0.2070817 0.4202259 -0.8834747 0.1738075 0.09357458 -0.9803239 0.2310546 0.3993639 -0.8871991 0.1204745 0.08203798 -0.9893208 0.02181965 0.2082751 -0.9778268 0.1172491 0.1326841 -0.984199 0.3236567 -0.9173886 -0.231613 0.2886046 -0.9029399 -0.3184446 -0.5441856 -0.8373308 -0.05233919 -0.5444374 -0.8371478 -0.05264639 -0.5405149 -0.8398321 -0.05025702 -0.7060622 0.7060396 0.05462872 -0.2567296 -0.9581535 0.1266168 0.705838 -0.7058345 0.05992048 -0.1977356 0.9741501 0.1092344 0.8969246 -0.4197754 0.1389787 0.3192251 -0.9436619 -0.0871638 0.5700995 -0.7563886 -0.3207224 0.7046104 -0.6914008 -0.1596531 0.4468886 -0.8821124 -0.1488903 0.8921459 0.0259248 -0.451003 0.9836934 -0.007053256 -0.1797153 -0.2922732 0.9562484 0.01286453 -0.5830016 0.8123558 0.01368892 -0.5730547 0.8194241 0.01235955 -0.8123977 0.5829433 0.01368254 0.9716876 0.03343665 -0.2338914 0.9076425 -0.07302755 -0.4133427 0.8939987 0.01742607 -0.4477307 0.5394756 0.786118 -0.3016365 0.3835631 0.9157202 -0.1197327 0.817937 0.5368679 -0.2067655 0.7773895 0.4551048 -0.4342181 -0.9562171 -0.2922881 0.01471501 -0.9661022 -0.2579298 0.01090955 -0.8123819 -0.5829656 0.0136767 -0.8194653 -0.572996 0.01234632 -0.2570543 -0.9663358 0.01088505 -0.2922681 -0.9562164 0.01515108 -0.04661113 -0.9987878 0.01582026 -0.9650424 -0.2586081 0.0426048 -0.9656684 0.2318091 0.1172564 -0.08487105 0.9866432 0.1390404 0.952195 0.2820976 0.1172427 -0.257709 -0.9617891 0.0924552 -0.9581444 0.2567595 0.1266256 -0.2577055 0.9617804 0.09255492 0.2583519 0.964187 0.05998313 0.7064768 0.7064502 0.04264706 0.9581611 0.2567008 0.1266178 0.2584319 -0.964487 0.05457073 0.4979336 -0.8628149 -0.08725017 0.4980896 -0.862734 -0.08716011 0.4981001 -0.8627257 -0.08718198 0.4980969 -0.862729 -0.08716851 -0.5407919 -0.8399691 -0.04467844 0.3311852 -0.9336818 -0.1362165 0.9844603 -0.1738032 -0.02510797 0.3191502 -0.9436879 -0.08715659 0.999929 0 0.01191973 0.9999337 -0.00941509 -0.006651103 0.3294565 0.944041 0.01565754 0.6482101 0.7613946 0.01010763 0.8988643 0.4380953 0.01075112 0.9313828 -0.363844 0.01198756 0.7070595 -0.7070424 0.01256948 0.37212 -0.9280917 0.01313996 -0.04053241 -0.9991135 0.01138293 -0.02276712 -0.9996465 0.01373422 -0.7385076 -0.6740865 0.01462912 -0.06651902 -0.9977496 0.008437752 4.33905e-7 -0.9959265 0.09016889 -0.01894819 -0.9996798 0.01676952 0.4963594 -0.5264002 -0.6903117 -0.01902568 0.999678 0.01679313 -0.04813522 0.9987311 0.01480913 -0.05936682 0.9981625 0.01213181 -0.06668376 0.9977388 0.008402228 -4.65003e-7 0.9960054 0.08929306 0.4953368 0.5280867 -0.6897578 0.2872081 -0.9578222 0.009394645 0.9101748 -0.4139764 0.01433902 0.9996466 -0.02276259 0.01373082 0.7070605 0.7070412 0.01258248 0.6474823 -0.7620139 0.0100767 0.9991127 -0.04054951 0.0113781 0.9313791 0.3638531 0.01199287 -0.02276778 0.9996744 0.01152282 -0.4139754 0.9102215 0.01102316 -0.438086 0.8988212 0.01418846 -0.9440386 0.329463 0.0156629 0.999929 0 0.01191973 0.9990975 0.03929471 0.01613157 0.9999485 -0.001952052 -0.009970307 0.3191148 0.9437 -0.08715629 0.3270462 0.920942 -0.2119122 0.3184361 0.9438258 -0.08826929 0.987686 0.1433813 -0.06259477 0.9728133 0.2047044 -0.1083076 3.07223e-7 0.9998478 -0.01745325 -0.002269327 0.99982 -0.01883661 2.09763e-4 0.9998489 -0.01738286 2.68711e-4 0.9998467 -0.01751041 2.10661e-4 0.9998458 -0.01756274 -0.00275892 0.9998365 -0.01787692 0.4609949 0.8830594 -0.08769184 0.3539907 0.931155 -0.08741289 0.3667576 0.9262508 -0.08688122 0.4980967 0.8627305 -0.08715474 0.4980965 0.8627305 -0.08715552 0.498097 0.8627302 -0.08715534 0.4580436 -0.8849251 0.08428424 -0.5019881 -0.8611372 0.08031642 -0.4980968 -0.8627303 0.08715504 -0.4955259 -0.8647296 0.08183485 -0.367728 -0.9258086 0.08749151 -0.4574502 -0.8849232 0.08746749 -0.3191305 -0.9436968 0.08713293 -0.3191138 -0.9437003 0.08715701 -0.3191143 -0.9437002 0.08715575 1.43967e-4 -0.999846 0.01755267 1.42205e-4 -0.9998461 0.01755124 -6.88867e-4 -0.9998036 0.01980948 -0.001370191 -0.9997977 0.02006936 -0.001754105 -0.9998368 0.01798307 -9.5008e-6 -0.9998475 0.01746451 -2.73964e-4 -0.9998578 0.01686662 -0.3481395 -0.9273195 0.137395 -0.3731964 -0.9144656 0.1564515 -0.5530859 -0.1060894 0.826342 -0.7997129 -0.07951807 0.5950935 -0.8857905 -0.2553028 0.3875508 -0.9350358 -0.2563016 0.2449852 -0.7123348 -0.6886789 0.13528 -0.9141137 -0.1988885 0.3533265 -0.9647763 -0.1654084 0.2045647 -0.4673374 -0.870294 0.1555128 -0.5416966 -0.1962398 0.8173462 -0.5791845 -0.5148584 0.6320333 -0.6059759 -0.5309435 0.5923616 0.06729561 0.9942902 0.082816 0.08634442 0.9395194 0.3314333 -0.4722358 0.8700447 0.1414768 -0.3422148 0.8093292 0.4773629 -0.259428 0.8110231 0.5243461 -0.467218 0.8653507 0.1813164 -0.474164 0.8700037 0.1351373 -0.1735613 0.8197954 0.5457216 -0.2934459 0.8243366 0.4841062 -0.03170043 -0.2988663 0.9537684 -0.01605182 -0.3369683 0.9413793 -0.06172418 -0.02812731 0.9976969 -0.117187 -0.02490627 0.9927976 -0.1158577 -0.05590337 0.9916915 -0.0876767 -0.0882982 0.992228 -0.1030883 -0.01510745 0.9945575 -0.08020484 -0.008263766 0.9967442 -0.0367794 -0.2516521 0.9671187 -0.1974744 -0.04700356 0.9791805 -0.2076584 -0.7043419 0.6788082 -0.2601395 -0.789421 0.5560054 -0.3476511 -0.8984459 0.2682048 -0.406017 -0.8929432 0.1944298 -0.1717518 -0.9317455 0.3199245 -0.4831997 -0.8673922 0.1189494 -0.4310318 -0.8829032 0.1862627 -0.2672178 -0.803799 0.5315091 0.3838804 0.5202692 -0.7628603 0.2835793 0.1971926 -0.9384551 0.3267769 0.9212276 -0.2110844 0.3496534 0.9176118 -0.1890267 0.4714503 0.4204488 -0.7752144 0.3950538 0.4838007 -0.7809414 0.3816391 0.7322937 -0.5640015 0.3478854 0.9223444 -0.1680976 0.4435737 -0.719648 -0.5341809 0.8967318 -0.005722522 -0.4425374 -0.2174774 0.9760393 -0.007140934 -0.9488886 0.3021263 0.09126943 -0.573054 -0.8195133 -0.002680182 -0.2563492 -0.9636515 -0.07523953 -0.6769159 -0.06637555 0.7330616 -0.6231129 -0.06160873 0.7797018 -0.2057802 -0.9784104 -0.01917582 -0.436949 -0.8964968 -0.07327425 -0.04048418 -0.9979292 -0.04998505 0.1980447 -0.9800259 -0.0180971 0.9295086 -0.3631169 -0.06449699 0.9934638 -0.1083014 -0.03606182 0.6418503 0.7633782 -0.07267701 0.2903127 0.9544054 -0.06949013 0.6751785 0.1822869 -0.7147765 0.5754848 0.3113011 -0.7562467 0.619405 0.09996294 -0.7786815 0.2197044 -0.9744732 -0.04617291 0.286647 -0.9559432 -0.06329417 0.9962407 -0.07832735 -0.03700524 0.9406102 0.3380126 -0.03162312 0.9307348 0.3635941 -0.03914403 0.3119615 0.9485212 -0.05465936 -0.0405333 0.999131 -0.009711325 -0.1973772 0.9775766 -0.07339185 -0.4344058 0.8912805 -0.1300418 -0.774103 0.6329414 -0.01223891 0.2548908 0.506899 -0.8234587 0.2504127 0.7903687 -0.5591161 0.6018785 0.7791976 -0.1749103 0.1724689 0.7641111 -0.6216018 0.5828368 0.6944958 -0.4218733 0.08526372 0.1617007 -0.9831495 0.425994 -0.8976884 0.112627 -0.4395594 -0.8831229 0.1639562 -0.02349984 -0.5269282 0.8495849 -0.2607122 -0.8810956 0.3945881 -0.4159407 -0.729269 0.5432864 -0.5899362 -0.3813986 0.7116955 -0.6782208 -0.7103614 0.1881574 0.6343382 -0.2119723 0.7434265 -0.4450284 -0.5802612 0.6820901 -0.3792844 -0.8060399 0.4543603 -0.3591458 -0.8676956 0.3436841 -0.3919364 -0.4742977 0.7883068 -0.4531225 -0.2250406 0.8625757 -0.3562399 -0.9087319 0.2174845 -0.3797407 -0.8892255 0.2550981 -0.3661854 -0.6811835 0.6339538 -0.389986 -0.1136892 0.9137756 0.253845 -0.9629825 0.09070467 -0.4952357 -0.310962 0.8111994 -0.5626605 -0.1737417 0.8082247 0.2148499 -0.3199157 0.9227641 -0.8849223 0.106377 0.4534275 -0.2586739 0.9654341 -0.0320127 0.2586635 0.9653845 -0.03355765 0.6986421 0.7142273 -0.04217356 0.7065311 0.7064906 -0.04104745 0.9984324 -0.004513204 -0.05579042 -0.9989467 -0.003217756 -0.04577302 -0.6401946 -0.7670986 -0.04136174 -0.2586746 -0.9654334 -0.03203004 0.2586702 -0.9653825 -0.03356355 0.7065527 -0.7065048 -0.04042595 -0.9655095 -0.2586287 -0.03004193 -0.706701 -0.7066842 -0.03422158 -0.6461028 0.7621444 -0.04107487 -0.6461694 -0.7620882 -0.04106944 -0.9654855 -0.2587333 -0.02991247 -0.6402166 0.7670802 -0.04136204 0.04009878 0.9980605 -0.04761797 0.7065507 0.7065067 -0.0404269 0.03985983 -0.9980594 -0.04783982 0.6648175 4.16925e-4 -0.7470057 0.6272853 2.13862e-4 -0.7787895 0.6444168 -0.0110256 -0.7645951 0.6864666 0.01229059 -0.7270576 0.6648064 -4.13964e-4 -0.7470155 0.1614084 -0.9855275 -0.05179762 0.90591 0.4187573 -0.06300354 -0.9415308 0.1831905 -0.2827741 -0.4960358 0.86669 -0.05288636 -0.9082214 -0.3680393 -0.1992012 -0.6930075 0.7208759 0.008871018 0.4751491 0.8584417 -0.1931613 0.06823474 -0.06917458 -0.9952682 0.9324499 0.3575853 -0.05167114 -0.5879688 0.8074301 -0.04847037 0.1493946 0.001055479 -0.9887772 0.07174235 0.06290441 -0.9954377 -0.9414966 -0.1832341 -0.2828595 0.9059053 -0.4187627 -0.06303709 0.9710181 -0.2316357 -0.05889821 0.162238 0.9853889 -0.05184245 -0.9024872 0.4197318 -0.09665435 -0.9389088 0.03380179 -0.3425021 0.551824 0.1746634 -0.8154649 -0.674738 -0.7377139 -0.02251374 0 -0.9907623 -0.1356101 0.6711527 -0.733551 -0.107038 0.9688599 -0.02569943 -0.2462726 -0.7726793 -0.5295148 0.3501155 0.8238387 -0.5372626 0.1806619 0.8540536 0.4187825 0.3085674 -0.9352557 -0.309729 -0.1713619 0.620054 -0.4620321 -0.6340816 -0.24356 -0.4846353 -0.8401233 0.05668908 0.7864881 -0.6149984 0.5492942 -0.7176523 -0.4280785 0.8572782 -0.3176144 0.4052101 0.3427274 0.9370073 -0.06749314 -0.3148756 0.9490438 -0.01301348 -0.8703317 0.4923734 0.009548604 0.008405268 -0.005618751 -0.999949 -0.5909036 -0.6250653 -0.510026 0.0029881 0.007663369 -0.9999662 0.03145128 -0.01217389 -0.9994313 -0.03275692 0.01642286 -0.9993284 -0.9337208 -0.2998784 0.1955468 -0.894675 0.4207513 0.1500836 -0.1250138 0.9653086 0.22924 0.01226955 4.16018e-4 0.9999247 0.0170347 0.01443219 0.9997508 0.03194618 -0.02957862 0.9990519 -0.005474388 -0.05879563 0.9982551 -0.01042038 0.02113145 0.9997225 -0.05454748 0.09561336 -0.9939229 0.1107089 0.2008328 -0.9733498 0.0475521 -0.04130005 -0.9980146 -0.0341438 -0.009351074 -0.9993733 -0.006763219 0.01250177 -0.999899 -0.9762514 0.1340192 -0.1702122 0.8261485 0.2669078 -0.4962247 -0.674736 -0.7377155 -0.02252578 0.6711499 -0.7335534 -0.1070387 0.968859 -0.02570408 -0.2462754 0.5448946 0.7974546 -0.2591447 -0.06705707 0.9194982 0.3873327 -0.9442451 0.2128428 0.2511961 -0.7342613 -0.6640894 0.1408742 0.8238404 -0.5372601 0.1806619 0.854054 0.4187818 0.3085674 -0.2684925 0.8619873 -0.429988 -0.3150624 -0.5287293 0.7881505 -0.3063457 0.4352601 0.8465819 -0.3310471 -0.3017495 -0.8940666 -0.2229589 -0.9675357 0.1190131 0.7531428 0.6576483 -0.01658248 0.7289945 -0.6734703 -0.1224942 -0.01126903 0.01310551 -0.9998507 0.006912946 -0.006918251 -0.9999523 0.04696768 0.002912402 -0.9988922 -0.6507821 0.7186539 -0.2449883 0.02498167 -0.02621102 -0.9993442 -0.001273572 6.30205e-4 -0.9999991 7.80348e-4 -0.001283109 -0.9999989 -0.01152187 -3.73334e-4 -0.9999336 -0.008113145 -0.03025519 -0.9995093 0.4384872 -0.7572978 -0.483972 -0.0276035 0.01275074 0.9995377 5.22789e-4 -0.05803036 0.9983147 0.002965211 -0.008120357 -0.9999626 0.002966761 -0.008120894 -0.9999627 0.0353474 0.0832678 -0.9959001 -0.001713633 -0.004108071 -0.9999902 0.04203939 -0.04313302 -0.9981846 0.06273931 -0.05337256 -0.9966019 0 -0.1983677 -0.9801277 0.03210186 0.01008838 -0.9994338 -0.05457651 -0.02150565 -0.998278 0.8268774 -0.03487646 -0.5613 0.968747 0.154781 -0.1938359 0.4247668 0.6067473 -0.671886 -0.5594795 0.8137181 -0.1576244 -0.6761994 0.7342737 0.05997169 -0.6747402 -0.7377119 -0.02251583 0.7203255 -0.6805114 -0.1342965 0.9433758 -0.1885594 -0.2729238 0.8013874 0.5962854 -0.04714089 0.2579945 0.9648684 -0.04967761 0.0695917 0.969928 0.2332313 -0.7342629 -0.6640899 0.1408642 0.1666013 -0.9788961 0.1183492 0.7432762 -0.004746019 -0.6689679 -0.4230564 0.630105 0.6511459 0.4028066 0.9111244 0.08717358 0.7979933 -0.2788 -0.5343008 0.4113987 -0.9104543 -0.04270976 0.5219267 -0.8512932 0.05378258 -0.505288 -0.6997464 -0.505014 -0.8718113 -0.4876739 0.04603791 0.9844285 0.1552673 0.08241862 -0.4358052 -0.897362 -0.06939291 -0.03473234 -0.06111097 -0.9975265 0.1483315 -0.07086622 -0.9863954 7.28625e-5 -2.83624e-4 -1 0.007167041 0.002121984 -0.9999721 -0.03231608 -0.1773762 -0.9836125 -0.9685677 -0.1191334 0.2183661 0.01478993 -2.36609e-4 0.9998907 -0.01587551 -0.01043969 0.9998195 8.34887e-4 -0.01271468 0.9999188 -0.00153464 -0.004094481 0.9999905 -0.02389168 0.06761932 -0.9974251 0.004516422 -0.01204526 -0.9999173 0.01465374 -0.001400291 -0.9998917 -0.0403307 9.3389e-4 -0.999186 0.07410299 0.04280066 -0.9963317 2.10611e-7 -0.196371 -0.9805298 -0.08614712 -0.02446776 -0.9959819 0.007390141 0.02398061 -0.9996852 -0.5215877 -0.5918961 -0.6144959 0.2336553 -0.9722594 -0.01081377 -0.5389288 -0.5903926 -0.6008265 0.9411095 -0.1040538 -0.3216922 2.00903e-6 -0.9907629 -0.1356061 0.6711559 -0.7335489 -0.1070318 0.2619497 0.9636769 -0.05205148 0.06955301 0.9694073 0.2353974 -0.7726786 -0.5295132 0.3501195 0.1666017 -0.9788962 0.118348 0.8238348 -0.5372669 0.1806668 0.8744094 0.4290038 0.2266358 -0.850398 -0.5189505 -0.08668243 -0.6569989 -0.6768012 0.3321034 0.9451998 -0.1961922 -0.2609714 0.6306204 -0.775259 0.03593796 0.1379533 0.9845792 0.107577 -0.2347941 -0.9415678 -0.2414992 -0.6067221 -0.7927491 0.05862939 -0.9987 -0.0509743 0 0.5974401 -0.8018885 0.006345808 0.299967 0.9531141 0.03991836 -0.2115437 0.9593213 0.1869552 0 -1.3286e-4 -1 7.5874e-4 3.69898e-4 -0.9999997 0.9895048 0.1363025 -0.04797786 -0.5833724 0.8029307 -0.1223888 0.1945399 0.9800938 -0.03962761 1.23087e-4 -2.99067e-4 -1 -0.0603519 -0.2064492 -0.9765944 -9.46149e-5 -4.64262e-4 -1 0.00113213 0.005749046 -0.9999829 0.01390713 -0.001469194 -0.9999023 -0.2962856 0.2785561 0.9135762 -0.9728116 -0.231598 0 0.01681315 0.9014163 0.4326269 -0.01860278 -0.9973587 -0.0702117 0.4948981 -0.8628535 0.1027605 -0.01999711 -0.02157849 0.9995672 -0.03944349 0.02046012 0.9990124 -0.03440856 -0.01677632 0.9992671 0.0270363 0.03687262 0.9989542 -0.003280282 -0.02062565 0.999782 -0.02326893 0.06580322 -0.9975613 2.94972e-4 -2.76056e-4 -1 3.06148e-4 -1.21645e-4 -1 -0.1217868 0.05210798 -0.9911876 -0.01149296 -0.01717025 -0.9997866 0.09450566 -0.1005268 -0.9904358 -0.1525142 0.7251375 -0.6715021 0.09619706 -0.8556343 0.508563 4.65971e-5 -0.9998438 0.01767599 0.9809311 -0.003392159 -0.1943262 0.9809316 -0.003392994 -0.1943238 -0.9809309 0.003392219 0.1943275 -0.9809317 0.003397047 0.1943234 0.4063203 -0.6191675 0.6719639 0.241796 -0.9121007 -0.3310696 -0.2827293 -0.7800213 -0.5582392 -0.3945759 -0.7587741 -0.5182393 0.19541 -0.9220847 0.3340283 -0.2000778 -0.01937413 -0.9795885 -0.1855378 -0.02223241 -0.9823857 -0.2181216 -0.03698098 -0.9752207 0.9809334 -0.003391385 -0.1943145 0.9809165 -0.003627657 -0.1943956 0.9808833 -0.003396987 -0.1945675 0.9809855 -0.003009736 -0.1940575 0.1943527 0.01711815 0.9807823 0.195999 0.0161646 0.9804709 0.1943552 0.01711934 0.9807819 0.1855439 0.0120635 0.982562 -0.9809306 0.002587258 0.1943411 -0.9805019 0.00343424 0.1964801 -0.9812782 0.003372669 0.1925662 -2.7383e-6 -0.9998477 0.01745551 3.86778e-6 -0.9998475 0.01746588 1.16069e-6 -0.9998478 0.01745176 -3.19427e-6 -0.9998477 0.01745784 -2.62598e-6 -0.9998477 0.01745575 6.40387e-6 -0.9998478 0.01745128 1.56801e-6 -0.9998477 0.01745688 9.61541e-7 -0.9998478 0.01744484 -0.02109158 -0.01744848 -0.9996253 0.3221531 -0.01652103 -0.9465434 0.3221483 -0.01652204 -0.946545 0.6265099 -0.01360183 -0.7792949 0.6261532 -0.01367312 -0.7795802 0.9882263 0.002669751 0.1529762 0.02030915 0.01756042 0.9996395 -0.6265123 0.01360255 0.7792929 -0.9823634 0.003292143 0.186953 -0.8763664 -0.008407175 -0.4815717 -0.3617567 -0.01627397 -0.9321306 0.8553009 -0.009010076 -0.5180535 0.9809315 -0.003398418 -0.194324 0.9882456 0.002650201 0.1528514 0.6587828 0.01313 0.7522187 0.02106297 0.01745241 0.9996259 -0.3221477 0.01658499 0.9465442 -0.6265102 0.01360183 0.7792947 -0.9809301 0.002368092 0.194347 -0.9882465 -0.002674698 -0.1528456 -0.658782 -0.0131309 -0.7522194 0.006948947 0.9998719 -0.01442265 0.001200795 0.9998699 -0.01608675 0.004562735 0.999878 -0.0149458 -0.09990477 0.9892242 0.1070261 -0.05592381 0.9980905 0.02622902 -0.006998896 0.9997635 -0.02058982 -0.2849709 -0.934078 -0.2151513 -0.5157133 -0.04971426 -0.8553177 -0.5079823 -0.815277 -0.2779883 -0.8050137 -0.327468 -0.4946895 -0.9818164 -0.0281372 0.1877365 0.003726363 -0.2957214 0.9552671 -0.8701046 -0.1061109 0.4813094 0.6249536 0.01222866 0.7805662 -0.406151 -0.006033658 -0.9137861 -0.9437311 -0.01123803 0.3305228 -0.1450952 0.005132555 0.9894044 0.3134409 0.0224446 0.9493425 0.5308206 0.01333302 0.8473793 0.9855138 -0.01875048 -0.1685555 0.7218792 -0.03673827 -0.6910432 0.2993145 -0.005411386 -0.9541392 0.089019 -0.03533709 -0.9954029 -0.1178668 -0.0197131 -0.9928337 0.326985 -0.1307545 0.9359402 0.6173196 -0.4213478 -0.6643664 0.1647439 -0.9745534 0.1520045 0.2184594 0.9651516 -0.1440758 0.991782 -0.06908392 -0.1076843 0.9952884 -0.04258525 0.08710753 0.6312934 -0.10085 -0.7689591 0.980703 -0.02727741 -0.1935917 0.2531959 0.5368365 -0.8047972 0.8570325 0.2300789 0.4610412 -0.8807854 -0.01108425 -0.4733861 -0.8974591 0.01684808 -0.4407759 -0.5452739 0.05070698 0.8367229 0.7749177 -0.01824015 0.6317991 0.4597104 -0.02624154 -0.8876813 -0.563481 0.05736541 0.824135 0.887535 0.02801477 0.4598879 0.9945846 0.006463229 0.1037296 -0.905723 0.408653 -0.1125553 0.102407 0.9844112 -0.1429947 0.01109111 0.9995585 0.02756851 0.01837372 0.999807 -0.006950497 0.04430365 0.8447722 -0.5332891 -0.3015236 0.8589118 -0.4139495 0.7307567 0.005691945 -0.6826144 0.7241488 0.406248 0.5572891 -0.8598346 0.1225635 -0.4956436 -0.7427906 -0.01204895 0.6694154 0.242038 0.135971 0.9606922 -0.8738878 -0.393423 -0.2855498 0.3781319 -0.2507085 0.8911575 0.2995703 0.6612713 -0.687734 0.4646164 0.07836645 0.8820377 -0.6584304 -0.5841567 0.4745844 0.9439455 0.2550299 -0.2095867 0.533943 -0.1103467 -0.8382891 -0.6995507 0.5891519 0.4043871 0.03253102 0.5193294 0.8539548 0.9522729 -0.179407 0.2469605 0.2804962 -0.6573663 -0.6994222 -0.1077151 0.06756228 -0.9918835 -0.7411563 -0.0424695 0.6699879 0.198919 -0.9734539 0.1132193 -0.1965699 0.03464704 -0.9798775 -0.8540344 0.3771396 0.3583168 0.7364917 -0.01155996 -0.6763479 -0.7472395 -0.1150277 -0.654524 0.8841176 -0.4094272 -0.2251789 0.2149222 0.2642955 -0.9401896 0.9048736 -0.3206121 0.2800211 -0.4180831 0.4821214 -0.7699127 0.08003699 -0.628888 0.7733654 -0.01196753 0.9993894 0.03282743 0.8607571 0.4662947 0.2041237 0.169671 0.1158906 0.978663 -0.6469908 0.2027628 0.7350443 -0.441411 -0.05324333 0.895724 -0.5971611 0.04052102 0.8010972 -0.971578 0.07880753 -0.2232168 0.02169603 0.0890035 -0.9957951 0.9527331 0.08968204 -0.2902705 0.4757406 0.07740986 0.8761729 0.8300024 -0.04055964 0.5562831 0.3557708 0.9095176 -0.2149537 -6.34329e-4 0.9998402 -0.01787108 -0.1050139 0.9906063 -0.08758628 -0.2738335 0.9611424 -0.03493797 -0.2091483 0.9738278 -0.08897501 -0.2010118 0.976158 0.08191448 3.85575e-7 0.9998478 -0.01744967 3.07902e-6 0.9998478 -0.01745361 0.06478446 0.9929662 0.09910273 -0.23174 0.9515764 -0.2019875 -0.9937094 0.07938253 0.0789951 -0.1264055 0.6732085 -0.7285684 -0.165064 -0.4991268 -0.8506623 -0.01580804 -0.9963645 -0.0837121 0.2238031 0.3246119 0.9189882 -0.02947938 0.9978287 -0.05889809 -0.2089655 0.07309776 -0.9751873 0.6091824 -0.4411096 -0.659029 -0.4849973 0.6129688 -0.6237363 -0.3450741 0.5569291 -0.7554825 -0.4595598 0.871965 -0.1687656 0.3470873 0.9243756 -0.1583043 0.561307 0.3983597 -0.7254268 0.8844676 0.4011795 -0.238269 0.2417959 0.70537 -0.6663241 0.550166 -0.7577193 -0.3509684 -0.8951107 -0.2126179 -0.3918805 -0.2557771 -0.1603929 -0.9533374 0.8048997 0.57153 -0.1596564 0.566963 0.8164146 -0.109637 -0.5619385 0.8226416 0.08652144 -0.8068504 0.5662553 0.1683667 -0.5686688 -0.8151677 0.1100795 0.5678384 -0.808681 -0.1536058 0.9539666 -0.2247545 -0.1985781 0.9654726 0.1750926 -0.1928865 -0.2534334 0.966294 0.04524898 -0.8426904 -0.5124794 0.1650387 -0.5605652 -0.8211935 0.1068084 -0.2313946 -0.9715238 0.0509721 -0.4023681 -0.9154663 -0.004630088 -0.3190878 0.6693069 0.6709779 -0.6485751 -0.6661129 0.3682988 0.9676351 0.2518333 -0.01619678 -0.5441669 0.8111755 -0.2141885 -0.0778554 -0.9263535 -0.368521 0.8104873 -0.5852746 -0.02375197 0.4193742 -0.8853206 0.2008302 0.8186029 0.5724184 0.04718756 0.9519272 0.204486 -0.2280792 -0.2386271 -0.9545651 0.1785015 -0.4824019 0.8759464 -0.002548575 0.3890042 0.918215 -0.07454645 -0.1943162 0.001023888 -0.9809384 -0.8503584 -0.3765969 0.3675126 0.4374186 -0.8929266 -0.1065222 -0.1201987 0.3204332 -0.9396142 -0.3513525 -0.1174154 -0.9288515 0.9596275 -0.1983894 -0.1993911 0.542034 -0.833355 -0.1082536 -0.5492518 -0.8295517 0.1008292 -0.8149931 0.5583738 0.1549361 -0.1879082 0.9814412 0.03826028 0.816022 0.552733 -0.1690995 0.1879076 -0.9814411 -0.038262 -0.9198755 -0.3511942 0.1746188 -0.915599 0.3586676 0.1817587 -0.3457112 0.9362748 0.06223553 0.1948292 0.9801177 -0.03756195 0.7024148 0.6981806 -0.1384104 0.9570909 0.1701847 -0.2345512 0.8421354 0.4966392 -0.2101365 0.6244916 0.7632275 -0.1658133 0.5379264 0.8286648 -0.1547573 -0.5507793 0.8324251 0.06091618 -0.821928 0.5578083 0.1152575 -0.9692961 0.1982688 0.1454463 -0.8249977 -0.5522102 0.1201784 -0.8596059 -0.4964397 0.1209352 0.8386092 -0.5024226 -0.2104902 0.8035702 -0.5577111 -0.2079266 0.532051 -0.83234 -0.1553448 0.323822 -0.9399926 -0.107487 -0.5566303 -0.8285675 0.06032168 -0.204039 -0.9789102 -0.0101422 -0.974543 -0.1700811 0.1460769 -0.6354494 0.7675834 0.08378517 -0.3399798 0.9400735 0.02599579 -0.004509031 0.9991811 -0.04021233 0.3304473 0.9377602 -0.1068197 0.9558655 -0.1767757 -0.2346734 0.2028415 0.791982 0.5758646 -0.3154171 -0.6740567 0.6679519 0.03512763 -0.1147874 0.9927689 -0.009519219 -0.1323124 0.9911624 0.003524899 0.9999938 3.56185e-4 0.1250472 -0.04148763 0.9912831 0.2457345 0.001338183 0.9693363 0.2437984 -0.007317125 0.9697984 0.1943206 -0.001034438 0.9809376 0.1943216 -0.001034379 0.9809373 0.1943212 -0.001034677 0.9809375 0.5146033 0.04619556 0.8561831 0.8163388 0.1930813 0.5443443 -0.9809324 0.003391623 0.1943196 -0.9808911 0.003390073 0.1945288 0.4548098 -0.8884513 -0.06166315 0.214696 -0.9751646 -0.05440473 0.8477097 -0.5030035 -0.1684514 0.627914 -0.7681466 -0.1251992 0.2949939 -0.9538606 -0.05593442 0.03583276 -0.9993249 -0.008121311 -0.9398139 -0.3126443 0.1378533 -0.9652532 -0.1728346 0.1959966 -0.9773616 0.07115346 0.1992526 -0.9719192 0.1376357 0.1908651 -0.7634188 0.6239427 0.1669954 -0.9565497 -0.2204456 0.1908311 0.9768783 0.109857 -0.183413 0.9747026 0.1030205 -0.198347 0.9666595 0.1703025 -0.1912238 0.8518454 0.497056 -0.1652114 0.002408564 0.9999831 -0.00530827 -0.3332664 0.9408347 0.06134784 -0.8482083 0.502941 0.1661116 -0.8726299 0.4561172 0.1745686 0.1583453 0.9870524 -0.02558088 -0.1495627 0.9881179 0.0354157 -0.6843769 0.7158238 0.1386526 -0.6899978 0.7105109 0.1381211 -0.849944 -0.4970601 0.174718 -0.6332336 -0.7638592 0.1246372 -0.9791042 0.1694712 0.1124036 -0.1591146 -0.6932532 0.7029102 -0.1133105 -0.2844098 -0.9519832 0.005785584 -0.9972815 0.07345938 -0.3165805 0.7123675 -0.6263459 0.963236 -0.003300666 -0.2686367 0.979101 0.06139934 -0.1938852 0.9896168 -0.003088533 -0.1436983 0.9863136 -0.03787529 -0.1604709 0.32089 -0.006869554 0.9470916 0.3103701 0.05852687 0.9488125 0.7838829 -0.6199069 -0.03525763 0.6434431 -0.7649791 0.02807432 -0.008031606 0.008821904 0.9999288 -0.004888296 -6.38901e-4 0.9999879 -0.9179129 0.3952142 0.03524196 0.9999613 -4.36574e-4 0.00879389 0.1797099 -0.9836814 0.008679747 0.9832615 0.1819912 0.008724868 -0.1866121 0.9823929 0.008966326 -0.1863519 0.9824447 0.008688509 0 -0.9999619 0.008726239 -0.9999707 8.25632e-4 0.00761497 0.435553 -0.1893671 0.8800193 0.9503152 -0.02890658 0.3099445 0.3334128 -0.9125708 0.2367501 0.3471186 -0.3285895 0.8783721 0.2640048 -0.1520467 0.9524617 0.2821171 -0.2112393 0.9358355 0.3356172 -0.8794822 0.3374499 0.3303672 -0.9055559 0.2661315 0.3220494 -0.3516398 0.878996 0.3430855 -0.5526245 0.7595384 0.4960912 -0.8450819 0.1993244 0.4658477 -0.8607752 0.2050654 0.8355955 -0.444047 0.3234233 0.2839083 -0.2997235 0.9108029 0.7378211 -0.6209017 0.2647665 -0.2615867 0.1051452 -0.9594358 -0.3346681 0.8904564 -0.308358 -0.2156696 -0.0812729 -0.9730784 -0.4894069 0.4533908 -0.7449279 -0.4095963 0.197386 -0.8906569 -0.723676 0.4108763 -0.5545031 -0.372668 0.9057823 -0.2016854 -0.4586056 0.8513814 -0.2546183 -0.7560976 0.5449406 -0.3624312 -0.9156883 0.1658815 -0.3660579 -0.8072093 0.5323612 -0.2549602 -0.5941581 0.7777728 -0.2050507 -0.8884968 0.3918701 -0.2387707 -0.9812248 0.03901284 -0.1888808 -0.9429372 0.3013513 -0.1416224 -0.975737 0.2006565 -0.08760309 -0.3319959 0.8795394 -0.3408654 -0.3477151 0.8045906 -0.4813817 -0.3109555 0.3119215 -0.8977816 -0.3581899 0.695874 -0.6224624 -0.5382155 0.6593708 -0.5249328 -0.6544347 0.4876824 -0.5778246 -0.9447368 0.2628422 -0.1959248 -0.5796601 -0.8148448 -0.004713475 0.01802897 -0.9997619 0.01229059 0 -0.9998478 0.01745146 -0.01921546 -0.9996336 0.01906514 0 -0.9998479 0.01744687 0.9998369 9.76322e-4 0.01804232 0.970564 0.2368524 0.04366642 -0.08714312 -0.996043 -0.01745289 -0.8308359 0.001459658 -0.5565158 -0.8307958 0 -0.5565775 1.18725e-6 -1.42185e-6 1 -0.9982577 0.004621803 -0.05882459 -0.7015153 -0.5608929 0.4396313 -0.6113454 -0.6366567 0.4700269 0.009941399 -0.9991488 -0.04003626 -6.31279e-4 -0.9986307 -0.05231076 0.03304553 -0.9994457 -0.004024207 0.9986304 4.73546e-4 -0.05231922 0.9990932 0.01774871 -0.0387035 6.51682e-6 0.9998476 -0.01746028 3.14059e-5 0.9998475 -0.01746523 -2.90206e-6 0.9998478 -0.01745051 -1.28168e-5 0.9998478 -0.01745307 -6.95028e-7 0.9998477 -0.01745283 -0.9986296 6.05178e-6 -0.05233585 -0.9987705 0 -0.04957318 -0.8709629 0.09871023 0.4813315 -0.9683333 -0.2320412 0.09212946 -0.6039233 0.02355611 0.7966943 -0.007014632 0.9999059 0.01179093 4.04695e-7 0.999962 0.008726418 -3.10233e-5 0.999962 0.008730947 0 0.9999619 0.0087381 -2.25238e-5 0.9999672 0.008102595 -0.8027493 0.5855608 -0.1127486 0.5137455 0.8536134 0.08608037 0.7025275 -0.7111239 0.02753132 0.00486499 -0.9997137 0.02342981 0 -0.9998478 0.01745271 -3.96349e-5 -0.9998471 0.01749306 1.34537e-4 -0.9998477 0.01745212 3.95542e-7 -0.9998477 0.01745235 3.12885e-4 -0.9998476 0.01746004 2.64314e-5 -0.9998473 0.01748013 -0.003061234 -0.9998917 0.0144006 0.9999513 0.00251168 0.009555816 0.08713567 0.9960436 0.01745045 0.08714324 0.9960429 0.01745259 0.08714962 0.9960424 0.01745116 0.08713269 0.9960439 0.01745247 -0.08714884 -0.9960425 0.01745176 -0.08714449 -0.9960429 0.01745116 0.9986295 6.1594e-5 0.05233657 0.9986296 0 0.05233651 0.4198956 0.9028108 0.09284687 0.001936376 0 0.9999982 0.2096359 0.1506778 0.9661 -0.04593843 -0.122223 0.991439 -0.7451367 0.1400862 0.6520332 -0.7671697 0.01522159 0.6412637 -0.08394539 0.7875688 0.6104825 -0.9988524 0.03141647 -0.0361514 0.365984 0.8937321 0.2594197 0.5611248 0.2771193 0.7799641 0.4718605 0.8270987 0.3053777 0.5066879 0.2132773 0.8353323 0.8093505 0.5073668 0.2958562 0.9310968 0.1203597 0.3443434 0.8051637 0.4824255 0.3449307 0.4435504 0.8691819 0.2185999 0.2598319 0.9605159 0.09948241 0.4071063 0.8670756 0.2871314 -0.8339275 -0.433133 -0.3419956 -0.9293044 -0.1588334 -0.3334146 -0.3921918 -0.8758323 -0.2812529 -0.7525256 -0.5995938 -0.2723834 -0.4722457 -0.8571276 -0.2057095 -0.4915758 -0.2977817 -0.8183394 -0.5059518 -0.6652776 -0.549016 -0.7094444 -0.3181754 -0.6288506 -0.691346 -0.6031393 -0.3978238 -0.8761979 -0.3325572 -0.3488309 -0.7969371 -0.5774568 -0.1772993 -0.5759075 0.8174249 0.01213288 0 0.9998477 0.01745212 6.52217e-5 0.9998481 0.01743298 1.95208e-4 0.9998469 0.01749962 0 0.9998477 0.01745194 -0.09095853 0.9956982 -0.0176565 -0.08714109 0.9960431 -0.01745146 -0.8309214 0.03836095 -0.5550659 -0.8325756 0 -0.5539114 0.003414452 0.002711117 0.9999906 -0.0265389 0 0.9996479 0.006629467 0.9986496 -0.05152857 6.45845e-5 0.9986372 -0.05219072 0.9984288 0.0195825 -0.05250298 7.18593e-6 -0.9998478 -0.017452 2.42467e-7 -0.9998477 -0.01745229 3.03132e-5 -0.9998474 -0.01747256 -1.68153e-6 -0.9998478 -0.01745188 -0.9986275 -4.07458e-4 -0.05237394 -0.9986722 0 -0.05151683 -0.003102719 -0.9999822 0.005096197 -0.007539689 -0.9998992 0.01203685 -1.05267e-4 -0.999962 0.008715033 -3.09705e-5 -0.9999619 0.008731603 0.6598609 0.7510516 0.02247351 0.004708349 0.9997116 0.02355182 0 0.9998477 0.01745271 0 0.9998477 0.01745271 -5.36127e-7 0.9998478 0.01745277 -1.31272e-4 0.9998488 0.01739156 0.09342193 0.9956223 0.002929568 -7.78974e-5 0.9998468 0.01750737 -0.7856183 0.6023817 -0.1412095 0.9974538 0.07129347 -0.001838922 -0.7349867 0.6696447 0.1066331 -0.01634508 0.9987976 0.04621934 -0.9999451 0.005646705 0.008824944 -0.6051875 -0.7730165 0.1902464 0.08714091 -0.9960431 0.01745218 0.08715111 -0.9960423 0.01745158 0.9998477 0 0.0174573 -0.01192158 -0.03774857 -0.9992163 0 -0.01059812 -0.9999439 0.6716663 -0.7369775 0.07568788 0.9986295 0 0.05233728 0.9986295 -4.18524e-5 0.05233639 -0.04607975 0.0782001 0.9958723 -0.6986453 0.2199496 0.6808208 -0.03957021 0.03396993 -0.9986392 -0.04264032 0.992345 0.1159019 0.06719338 0.2943847 0.953322 0 0.08741539 0.996172 -0.004671156 -0.8263675 0.563112 0.314458 0.9298986 0.1908007 0.3144482 0.9299002 0.1908087 0.3144487 0.9299 0.1908091 -0.3144143 -0.9299982 -0.1903864 -0.3178298 -0.9399005 -0.1247851 -0.2994855 -0.9287864 -0.2183215 -0.3144485 -0.9299001 -0.1908089 -0.3144386 -0.9298925 -0.1908625 5.0432e-4 0.005761921 0.9999834 1.71154e-7 0 1 -5.19314e-4 -0.002427041 0.999997 -0.1122716 0.2665676 0.957255 -1.32963e-4 9.18137e-5 1 -4.68638e-4 -0.003441452 0.999994 -4.87142e-4 -0.003430902 0.9999941 -6.77251e-5 2.29209e-5 1 -0.001336872 -8.25619e-5 0.9999992 0.01864004 0.06703865 0.9975762 -0.005506455 -0.001563549 0.9999836 -3.33638e-4 -0.001194536 0.9999992 0.06763154 0.00771439 0.9976806 -0.3473621 -0.8610832 -0.3713157 -0.3479644 -0.2071723 -0.9143306 -0.3323111 -0.8767884 -0.3475795 -0.3276714 -0.901329 -0.2832623 -0.3441361 -0.5799954 -0.7383602 -0.4032295 -0.6929041 -0.5977373 -0.4000675 -0.622981 -0.6721911 -0.4125497 -0.4038217 -0.816536 -0.2576126 -0.08886331 -0.9621534 -0.3243629 -0.4596582 -0.8267425 -0.3437424 -0.8739982 -0.3434655 -0.34562 -0.8220428 -0.4525402 -0.284446 -0.2480294 -0.9260517 0.3144487 -0.9298998 0.19081 0.3144419 -0.9298975 0.1908325 0.3130882 -0.9245257 0.2173201 0.1294222 -0.9745671 0.1829455 0.3144487 -0.9298999 0.1908094 0.3144482 -0.9299 0.1908101 0.3144487 -0.9299001 0.1908088 -1.51663e-4 -5.07882e-5 1 1.5399e-4 5.3967e-4 0.9999999 0.001070499 -0.003629028 0.9999929 0.002784848 -0.04996925 0.9987469 0.03841459 0.03104197 0.9987797 -0.004294455 7.59298e-4 0.9999906 0.004727542 0.02747201 0.9996114 -0.3144474 0.9299007 -0.1908081 -0.3144483 0.9299002 -0.1908091 -0.3341203 0.9230034 -0.1908626 -0.3134052 0.9288552 -0.1974976 0.9999282 0.01000386 0.006601631 0.9999979 0.001950502 6.82968e-4 0.9999987 0.001378774 8.60716e-4 0.9999978 2.97051e-4 -0.002079367 0.9898439 -0.1254676 -0.06683576 0.9265493 -0.250661 -0.2804913 0.9116549 -0.04325938 -0.4086736 0.9959487 -0.08877152 0.01435059 0.6338696 0.2143387 0.7431476 0.9421142 0.318583 0.1045266 0.6686688 0.3526756 0.6546007 0.6643771 0.1224291 0.737302 0.9999912 -0.001995503 -0.003714382 0.4678148 4.52536e-4 0.8838265 0.46985 -0.02457714 0.8824041 0.6139569 -0.006836354 0.78931 0.9465829 0.009720921 0.3223141 0.9476575 0.004121422 0.3192623 0.9687593 -0.003794491 0.2479742 0.5096813 -0.003554582 0.860356 0.4634792 6.84962e-4 0.8861076 0.7327841 9.18858e-4 0.6804606 0.7642019 3.87174e-4 0.644977 0.9742515 0.0399369 0.2218986 0.7680264 0 0.6404181 0.8306532 -0.008043944 0.5567321 0.8624119 -0.01875329 0.5058599 0.9999809 0.001963078 0.005879282 0.8747672 -0.01769477 0.4842204 0.9194102 0 0.3933002 0.9340857 0.08202338 0.3475 0.9891656 -0.03892475 0.1415495 0.9941527 0 0.1079831 0.9941572 -5.47953e-6 0.1079419 0.9907807 6.04831e-6 0.1354761 0.9906163 1.15797e-4 0.1366731 0.9931619 -0.003575265 0.1166906 0.9885864 0.007493615 0.1504693 0.8675585 -0.4950523 -0.04759603 0.9443377 -0.01763379 0.3285046 0.9891527 0.03899741 0.1416198 0.9818586 -0.06344377 0.1786861 0.9445217 0.005185484 0.3284083 0.9458844 0.01766067 0.3240232 0.8794623 0.005582869 0.4759359 -0.8418016 0 -0.5397871 0.6816185 -1.2209e-4 0.7317078 0.4881486 0.01250427 0.8726709 0.8829326 0.01561588 0.4692401 0.9090998 -0.003551721 0.4165633 0.9466151 -0.006615817 0.3222981 0.9520257 0 0.3060183 0.9511607 -0.001379013 0.308693 0.9257023 0.00787872 0.378171 0.25146 0 0.9678677 -0.133556 0.01229697 0.990965 0.2293936 3.75191e-5 0.9733338 0.2288151 -5.59402e-4 0.9734697 0.2566542 -2.28751e-4 0.9665033 0.2783143 9.55169e-4 0.9604897 0.2521023 9.9248e-5 0.9677007 0.2396535 2.13697e-4 0.9708585 0.2305401 -2.90316e-5 0.9730629 0.2264356 -0.005640029 0.9740099 0.2326043 -0.001775562 0.97257 0.2252818 -8.77724e-4 0.9742934 0.2284343 1.47982e-4 0.9735593 0.2576638 -0.02732926 0.9658482 0.4286594 -1.04621e-4 0.9034662 0.4488973 3.29049e-4 0.8935833 0.8236891 0.0912984 0.5596436 0.9382148 -0.008224785 0.3459558 0.9527294 -0.001583576 0.3038164 0.9151584 -0.1170191 0.3857353 0.8616074 0 0.5075752 0.8162588 -0.4078462 0.4091248 0.9859332 -0.01195132 0.1667122 0.9941231 -2.21988e-4 0.1082554 0.8400719 0.01132577 0.5423569 0.8224034 -0.1062136 0.558902 -0.8438906 0 -0.5365154 0.8624939 0 0.5060674 0.826963 0.3738253 0.4199844 0.920322 0.04517149 0.3885448 0.9249396 0.04801756 0.3770694 0.9283761 0.03849905 0.3696426 0.9224625 -0.06534659 0.3805167 0.8079694 -0.05127161 0.5869895 0.6115459 -1.06623e-4 0.791209 0.2853377 -2.98134e-4 0.9584271 0.2221487 -1.74945e-5 0.9750128 0.584051 -0.006540775 0.8116908 0.2566205 8.91228e-4 0.9665119 0.2448093 2.34133e-4 0.9695712 0.3880678 4.09655e-4 0.9216309 -0.5577196 0.001155972 -0.8300287 -0.5592409 0.002560257 -0.8290013 -0.7597028 -0.02923637 -0.649613 -0.8709741 -0.006510615 -0.491286 -0.9362947 2.28776e-5 -0.3512156 -0.9077619 -2.07046e-5 -0.4194859 -0.9072135 3.40648e-4 -0.4206704 -0.8756485 4.19058e-4 -0.4829487 -0.7881104 0 -0.6155339 -0.6918994 -8.54671e-4 -0.7219935 -0.7498596 0 -0.661597 -0.6633924 0.001110315 -0.7482709 -0.5175616 -1.75057e-6 -0.855646 -0.444072 -0.003419101 -0.8959846 -0.4557667 -0.001486957 -0.890098 -0.549661 0.00200951 -0.8353855 -0.5695045 -0.01318663 -0.8218824 -0.7087998 0.00764513 -0.7053683 -0.5290225 -7.21148e-4 -0.8486075 -0.4608482 -1.85461e-6 -0.887479 -0.3215222 -8.96646e-4 -0.9469016 -0.2937922 -5.59812e-4 -0.9558692 -0.7283642 -0.01441484 -0.6850385 -0.6100857 -9.30525e-4 -0.7923349 -0.8332267 8.0469e-5 -0.5529317 -0.8763467 3.23722e-4 -0.481681 -0.9623061 0.003221571 -0.2719497 -0.9594049 -0.01122218 -0.2818093 -0.9472262 1.41921e-4 -0.3205659 -0.9551201 0.001607179 -0.2962145 -0.9574485 0.007302343 -0.288512 -0.9720705 -0.004432439 -0.2346474 -0.9557589 0.0019508 -0.294145 -0.9774968 -0.007457613 -0.2108188 -0.9920231 -0.001513719 -0.126047 -0.9850013 -0.005972504 -0.1724436 -0.9850109 0.003831326 -0.17245 -0.9985356 -0.00234425 -0.05404907 -0.9992877 0 -0.03773581 -0.9975705 0 -0.06966549 -0.9917678 2.65367e-5 -0.1280503 -0.9934586 -0.002367556 -0.1141688 -0.9784882 0.008242905 -0.2061387 -0.3401039 0.005725145 -0.9403705 -0.3674166 -1.30063e-4 -0.9300565 -0.369776 1.20035e-4 -0.929121 -0.2429251 0 -0.9700452 -0.2416057 -8.55371e-5 -0.9703745 -0.25801 0 -0.9661422 -0.2715638 9.52591e-6 -0.9624205 -0.2267317 -0.00475341 -0.9739457 -0.2598053 1.96179e-4 -0.9656611 -0.2687868 1.94303e-4 -0.9631997 -0.2321894 0.002010405 -0.9726685 -0.2264868 0.005634486 -0.973998 -0.2222848 1.73198e-5 -0.9749818 -0.2353779 -0.002361536 -0.9719011 -0.2413393 -1.22917e-4 -0.9704408 -0.9778557 0.009248793 -0.2090761 -0.9934586 0.002356588 -0.1141689 -0.4135844 -1.12131e-4 -0.9104658 -0.2434412 0 -0.9699156 -0.2310257 1.01218e-4 -0.9729477 -0.2355647 0.003057956 -0.9718539 -0.2285416 0 -0.9735342 -0.4604545 -2.02952e-5 -0.8876835 0.3707717 -0.9239417 -0.09412813 0.9286782 -0.3671634 -0.05242228 -0.5581813 -0.006021976 0.8296971 -0.804456 0.00315535 0.594004 -0.2633808 0.9646913 -0.001147568 -0.2311596 0.9727582 0.01751667 0.3144507 -0.9298993 0.1908094 0.3144467 -0.9299007 0.1908088 0.3516145 0.5385239 0.7657411 0.3329544 0.891656 0.3067425 0.3466849 0.7109844 0.6118096 0.38949 0.5647883 0.7275382 0.3451822 0.6980822 0.6273202 0.3498937 0.5300911 0.7723845 0.9998875 -0.01410084 -0.005130648 0.9998952 -0.01376271 0.004490911 -0.1507337 -0.9885743 -4.79298e-4 0.008053958 -0.9999658 -0.001913547 0.008407235 -0.9999637 -0.00138241 0.170776 -0.9698284 -0.1739787 0.02172148 -0.939755 -0.3411581 -0.8782479 -0.01852768 0.4778466 -0.3064227 0.220838 0.9259243 0.9929243 0 0.1187492 -0.2152758 -0.9764297 -0.01553463 -0.2570319 -0.9663761 0.007210195 0.2608034 -0.960538 -0.09668761 0.01608937 -0.9997649 0.01453918 -0.26239 -0.9649049 -0.01049107 -0.2396847 -0.9633368 -0.1205553 -0.3836342 -0.5980629 0.7036659 -9.51298e-7 0.9999619 0.008726418 -5.11559e-4 0.9999615 0.008760154 0.9999619 0 0.008735418 0 -0.999962 0.008723795 -9.93853e-6 -0.9999619 0.008727014 -0.001964092 0.005944073 0.9999804 0.1722326 -0.1722314 0.9698826 -1.59279e-5 0.9999395 0.01100838 -0.9999619 1.51764e-5 0.008726537 -0.999962 0 0.008730232 0.999962 0 0.008726358 -0.9999626 0 0.008656263 0.2390588 0.2390602 0.9411171 -0.3019664 0.3019648 0.904231 0 0.999962 0.008725047 0.9999608 0.00141853 0.008743524 0.999962 0 0.008729994 0.9999626 0 0.008656084 0.9999614 0.001086533 0.008716821 -4.87894e-4 -0.9999619 0.008730709 -0.999962 0 0.008729517 0.2211341 0.03331613 0.9746742 -0.3464945 0.6461338 0.6800388 -0.1369836 -0.5026603 0.8535621 -0.1077105 -0.1619871 -0.9808968 0.3281596 0.7290773 -0.6006311 0.1266125 -0.2906547 -0.948414 0.04522532 0.4419397 -0.895904 -0.01636439 -0.5725719 -0.8196911 -0.3732132 -0.4593824 0.8060271 0.06036049 -0.0461446 0.9971095 -0.4137033 0.140105 0.8995667 -0.07038277 0.4797939 0.8745537 0.06775552 0.997573 -0.01604789 5.39911e-4 -0.9999619 0.008724331 0.001877605 0.9999601 0.00873965 0.9998799 0.01288366 0.008615612 -0.01354885 -0.9998712 0.008607149 -0.160371 -0.006401062 -0.9870361 -0.364785 0.9310301 0.01072913 -0.2390045 0.9666364 0.09214663 -0.2841645 0.002125144 -0.9587732 -0.168601 -0.01611512 -0.9855527 -0.1649262 -0.02015537 -0.9861 0.8012458 0.008556187 0.5982742 0.8139899 0.004489839 0.5808619 0.9052889 -0.00357449 0.4247814 0.9801025 -0.02922856 -0.1963284 0.9399325 -0.01162225 -0.3411629 0.5286432 -0.005549013 -0.8488261 0.829006 -0.0273627 -0.55857 0.4030873 -0.02870082 0.9147115 -0.3743798 -0.01185005 0.9271998 -0.001160979 0.9999994 -2.41133e-5 0.2707032 0.9381784 0.2157343 0.05114781 0.9803377 -0.1905831 -0.03591531 0.9323598 -0.3597438 0.09106361 0.9757204 -0.1991914 -0.8322365 -0.313431 -0.4573222 -0.9606799 -0.05144304 -0.2728512 -6.78828e-5 -0.9998439 -0.01767086 0.9421139 -0.3185836 0.1045274 0.03348231 0.999432 -0.003820896 0.001394748 0.9784119 -0.20666 0.8816091 0.2869117 0.374763 0.95994 0.1620181 0.2286167 0.3434284 0.8986364 -0.2729645 0.3707421 0.9239485 -0.09417873 -0.2782967 -0.587705 -0.7597065 0.9898805 0.1255958 -0.06604832 0.8740121 0.003308832 0.485893 0.7903341 -0.4960036 0.3596563 0.8962454 -0.002036869 -0.4435541 0.5671997 -0.01850628 -0.8233724 0.415094 -0.05369704 -0.9081926 0.8942137 -3.30969e-4 0.4476405 0.4501624 -0.02742934 0.8925254 -0.4270117 -0.04325157 0.9032112 -0.6156454 0.01218914 0.7879291 -0.8012068 -2.94154e-4 0.5983875 0.5884228 -0.6414376 -0.4922565 0.3450863 0.9383459 0.02055853 -0.1539534 0.9752893 0.158459 -0.08866649 0.9774257 0.1917741 -0.2053202 0.9721447 -0.1130419 -0.28937 0.9507764 -0.1108568 -0.0107544 0.9999365 -0.003394424 0.2376354 0.9681742 -0.078538 0.2196239 0.9469248 -0.2347315 0.917348 -0.2634469 0.2984434 0.3916136 0.897242 0.2039502 0.007883727 0.9999509 -0.006018459 -0.08947652 0 0.995989 -0.02046817 0.9991522 -0.03572022 -0.01499098 0.9965854 -0.08119773 -0.9640981 -0.01576244 0.2650783 -0.9652005 -0.01457083 0.2611052 -0.006661713 0.9973074 0.07303124 -0.02573788 0.9986479 0.0451669 0.9999911 0.002003967 -0.003713965 0.6686701 -0.3526753 0.6545995 0 0 1 3.41909e-7 0 1 -3.05792e-7 0 1 0.6338675 -0.2143457 0.7431473 -0.1609417 -0.6036082 -0.7808682 -0.07855349 0.9952124 -0.05815333 0.419736 0.8917861 -0.1689361 -0.3998603 -0.8406383 -0.365293 -0.1530641 0.1727451 -0.9730008 0.2053317 -0.2321817 -0.9507527 0.6636911 -0.6565247 -0.3584544 -0.2016906 -0.9625412 -0.1812053 -0.5884324 -0.2280671 -0.7757145 0.9959487 0.08877199 0.01435202 0.9114676 0.04284381 -0.4091349 0.9264391 0.2514489 -0.2801504 0.3162482 0.8583 0.404114 0.6319851 0.3024751 0.7135151 0.05922555 0.9244548 0.3766641 0.6603061 0.4531532 0.5988724 -0.4051089 0.6516852 0.6412435 -0.7685233 0.4104822 0.4907916 0.9022147 -0.009448945 0.4311838 -0.853044 -0.01498782 0.5216237 0.89063 0.04532468 0.4524645 0.9556419 0.00477463 0.2944926 0.9823617 -0.05189889 -0.1796444 0.8895813 0.03012859 -0.4557824 -0.5379695 -0.1221476 -0.8340677 -0.8681099 -0.006108999 -0.4963346 -0.9551703 0.04742336 -0.2922342 0.09224104 -0.9821863 0.1637122 0.6500661 0.02829021 -0.7593508 -0.4395525 0.02369779 -0.8979043 -0.7446815 0.09535652 -0.6605729 0.03899723 -0.6801849 0.7320026 -0.1030619 0.8774809 0.4684075 -0.4647457 -0.8080032 0.362136 0.7440481 0.02217328 -0.6677581 0.5732933 0.3318631 -0.7491341 -0.3360419 -0.8440775 0.4178626 -0.007324397 0.9972577 0.073646 0.5144259 -0.3435449 0.7857119 1 4.67781e-7 0 0.9690513 0.07762771 0.2343368 1 -8.82143e-6 0 1 8.65972e-6 -9.1631e-7 1 0 4.24198e-7 1 -6.43558e-6 0 0 2.6078e-5 1 -1 -1.64936e-5 4.55535e-5 -1 -2.42611e-5 -1.79701e-5 -1 6.03664e-5 0 -0.3585742 0.8162181 -0.453004 -1 -9.0192e-6 -6.76867e-5 -0.9813095 0.09906029 0.164981 -0.7289928 -0.6426985 -0.2356018 -1 3.62261e-5 2.98322e-5 -1 6.49132e-6 0 -1 -6.49132e-6 0 0.4383063 0.2757495 0.8554822 -0.9921377 0.03381371 0.1204969 -0.9995349 -0.01305598 0.02755874 0.2708966 0.922993 0.2733109 0.04942148 -0.9179543 0.3935956 -0.2704294 0.1990607 -0.9419357 0.9876042 0.06059008 0.1447994 0.4194734 0.6366363 -0.6470985 0.7632104 0.4339343 -0.47876 0.1286559 0.8723923 -0.4715712 0.2342018 -0.1078902 0.9661828 0.08703953 0.715077 0.6936058 -0.3353264 0.01226317 0.9420222 0.9688428 -0.04214662 0.2440641 -0.06285983 0.634532 -0.7703361 -0.05380845 0.9946017 -0.08872467 0.3974078 0.07851058 0.9142774 0.1672596 0.2766422 0.9463051 0.200178 -0.2134729 0.9562208 0.2686522 -0.9204553 0.2838805 0.4420037 -0.01911979 0.8968095 -0.1290395 -0.5374647 0.833355 0.04849511 0.495281 -0.8673783 0.5564509 0.2841467 -0.7807837 -0.1944219 -0.01993787 -0.9807153 -0.1822702 0.9539452 -0.2382565 -0.07424628 -0.5480543 0.8331411 0.2678009 0.5483071 0.7922387 0.9181307 -0.3378868 0.2070471 0.9181182 -0.3380538 0.2068303 0.8243038 0.3223933 -0.4653881 0.9777896 0.1138215 0.1759894 0.9999833 3.00137e-4 0.005770325 0.9999962 -0.001756906 -0.002154111 0.9530953 -0.2123953 -0.2156335 0.9999991 0.001342892 -4.54327e-4 0.8969027 -0.4100511 -0.1656007 0.2984052 -0.07371598 0.9515883 -0.07765913 0.2704172 -0.959606 0.06350821 0.05444556 -0.9964951 -0.2231388 -0.03587579 -0.9741263 0.115161 -0.9546568 -0.2745334 0.3100913 0.04697835 -0.9495454 0.9160317 0.2779861 -0.2891535 0.8852979 0.1122187 -0.4512811 0.1068472 0.7430515 -0.6606498 -4.27113e-4 -0.8297828 -0.5580864 0.1506189 -0.7078199 -0.6901485 0.2107787 -0.08269649 0.9740297 -0.09225469 0.9935399 -0.06608664 -0.1838994 0.9425113 -0.2790223 -0.1056625 -0.9923158 -0.06437981 0.1217711 -0.5892503 0.7987214 -1.24281e-4 -0.691626 -0.7222558 -0.8669021 0.1791924 0.4651569 -0.8962336 0.3215624 0.3055534 -0.8403747 0.3454441 -0.4176585 -0.8051214 0.442842 -0.3945513 0.3234376 0.3024477 0.8966124 -0.8386446 -0.2901965 -0.4609354 -0.8082172 -0.5828481 0.08410161 -0.9497122 -0.1532678 0.2730488 -0.7663866 -0.532993 -0.3585671 -0.9431336 0.3317164 0.02152323 0.09018719 0.4343745 0.8962059 0.1165813 -0.3117859 0.9429732 0.3805896 0.1697737 0.9090262 0.1020284 -0.8343737 -0.5416741 -0.3902123 0.04409182 0.9196686 0.5529064 0.811645 0.1884865 -0.1743997 0.6925444 0.6999766 -0.2193367 0.9214614 0.320625 -0.5156661 -0.5103529 0.6882067 -0.00653392 -0.8633508 0.504562 0.6034833 -0.7733669 0.1941943 -0.8009274 0.5984668 0.01878654 -0.8460406 0.4533424 0.2805279 -0.9505711 -0.1003375 0.2938485 -0.9585621 -0.2848578 -0.003867745 0.7786181 -0.4953132 0.3852517 0.6417105 -0.0764802 0.7631241 0.9432922 -0.3238886 0.07277441 0.7148295 0.09345406 0.6930261 0.92115 0.3198722 -0.2217307 0.47394 0.5171884 0.7126691 -0.04386097 -0.7340399 0.6776886 0.4908143 0.8499723 -0.1914384 0.8513954 -0.5004107 0.15721 -0.6673024 -0.7067352 0.235017 0.922903 -0.384996 0.005321562 -0.322211 -0.8949682 -0.3085647 -0.2058648 -0.9315872 -0.2996079 -0.4026201 -0.8758004 -0.2662159 -0.3622589 -0.89811 -0.2493333 -0.2377674 -0.8506057 0.468974 -0.1295368 0.2318042 -0.9640991 0.04233533 -0.02154791 -0.9988712 -0.08044773 0.07450044 -0.9939708 0.7339391 0.3997528 -0.5491184 0.1916271 0.5789508 -0.7925245 0.267618 0.03455609 -0.9629052 0.4728872 -0.3523605 -0.8076013 0.2956904 0.04510205 -0.9542185 0.0671091 -0.2475693 -0.9665433 0.3092507 0.2867132 -0.9067302 0.3451435 0.8990758 0.2693302 0.2030513 0.9137932 0.3517844 -0.2593279 -0.9657599 0.007544338 -0.252707 -0.96754 -0.002349317 -0.2748711 -0.9613574 -0.01542657 -0.2766905 -0.960605 -0.02608495 0.153535 0.9578313 -0.2428708 0.4311236 0.8420752 -0.3241018 0.3063937 0.9519048 -3.79854e-4 0.310158 0.9506264 0.01056307 0.3142597 0.949337 -4.33601e-4 -0.9510049 -0.2707385 -0.1492998 -0.7087194 0.6446382 -0.286633 0.723336 0.6904727 0.005710601 0.6392716 -0.7685061 0.02702522 0.9928806 0.1003363 -0.06419348 -0.8945468 -0.4454262 -0.03717148 -0.8938797 -0.4467872 -0.0368815 -0.8024839 0.5945252 -0.05059152 -0.4586975 0.8885925 0 -0.9957057 -0.09227007 -0.007518529 -0.9966863 -0.002231419 -0.08131045 -0.4152076 -0.9045 0.09737783 -0.1908174 -0.9757822 0.1069481 0.7783818 0.4004755 -0.4834681 0.3122126 -0.1156946 -0.9429412 0.4777932 -0.6730087 -0.5645998 0.7702769 0.3513203 0.53221 0.05121845 -0.0681039 0.9963628 0.475857 0.8638545 -0.1652746 0.3332253 0.9428473 -1.40006e-4 0.3401483 0.9403652 -0.003552258 -0.7076936 -0.1118098 -0.6976163 -0.06530672 -0.04299515 -0.9969387 -8.76301e-7 0 -1 0.1962771 -0.1981573 -0.9603171 -0.07296782 -0.05686622 -0.9957118 -0.2762609 -0.04027616 -0.9602384 0.08479583 0.9963972 -0.00150603 -0.3500753 0.936246 -0.02984446 -0.7756952 0.6307154 -0.02225565 -0.9877269 0.1559671 -0.008359253 -0.9966137 -0.08142822 0.01143753 -0.7725741 0.6345649 -0.02137744 -0.5168841 -0.8560555 2.9858e-4 0.3457382 -0.938331 4.17343e-4 0.6750597 -0.7377631 2.53335e-4 0.8887471 -0.4583207 -0.008417546 0.9906226 -0.1366256 6.48266e-4 0.9898698 0.1417611 -0.007854163 0.9981947 0.0504046 -0.03266185 0.7815257 -0.6232522 -0.02783101 -0.5139505 -0.85782 0 0.3502308 -0.9366635 0 0.8396286 0.5431604 6.99775e-4 0.5050817 0.8630716 -7.35433e-5 -0.007238447 0.0186696 -0.9997996 0.01025766 0.03143846 -0.9994531 -0.358356 0.360817 -0.8610414 -0.01259893 0.004816889 -0.9999091 0.1994916 -0.06976324 -0.9774131 0.03700226 -0.2416468 -0.9696585 0.2153199 -0.1512308 -0.9647625 0.01444244 -0.1270815 -0.9917872 0.05975002 0.03582769 -0.9975702 0.4982206 -0.8670389 0.004456758 0.894481 0.4471039 -0.001432061 0.9824755 -0.1424372 -0.1202235 0.9974018 0.01632916 -0.07016474 0.9021472 0.4314283 0 0.9945248 -0.02155685 0.1022537 0.6271298 0.7789149 0 -0.2847766 0.9585939 0 -0.5536125 0.8327744 0 -0.6775567 0.7332956 0.05652052 -0.8814265 0.4721677 0.01204413 0.1933239 0.9811351 0 -0.2847742 0.9585946 0 -0.7558642 0.6538302 -0.03428602 -0.8058983 0.592035 -0.004763782 -0.9999324 -0.009191989 -0.007127463 -0.7953137 -0.6061951 0.001890599 0.04709404 -0.9988659 0.007015347 0.4362691 -0.8997881 0.007130026 0.6674594 -0.7419349 0.06348675 0.04709392 -0.9988659 0.007015347 0.6853632 -0.7224992 -0.09095269 -0.9927908 0.1193143 0.01142638 -0.007580876 -0.002367436 0.9999685 -0.004929304 0.006488382 0.9999669 -0.004739642 0.1005407 0.9949216 -0.008734107 0.07037484 0.9974824 -0.6640875 0.3421675 -0.6647625 -0.8239333 -0.2563126 -0.5054086 0.598204 0.168181 0.7834969 0.02051383 -0.03603368 0.9991401 0.3066401 -0.4395391 0.8442614 0.5260481 0.7090017 -0.4696704 0.4673776 -0.6567227 -0.5918391 -0.1307322 -0.719322 -0.6822646 -0.03974282 0.9511152 -0.3062688 0.4639542 -0.2184216 -0.8585095 -0.7176392 -0.6587978 -0.2257864 0.2739226 -0.6642839 0.6954807 -0.6896127 -0.1560485 0.7071657 -0.6716324 0.3657251 0.6443254 -0.7810776 -0.604047 -0.1582567 -0.4254153 0.8322547 -0.3554913 3.23615e-6 5.49508e-4 -1 0.1010533 0.9947378 -0.01688206 -1.06917e-4 1.86423e-4 -1 -0.7263655 0.6856762 -0.04734325 0.07839608 0.9968411 -0.01273125 -0.9100228 0.4145582 -2.74079e-4 -0.08020287 -0.9967722 0.003589451 0.9468868 -0.3065516 -0.09711593 -0.7475478 -0.6640343 -0.01519656 -0.9894745 0.1424024 -0.02572321 -0.9987683 -0.04554724 -0.01967954 0.001652896 0.006746828 -0.9999759 0.09049516 -0.02075082 -0.9956807 -0.01106804 -0.007412493 -0.9999114 0.01108992 -0.008538842 -0.9999021 -0.949173 0.3096748 -0.05632227 0.9497097 -0.3098575 -0.04516583 0.9506769 -0.3101829 0 0.9506785 -0.3101779 0 -0.9506799 0.3101737 0 -0.9506784 0.3101783 0 -1.61692e-6 0 -1 0.3101741 0.9506798 4.18665e-6 0.3101832 0.9506769 -4.85084e-6 0.310176 0.9506792 0 0.3101755 0.9506794 0 0.3101598 0.9506844 0 0.9506788 -0.3101772 0 0.9506804 -0.3101723 0 -0.3101749 -0.9506796 3.06782e-7 -0.3101794 -0.9506781 0 -0.3101703 -0.9506811 0 -0.9506787 0.3101773 0 -0.9506804 0.3101723 0 0.2915763 -0.0722863 0.9538124 -0.3012951 0.07413727 -0.9506445 0.9927285 0.1021121 0.06374412 0.370113 0.9143442 0.1642903 -0.7423253 0.6667995 0.06581616 -0.8927825 -0.4041467 0.1990096 0.5869537 0.8011333 -0.1169224 -0.8285124 -0.5454279 0.1267901 -0.5013108 -0.836736 0.2203641 0.6309596 -0.7212862 0.2857203 -0.9656745 -0.2154493 0.1451016 3.18402e-6 0 1 -2.5385e-6 0 1 -6.82676e-4 -8.18262e-4 0.9999995 -0.001255035 4.09773e-4 0.9999992 -3.65825e-4 9.78258e-4 0.9999995 -0.03801625 -8.82306e-4 0.9992768 0.01864707 0.0122599 0.999751 9.86716e-5 -0.001539051 0.9999988 -2.53854e-6 0 1 0.6160359 0.7874262 -0.02144062 0.995446 0.03574824 -0.0883708 0.8655366 -0.4962065 0.06801062 0.7490903 -0.6590349 -0.06735563 0.1719868 -0.9805875 0.09417462 -0.9652006 0.1898882 -0.1798064 -0.995943 -0.03584545 0.08254051 -0.7883571 0.6143869 -0.03196763 -0.06728351 0.9949502 0.0744785 -0.1105436 0.9933097 -0.03340548 -0.008041977 -0.02844101 0.9995632 0.07294738 -0.05420088 0.995862 0.05167067 0.08344703 0.9951718 0.008140921 -7.97241e-4 -0.9999666 -0.009709417 0.004911124 -0.9999408 -0.006511151 0.007474184 -0.9999509 4.11138e-4 4.95142e-4 -0.9999999 -3.98214e-4 -4.8265e-4 -0.9999999 -0.007745504 -0.01801174 -0.9998078 1.11696e-6 0 -1 -0.9051409 -0.4115369 -0.106571 -0.9688245 -0.2472665 -0.01544308 0.255126 0.9668931 -0.005350828 0.5341408 -0.7893222 0.3027609 0.2499902 0.9682256 -0.006652534 0.8748462 0.4823105 0.04495215 -0.3083918 0.7605644 -0.5713461 -0.5394983 0.630034 -0.5585685 -0.578276 0.5770131 -0.5767607 -0.5407027 0.6281944 -0.5594753 -0.2739009 0.7829215 -0.5585806 -0.7229796 -0.6879494 0.06345194 0.2202262 0.974183 0.04968005 0.9805546 0.194988 -0.02219021 -0.9938393 0.08876222 -0.06636941 -0.6528375 0.75292 -0.08315533 0.2096205 0.9770403 0.03809893 0.9741761 0.2202583 -0.04967135 0.01170849 -0.005302369 0.9999174 -0.00475955 0.002887368 0.9999846 -0.6146453 -0.3231778 0.7195606 0.5285908 0.3770115 0.7605618 -0.4108252 -0.2272707 0.882933 -0.5789312 -0.3915891 0.7151899 0.7215712 0.3938978 0.5693678 7.47149e-4 4.85724e-4 0.9999997 2.51509e-6 1.37268e-5 1 -0.6368924 -0.3712179 0.6756962 -0.7562639 -0.4587128 0.4665271 -0.716076 -0.4087246 0.565844 0.3203219 0.1848727 0.9290943 0.5640983 0.3256765 -0.7587675 0.4743092 0.2751152 0.8362671 0.8585039 0.4933865 0.1397885 0.861061 0.4971315 0.1069323 -0.2845149 0.7671459 -0.574925 0.4202948 0.2448304 -0.8737336 -0.5968362 -0.3183246 -0.7365162 0.2934807 -0.8187684 -0.4934445 0.5784125 -0.7172869 -0.388508 0.8707165 -0.4207385 -0.2546213 -0.8715298 0.320699 -0.3709289 -0.9646505 -0.2523471 -0.07596266 -0.8670709 -0.4973632 -0.02860063 -0.8667827 -0.4978451 -0.02895021 -0.8665726 -0.4964984 -0.05041021 -0.8647878 -0.5002373 -0.04364329 -0.8654609 -0.4996884 -0.03590166 0.006153166 -0.9881032 0.1536698 -0.1461707 -0.9806876 0.1299463 -0.0285955 -0.9881318 0.1509238 0.606404 -0.7732585 0.1853256 0.5344568 -0.2772731 -0.7984207 0.4976145 -0.8467452 0.1881556 0.03557443 0.01983004 -0.9991703 0.02372777 0.02112293 -0.9994953 -0.0573675 -0.04094225 -0.9975132 0.5268652 0.4748187 0.7049542 -0.8922026 -0.396694 -0.2158898 -0.9343011 0.3471479 -0.08105504 -0.5358634 -0.1455078 -0.8316718 -0.01941412 0.9756966 -0.2182644 0.7323587 0.4987974 -0.4635214 0.3725911 -0.6769216 -0.6347859 0.3555926 -0.571958 -0.7392009 0.9385454 -0.2087057 0.2749081 0.6137301 0.3759325 0.6942695 0.6815072 0.4016229 0.6117573 -0.520552 -0.8326552 0.1889735 0.8645815 0.4981203 -0.06614512 0.8734956 0.4857322 -0.03270375 0.8525022 0.5210719 -0.04152292 0.8584846 0.5114805 -0.03731077 0.8656471 0.4997882 -0.02944397 0.8656884 0.4997681 -0.02855545 0.865122 0.5007293 -0.02888083 0.8667045 0.498055 -0.02765518 0.8673264 0.497048 -0.02623385 -0.08494061 0.1468326 -0.9855076 -0.4938551 0.8525546 -0.1710495 0.4373118 -0.7915151 0.426922 0.9181146 0.3378998 0.2070976 0.5593153 0.8219642 -0.1074307 -0.2952983 -0.9415684 -0.1620122 0.6157404 -0.5116761 -0.599209 0.6736261 0.3196859 -0.6663549 0.8333448 0.4945435 -0.2469076 0.5899271 0.4763726 -0.6519625 0.5257102 0.5841237 0.618408 -0.2490952 0.3743782 0.8931924 -0.1795898 -0.8439115 -0.5055304 -0.8446039 -0.4673475 -0.2612097 0.9791618 0.08578521 0.184074 -0.7023398 -0.4783074 0.5272011 -0.4797213 -0.4327272 0.763292 0.7896949 0.3376895 0.5121991 0.4579372 -0.8725338 -0.1702306 -0.4915847 0.8494262 -0.191885 0.0724833 -0.1555184 0.9851702 -0.08373683 0.1494514 -0.985217 0.2485204 -0.5949375 -0.7643867 -0.7782496 -0.4319552 -0.4557876 -0.9117354 -0.3632521 0.1917983 -0.839666 0.512895 -0.1786052 0.2486884 0.8659128 -0.4339921 -0.02597332 -0.9193606 0.3925576 -0.4972733 -0.8479628 0.1835169 -0.6714525 -0.5075002 0.5399955 -0.7191329 -0.5138626 0.4677534 0.7447925 0.434943 -0.5060721 0.4239004 -0.7559758 -0.4988078 0.2874048 -0.4845412 0.8262072 0.4771824 0.8672889 -0.1417992 0.97343 0.1588816 0.1648966 0.2336679 -0.4725412 0.8497672 0.3774744 0.02320134 0.9257293 0.7868115 0.3615769 0.5001898 -0.2843587 0.5003005 -0.8178261 -0.2948294 0.526983 -0.7970977 0.4913623 -0.8600541 0.1373686 0.4411209 -0.7884324 0.4287035 -0.00849682 -0.004966616 -0.9999516 -0.4817664 0.8547133 -0.1933039 -0.4897402 0.8486071 -0.2000513 0.9223859 -0.3637585 0.1299391 0.158837 0.9149761 -0.3709306 -0.5211967 0.7299938 -0.4421122 -0.3235987 0.8342726 -0.4464001 -0.282508 0.8518635 -0.441042 -0.5004858 0.7427567 -0.444777 0.5373907 -0.631492 -0.5589537 0.412178 -0.7139163 -0.5660679 0.3444533 -0.7374306 -0.5809888 0.2314555 -0.7173856 -0.6571046 0.4103955 0.2369421 -0.8805873 0.8678258 0.4968616 0.002664327 3.76157e-7 0 1 -7.3634e-7 0 1 3.05554e-7 0 1 -0.8642063 -0.5031309 0.002638816 -0.364919 -0.2168594 -0.9054315 0.698552 -0.7153921 -0.01547616 -0.8346318 0.5503436 0.02262538 -0.96355 -0.2674464 -0.006633758 -0.5600854 0.8072832 -0.1860063 -0.4117444 -0.7131261 -0.567378 -0.276839 -0.7792274 -0.5622856 -0.2104651 -0.7893236 -0.576778 -0.429764 -0.7599975 -0.4875518 -0.5410745 -0.6286768 -0.5585731 -0.5300425 -0.6334172 -0.5637711 0.967377 -0.2329881 0.0994901 0.0971958 -0.9826547 0.1579326 -0.2089064 -0.9732322 -0.09579843 -0.004273176 -0.003158152 0.9999859 0.003396272 -0.003000557 0.9999898 -0.5373827 0.7691168 0.3459468 -0.5907205 0.2691972 0.7606459 0.4307898 -0.2491958 0.8673647 0.4022814 -0.2421749 0.882905 -0.7019277 0.4279632 0.5693373 -7.93255e-4 4.0155e-4 0.9999997 -1.25757e-5 -5.09169e-6 1 0.6469749 -0.3691768 0.6671822 0.8620126 -0.475188 0.1764389 0.7238652 -0.4307165 -0.5389829 0.6659711 -0.3865923 -0.6379882 0.8640533 -0.4854946 0.1330675 0.09203237 -0.845723 -0.525626 0.8619595 -0.497654 -0.09678089 -0.2147576 0.1239741 0.9687672 -0.8153822 0.4613416 -0.3497371 -0.2146409 0.09848052 0.9717155 0.7382693 -0.5174524 0.432668 -0.861062 0.4971321 0.1069207 -0.5220909 -0.6299967 -0.5749133 -0.4221633 0.2415822 -0.8737369 0.1609397 -0.6638991 -0.7302988 0.5740824 -0.3577041 -0.7365306 0.8556536 0.5003792 -0.1322029 0.3320139 0.8595714 -0.3884634 -0.0709905 0.9644249 -0.2546471 0.05644029 -0.9191457 -0.3898538 0.870808 -0.4911876 -0.02069389 0.8587577 -0.5110391 -0.03707045 0.8508468 -0.5236556 -0.04294985 0.8688007 -0.493916 0.03510481 0.8332195 -0.5357294 -0.1368917 0.8632614 -0.5022258 -0.05048811 0.8742486 -0.4851942 -0.01661866 0.8654756 -0.4996649 -0.03587579 0.8526332 0.4994017 0.1536712 0.9060449 0.4012687 0.1344103 0.5537205 0.8121035 0.1840696 0.5657898 0.8027337 0.1884163 0.4197591 0.5427327 -0.7274913 0.3664261 0.9118038 0.1853262 0.6147022 0.7668448 0.1846359 0.3669312 0.9115861 0.1853981 0.6675097 0.7247523 0.1707776 0.02252304 -0.01556646 -0.9996252 0.06414949 -0.02921795 -0.9975126 0.9406831 0.05628043 -0.3345861 0.4443559 -0.4276415 -0.7871916 0.6357121 -0.4753815 -0.6081798 -0.751272 0.3726419 0.5447279 -0.8353005 -0.5046067 -0.2182779 0.3999505 0.6611485 -0.6347616 -0.3675921 -0.7176261 0.591514 0.9813773 -0.03441923 0.1889815 -0.863669 0.499695 -0.06618809 -0.8574868 0.5134741 -0.0325694 -0.8721855 0.4877515 -0.03729742 -0.8656538 0.4997785 -0.02941375 -0.8649984 0.5010678 -0.02662605 -0.8659334 0.4990304 -0.03358983 -0.8656417 0.4997276 -0.03061008 -0.8641139 0.5026121 -0.02623766 -0.08814138 -0.1471022 -0.9851863 -0.08468711 -0.1469783 -0.9855077 -0.4907963 -0.854335 -0.1709706 -0.46868 -0.8616578 -0.1946409 0.4205585 0.7822685 0.4595504 -0.008649826 -0.009514451 0.9999174 0.4297882 -0.8944249 -0.1236383 -0.9259973 0.1984184 0.3211842 -0.9914963 0.0734561 -0.1074209 0.1352039 0.7891376 -0.5991509 -0.6136631 0.4235811 -0.6663308 0.9518975 -0.2109657 0.2222263 -0.04633289 -0.06209963 0.996994 -0.1990464 -0.403243 0.8931829 0.5593836 -0.4640743 -0.6868225 0.9801102 0.04439526 0.1934247 -0.687325 0.5150569 0.5121532 0.2948298 0.5985908 -0.7448251 0.5266726 0.8328498 -0.170228 -0.490106 -0.8503121 -0.1917435 0.09981077 0.1404961 0.9850374 -0.08759999 -0.1472411 -0.9852139 -0.08516836 -0.1473931 -0.9854044 0.4619496 0.7706424 0.4389907 0.5752313 -0.4555087 -0.6794269 0.3909969 0.5127729 -0.7643203 0.6226211 -0.7769785 -0.09299129 -0.8742414 -0.2176094 -0.4339911 0.9830076 -0.006817758 0.1834385 0.7746871 -0.3272112 0.5411033 0.7970626 -0.394994 -0.4568052 -0.3019421 0.1816359 -0.935863 0.4427512 0.7451085 -0.4987833 -0.46265 -0.6901624 0.5564449 -0.8550848 0.4653324 0.2286826 -0.9838937 0.1490116 -0.09873682 -0.6085838 0.7783676 0.1541746 0.2923722 0.4385908 0.849798 -0.2088176 0.3152871 0.9257372 -0.7065576 0.5006136 0.5001623 -0.3551282 -0.5947945 0.7211821 -0.2911341 -0.4964745 -0.8177739 0.4991467 0.8555684 0.1373152 0.4362936 0.7797976 0.4489584 0.08238351 0.1430849 0.9862757 0.008549928 -0.004875481 -0.9999516 -0.02862519 0.9881304 0.150927 -0.7937379 -0.4575327 -0.4008043 -0.3716114 -0.8163614 -0.4421074 -0.4750137 -0.7593689 -0.4446581 -0.4734753 -0.7602363 -0.4448166 -0.5964342 -0.6706236 -0.441056 -0.3845481 -0.8309015 -0.4021514 -0.3734706 -0.8138033 -0.4452459 -0.4302086 -0.7863988 -0.4432805 0.2212789 0.7845247 -0.5792726 0.2781995 0.781144 -0.5589446 0.2964798 0.768447 -0.5670882 0.4121769 0.7139123 -0.5660739 0.515937 0.6415035 -0.5676991 0.5055542 0.5590742 -0.6571538 0.2609234 0.7416563 -0.6179523 -0.8642067 0.5031301 0.002630293 -0.8642221 0.4989584 0.06450587 2.91794e-7 0 1 -2.70971e-6 0 1 -1.93727e-7 0 1 0.01610279 0.006539046 0.999849 0.8678275 -0.4968588 0.00264734 0.8642219 -0.4989565 0.06452292 0.4368414 -0.2522104 -0.8634579 -0.897046 0.4288864 -0.1066068 -0.8121095 0.5833001 -0.01546525 -0.08789122 0.9957978 0.02573001 -0.261336 -0.9165366 0.302761 -0.3650424 -0.81639 0.4474946 0.9317994 -0.3601826 0.04492878 0.384281 0.7251688 -0.5713654 -0.04291564 -0.849259 0.5262295 0.07024878 0.8138749 -0.576778 0.1336674 0.8179974 -0.559476 -0.9937302 0.02946668 0.107852 -0.2664237 0.9508333 0.1579066 0.8054389 -0.5885356 -0.06995749 0.003643691 0.003399312 0.9999877 0.003474771 -0.01239722 0.9999172 -0.001557469 -0.002431929 0.9999958 -8.51842e-4 0.005504727 0.9999845 -0.3157861 0.1149192 0.9418454 -2.37172e-4 8.28304e-5 1 7.53663e-5 -1.43762e-5 1 -0.6933925 0.2491783 0.6761043 0.3784177 -0.1345697 -0.9158009 -0.5885236 0.2127776 -0.779978 -0.8375743 0.2844787 0.4664133 -0.7778216 0.2874275 0.5589089 -0.7228584 0.2650191 -0.6381542 0.4710451 -0.7341391 -0.4890362 -0.9352293 0.3280749 0.1330907 -0.9352675 0.3404167 -0.09690964 0.6754624 -0.243854 -0.6959064 0.6239843 -0.2235742 -0.7487711 0.7376254 -0.2891659 0.6101574 0.8831243 -0.3127445 -0.3496892 0.5106638 -0.2119957 0.8332349 0.2284834 -0.05971544 0.9717147 -0.3453661 0.1110673 0.9318725 -0.8169156 0.381403 0.432644 -0.6874508 -0.4600651 -0.5619178 0.9343109 -0.3400601 0.106876 0.5268835 -0.1878598 -0.8289166 0.503899 -0.1820535 -0.8443593 -0.6274493 0.2525693 -0.736557 -0.7557151 -0.6414291 -0.132149 -0.2452108 -0.7729083 -0.5852216 -0.1413623 0.9026914 -0.4064051 -0.255347 0.885902 -0.3872669 -0.2151081 0.8953964 -0.3898639 -0.9378203 0.3395851 -0.07193905 -0.9108679 0.390345 -0.1339794 -0.9403528 0.3392335 -0.02563774 -0.9368199 0.3484749 -0.03055948 -0.8172454 0.5715681 -0.0736199 -0.9425172 0.3334187 -0.02221488 -0.938526 0.3439923 -0.02895122 -0.9636985 0.2646126 -0.03557169 -0.9114113 0.3624005 -0.1949241 -0.9376671 0.342742 -0.05751943 -0.7753651 -0.613211 0.1509352 -0.2659083 -0.9463346 0.1836945 -0.4043149 -0.8959068 0.1840664 -0.2089939 -0.9760924 -0.0597102 -0.01142364 -0.005237579 -0.999921 -0.06825202 0.01763552 -0.9975123 -0.8869573 0.4186054 -0.1951319 -0.9190717 -0.2331014 -0.3177592 -0.3556538 0.9237946 -0.1418244 -0.5180742 0.3391464 -0.7852253 -0.4559306 0.3169741 -0.831658 0.8045244 -0.2365156 0.5447943 0.8179631 -0.5716065 -0.06482619 0.7287228 0.646812 -0.2249385 -0.2793279 -0.72039 -0.634834 -0.2089782 -0.6382902 -0.7408871 0.443476 -0.8530868 0.2749036 0.6824439 -0.2284864 0.6943085 0.7457327 -0.2639139 0.6117452 -0.7816094 -0.5310169 0.3272734 -0.9824554 -0.04699373 0.1804801 -0.8036425 0.2808789 0.5246579 0.9373837 -0.3420419 -0.06572097 0.9475582 -0.3167583 -0.04239797 0.9489873 -0.3122568 -0.04380542 0.9392138 -0.3418407 -0.03197491 0.9397431 -0.3406757 -0.02868753 0.9393029 -0.3418988 -0.02855491 0.9509688 -0.2624103 -0.1637047 0.938804 -0.3433698 -0.02728235 0.9397612 -0.3401343 -0.03402197 0.9383863 -0.3445494 -0.02677422 0.9387095 -0.3435773 -0.02791172 0.335747 0.926308 -0.170961 -0.3249419 -0.8438917 0.4269188 -0.295891 0.9101681 -0.2899009 -0.8830336 0.3837814 -0.2701177 -0.03159248 0.8795824 0.4746968 -0.9113762 -0.3785061 -0.1616374 0.9110819 -0.3138625 -0.2672457 0.7441111 -0.1456982 -0.6519746 0.7854969 -0.02732694 0.6182621 -0.9013667 0.3565717 -0.2457535 0.8155006 -0.52692 0.239404 0.6207717 -0.7455304 0.2425426 -0.9575037 -0.2139465 0.1934257 -0.1075481 -0.2361298 -0.9657517 -0.1940153 -0.6543629 -0.7308675 0.3347976 0.9225432 -0.1918981 0.3329039 0.9229493 -0.1932349 -0.07353621 -0.1551299 0.9851533 -0.05513107 -0.1530683 0.9866766 0.06061112 0.1602974 -0.9852061 -0.3202602 -0.83927 0.4393851 -0.9492108 0.1280134 0.2874218 -0.7765855 0.6111024 -0.1531955 -0.8311343 0.3185169 -0.4558101 -0.1468369 0.972904 -0.1785969 -0.494799 0.853601 -0.162909 -0.7210338 -0.5709864 0.3925364 -0.9708891 -0.1578893 0.1801264 -0.8113922 0.1833814 0.5549901 0.5471836 -0.7454873 -0.3805771 -0.4718451 0.1907675 -0.8607962 -0.3066616 -0.8104677 -0.4991 0.8243999 -0.5614653 0.0715664 0.9591935 0.2560679 0.1199053 0.9949726 0.02097034 -0.09792834 0.7234508 -0.6707599 0.1634016 -0.2128672 -0.4860823 0.8475917 0.2198995 -0.2589624 0.9405226 0.8810181 -0.3819454 0.2791504 0.2804316 0.6581796 0.6986829 0.2249014 0.5644626 -0.7942301 -0.294264 -0.8437067 0.4489631 -0.05630046 -0.1552184 0.9862746 0.001385509 0.003918588 -0.9999914 -0.009266436 0.00331676 -0.9999516 0.3351744 0.9206718 -0.200054 0.3142178 -0.940416 0.1299426 0.2747526 -0.9520718 0.1344265 0.7021793 0.5884641 -0.4008172 -5.1616e-5 2.28644e-5 1 -1.25718e-6 4.87373e-7 1 -0.0374757 0.8998272 -0.4346339 0.2242135 0.8684839 -0.4421131 0.3359295 0.8303186 -0.4446601 0.3342713 0.8309009 -0.4448218 0.4492959 0.7770575 -0.4408115 0.5483453 0.6787608 -0.4884684 0.1469807 0.885941 -0.4398924 0.2869268 0.849217 -0.4432871 -0.07663697 -0.8121609 -0.5783784 -0.1383219 -0.8176024 -0.5589218 -0.281937 -0.77465 -0.5660645 -0.3966342 -0.7213898 -0.5676954 -0.4007958 -0.6384081 -0.6571134 -0.1280814 -0.775647 -0.6180348 0.417403 -0.1581294 -0.8948575 0.9384452 -0.3454186 0.002604722 2.5435e-7 0 1 -4.96229e-7 0 1 0 0 1 1.95138e-7 0 1 0.9878794 -0.07977825 0.1331534 0.7120296 -0.7013486 0.03352838 0.5124204 -0.8582515 -0.02880454 -0.538456 0.8002279 0.2640089 0.2625939 -0.7748072 -0.5750812 0.4189189 -0.7129788 -0.5622884 -0.5126366 0.678166 0.5265877 0.4218497 -0.7142292 -0.5584976 0.4693486 -0.6685971 -0.5767928 0.4233812 -0.7125568 -0.5594741 0.1337987 -0.8187928 -0.5582799 0.1212989 -0.81735 -0.563228 0.1552395 -0.8090669 -0.5668434 0.5357465 0.834684 0.1275875 0.8740547 -0.4536899 0.1737637 -0.3811591 -0.9094576 0.1661469 -0.9955983 0.02157592 0.0912075 -0.557751 0.830008 -8.25154e-4 0.9316236 -0.3452294 0.1135525 -0.7383469 -0.6700565 -0.07660335 -0.9980828 -0.01611727 0.05975943 -0.003849267 -0.001953482 0.9999908 0.002211749 0.0052796 0.9999836 0.6626374 0.2151786 0.7173632 -0.5878022 -0.2789266 0.7594001 0.3157476 0.1149416 0.9418556 0.6753067 0.2462841 -0.6952014 0.3875454 0.1313819 0.9124404 2.34834e-4 8.76593e-5 1 -6.53181e-5 -3.47972e-5 1 0.6914124 0.2548415 0.6760213 -0.3765148 -0.1402034 -0.91574 0.7952375 0.2776568 -0.5389842 0.8244951 0.3204538 0.4663873 0.7805808 0.279792 0.5589365 0.7242117 0.261678 -0.6379986 0.9273135 0.3498327 0.1330671 0.702363 -0.4794166 -0.5261615 0.9352762 0.3404041 -0.09686905 -0.6741483 -0.2473612 -0.6959429 -0.3437421 -0.1251347 0.9306894 -0.7510252 -0.2526684 0.6100164 -0.6121862 -0.2228161 -0.7586706 -0.8775314 -0.328077 -0.3497202 -0.3376178 -0.1110661 0.9347078 -0.9343094 -0.3400588 0.1068922 0.1469054 -0.8048809 -0.5749656 -0.5243867 -0.1947674 -0.8289055 -0.5030248 -0.1844365 -0.8443633 0.6120303 -0.3033857 -0.7303261 0.1666681 0.9771199 -0.1321312 -0.146849 0.8572704 -0.4934804 0.7650169 -0.5145556 -0.3872749 0.9366934 0.3426793 -0.07194852 0.9419274 0.3343833 -0.03099387 0.939309 0.3418818 -0.02856022 0.9305187 0.3662217 -0.004082679 0.9363128 0.3504656 -0.022188 0.9492366 0.3114502 -0.0441423 0.9254457 0.3771545 0.03612285 0.9410798 0.3177964 -0.1156474 0.9390838 0.3418093 -0.03588759 0.1997483 0.9681524 0.1509359 -0.404676 0.8958199 0.1836959 -0.2661603 0.9461909 0.1840692 -0.4673009 0.8820973 -0.05944901 -0.4629595 0.8667896 0.1853227 -0.319656 0.9300547 0.1811589 -0.4788998 0.3656478 -0.7980957 -0.4624567 0.867042 0.1853975 -0.1260751 0.9772125 0.1707655 -0.03847855 -0.01335173 -0.9991703 0.06361627 0.03036129 -0.9975125 0.9485276 0.2494154 -0.1951601 0.5544158 0.7692691 -0.3175664 0.6148649 0.07322472 -0.7852257 0.5529859 0.0502485 -0.831674 -0.7683265 -0.3359102 0.5448293 -0.994015 -0.08786928 -0.06490981 -0.1503056 -0.9642428 -0.2182756 -0.563027 -0.3587295 -0.7445226 -0.2501958 0.6232976 -0.7408794 -0.9164589 0.3055619 0.2583316 -0.6697098 -0.2636576 0.6942431 0.3133637 -0.7428746 0.5915577 0.2574269 0.9091916 0.3272647 0.7961812 0.3014171 0.5246364 -0.9379369 -0.3405179 -0.06574243 -0.9284152 -0.3690207 -0.04323327 -0.9276802 -0.3707967 -0.04380911 -0.9388559 -0.3431203 -0.02860361 -0.9393166 -0.3418613 -0.02855485 -0.9389381 -0.3428731 -0.02886945 -0.9406011 -0.3390893 -0.01696974 -0.9424104 -0.3344461 0.002930939 -0.9398651 -0.3404538 -0.02729058 -0.9389807 -0.3425019 -0.03174644 -0.9400507 -0.3399275 -0.02745991 0.05815726 -0.1593512 -0.9855074 0.3383417 -0.9253413 -0.1710801 0.3548985 -0.9154074 -0.1899375 -0.3293392 0.824616 0.4599394 0.001726984 -0.01274269 0.9999174 -0.01685583 -0.007077574 0.999833 0.8726848 -0.1308244 -0.4704318 -0.6935636 -0.7123402 -0.1074295 -0.6583216 -0.7431941 -0.1194791 -0.5176827 0.610747 -0.59916 -0.9065622 -0.3423171 -0.2469092 -0.619142 -0.4839924 0.6183969 0.1716213 -0.3408339 0.9243259 0.2027909 -0.6541984 0.7286291 0.03611099 0.6918616 -0.7211266 0.9326995 0.3266868 -0.1527984 -0.9844595 0.0558542 0.1664929 -0.9550639 0.1738392 0.2400684 0.5959728 0.7793603 0.193427 0.7747545 0.3490969 0.52715 -0.8746684 -0.2550604 0.4121889 -0.08715879 0.2405167 -0.9667239 -0.2455247 0.4972838 -0.8321217 0.3366367 -0.9219365 -0.1915957 0.3384945 -0.9209001 -0.1932988 0.05666309 -0.1615338 -0.9852392 -0.2941219 0.8486825 0.4395798 -0.1485807 0.4530097 0.879037 -0.1414725 0.6291373 -0.7643114 0.8094333 0.5120632 0.2874179 0.9464986 0.1054124 -0.3050061 0.8414335 0.2902461 -0.4557927 0.7380135 0.26534 -0.620428 0.5926918 -0.06201314 0.8030386 0.1852633 0.9008834 0.3925387 0.6422733 0.7450103 0.1801242 0.7380468 0.3810909 0.5568273 0.7947543 0.378516 0.4744378 0.8290605 0.3557787 -0.4313702 -0.8894197 0.216412 -0.4026144 -0.733762 -0.5763065 0.3598114 -0.8392046 -0.5408864 -0.05637192 0.02493399 -0.9785479 -0.2045053 -0.9860314 0.08223694 0.1448421 -0.1493575 0.5091423 0.8476241 -0.3837149 0.03811514 0.9226647 -0.7899012 -0.1910787 0.582705 -0.90737 -0.2683465 0.3235272 0.1401741 -0.4142218 0.8993173 0.1375622 -0.4038811 -0.9044097 -0.3169226 0.8354622 0.4489577 0.009315013 0.003445804 -0.9999508 0.3352568 -0.9206846 -0.1998574 -0.8452241 0.5183753 0.1299363 -0.8224653 0.5527013 0.1344329 -0.3152574 -0.8735145 -0.3709245 -0.1597522 -0.9021238 -0.4008141 5.39567e-5 1.69564e-5 1 -6.28619e-7 -2.68661e-7 1 0.3865638 -0.809387 -0.4421099 0.3893427 -0.8286799 -0.4021219 0.3833428 -0.8091961 -0.4452529 0.4568812 -0.7731493 -0.4398862 -0.4633426 0.6714197 -0.5783677 -0.419604 0.7152067 -0.5589383 -0.4049401 0.7186933 -0.5652464 -0.2819449 0.774644 -0.5660688 -0.1382903 0.8175621 -0.5589885 -0.08168333 0.8110614 -0.5792301 -0.1033316 0.7466563 -0.6571355 -0.4004334 0.6765291 -0.6180303 -0.4213882 -0.1471625 -0.8948605 -0.9409215 -0.3386149 0.002621769 -0.9377344 -0.3413078 0.06452292 2.41591e-7 0 1 4.73985e-7 0 1 1.01662e-6 0 1 -5.20259e-7 0 1 0.9377363 0.3413098 0.06448572 0.6097022 0.7765491 -0.158855 -0.9566364 0.2885561 0.03977775 -0.03086167 -0.9994099 0.01508402 -0.001694738 0.001841485 -0.999997 -0.2106538 0.1406775 -0.9673857 -0.006332457 0.02331429 -0.9997082 -0.1186146 -0.06207662 -0.990998 -0.005318105 0.03788012 -0.9992682 -0.7462019 -0.1295368 0.6529954 0.4260327 0.3851345 0.8186377 0.9219368 0.008751332 0.3872416 0.3456691 -0.7291427 0.5906469 0.3511785 -0.6900832 0.6328182 -0.463087 0.5994549 0.6528432 -0.3025585 -0.4123048 0.8593389 0.6371468 0.7622182 -0.1143131 -0.943508 -0.3238732 -0.06999212 -0.2001346 -0.9759027 -0.0869494 0.1568191 -0.9875142 -0.01494979 0.7044194 0.7044218 -0.08708298 0.03088492 0.9994115 0.01492571 -0.7548369 0.6526982 -0.06485676 -0.9810147 -0.1905344 -0.03615212 -0.6399617 -0.7683097 -0.01222121 -3.95517e-4 -0.002492308 -0.9999969 0.0914036 0.01366901 -0.9957202 0.05419993 0.0542007 -0.997058 0.1186535 0.06363707 -0.9908944 -1.34203e-4 -0.001419723 -0.999999 -0.2001113 0.1204766 -0.9723379 -0.215613 0.1036385 -0.9709636 -0.001929044 0.002007722 -0.9999961 0.3174162 0.3569144 0.8785552 -0.4493218 0.7904449 0.4163016 0.3331729 -0.7046633 0.6264547 -0.547861 -0.8175948 -0.1771644 -0.3849384 -0.3083493 0.8699099 0.9748404 -0.2213806 -0.02601575 -0.2809028 0.9596168 -0.0151441 -0.9757664 0.2185338 -0.01108932 -0.6434589 -0.7636443 -0.05299341 0.9994696 0.03255933 5.58642e-4 -0.9610005 0.2763312 0.01092153 -0.6794314 -0.7328228 -0.03665506 0.1186555 0.06363713 -0.9908942 -0.3651514 -0.2918027 -0.8840338 -0.5585544 -0.1990296 -0.8052356 -0.2262929 0.1757723 -0.9580687 -0.02458757 0.06427818 -0.9976291 0.05787658 0.03047496 -0.9978585 4.76546e-4 -0.001191079 -0.9999992 -3.79137e-4 0.001447081 -0.9999989 -0.4318069 0.7726467 0.4653603 -0.2109438 -0.3757798 0.9023814 -0.1458668 -0.7400783 0.6565113 0.7382946 -0.6680585 -0.09283888 0.2514953 0.9674533 -0.02800691 -0.6410292 -0.7612754 -0.09768104 0.9837135 0.1787894 -0.01849925 -0.998791 0.0476287 0.0121625 -0.9987545 -0.04743117 0.01549112 -0.002628624 -0.001282989 -0.9999958 0.005903244 -0.01109367 -0.9999211 0.009998559 0.2590813 -0.9658038 1.46804e-4 -2.6393e-4 -1 -8.84074e-4 -0.005629122 -0.9999838 0.0181061 -0.05784034 -0.9981617 -0.06376117 0.2379639 -0.969179 0.003226518 0.02364343 -0.9997153 0.03224277 -0.06057667 -0.9976428 0.002232193 0.0024724 -0.9999945 -0.7474626 -0.1334152 0.6507689 -0.4848537 0.02871042 0.874124 -0.4139131 0.580873 0.7009013 0.8169041 0.2200457 0.5331488 0.4560398 0.3988204 0.7955942 0.2811657 -0.751777 0.5964708 0.2973902 0.6972478 0.6522305 -0.4401972 0.07477343 0.8947824 0.05814945 0.9710077 0.2318682 0.2580589 -0.9630748 -0.07676309 0.7879689 0.6142141 -0.04296553 -0.3323376 0.9428764 -0.0231505 -0.9265958 0.3755559 -0.01944255 -0.05108112 -0.05107963 -0.9973874 -0.02436077 -0.09091126 -0.995561 0.1735218 0.2204455 -0.9598407 0.06559866 0.2448276 -0.9673451 0.1411959 0.1101394 -0.9838359 -0.01487803 -0.1255617 -0.9919742 -0.005872249 0.002339482 -0.9999801 -0.002385437 -0.001834928 -0.9999955 -0.103981 -0.8534163 0.510753 0.2358465 -0.5061978 0.8295423 -0.7315604 -0.1995543 0.6519184 0.7171404 -0.3967429 0.5729789 0.2408509 0.3985749 0.8849457 -0.01525545 -0.1273621 0.991739 0.4725162 -0.8806752 0.03375995 0.9949883 -0.02584397 -0.09659409 0.9874358 -0.1486617 -0.05357515 -0.937834 -0.3391296 -0.0738818 -0.7069351 -0.7069197 -0.02252757 -0.001497805 -0.9982607 -0.05893588 0.02222603 -0.08747476 -0.9959189 0.08808606 0.06565606 -0.9939468 0.00536412 0.06122851 -0.9981095 -5.96481e-4 -1.59906e-4 -0.9999999 -0.169986 0.122977 -0.977743 -0.1955645 0.1866943 -0.9627563 -0.08341366 -0.04503631 -0.9954968 2.67881e-4 -0.005083084 -0.9999871 0.001523137 -0.00144124 -0.9999979 -0.7478219 -0.1323388 0.6505758 -0.406369 0.7424997 0.5325021 0.5724979 0.2932354 0.7656757 0.3512831 -0.6897094 0.6331676 0.3966028 0.7903078 0.467033 -0.4165921 -0.2357183 0.8780022 -0.6483973 -0.7570853 -0.0800184 0.9626042 0.2579467 -0.08280581 -0.9907168 0.08917504 -0.1026063 0.03273993 -0.2119315 -0.9767361 0.08752447 0.04157763 -0.9952944 0.05120015 0.01371908 -0.9985942 0.03957945 0.1545454 -0.9871926 0.04620778 0.1283242 -0.9906553 -0.08633315 0.005593776 -0.9962506 -9.99123e-4 1.49624e-4 -0.9999995 0.1589049 0.09366029 0.9828413 -0.449576 0.5792699 0.679947 0.1635707 0.9412074 0.2955901 0.7669092 0.1301586 0.6284179 0.6052101 0.2396333 0.7591422 0.310774 -0.8555252 0.4141209 -0.4941752 0.2192507 0.841261 0.3335847 -0.9423484 -0.02647572 0.9955417 -0.08249282 -0.04573726 -0.8163288 0.5705118 -0.09013074 0.4646638 -0.8835956 -0.05784821 -0.2587414 0.9656793 -0.02272748 -0.7596554 0.647522 -0.06032568 -0.3676088 -0.9298529 -0.01541113 0.114455 0.04010879 -0.9926185 -0.08451092 0.007566869 -0.9963939 -0.01417326 -0.001161634 -0.9998989 -0.001948893 0.00726813 -0.9999717 -0.2220238 0.1892668 -0.9564955 0.1521472 0.01906585 -0.988174 0.005940496 -0.01911056 -0.9997997 -0.853819 -0.2229144 0.4704278 -0.4053313 0.06436014 0.9119015 -0.4304842 0.7725672 0.4667156 0.9588825 -0.02675598 0.2825396 0.316724 -0.8000435 0.5095257 -0.1740847 0.07606208 0.9817888 -0.4451981 0.02434235 0.8951013 -0.8145043 -0.5137917 0.2694455 0.05380868 0.9134917 0.4032837 0.5768421 -0.4808939 0.6602987 0.9824934 -0.1843028 0.02719038 0.6824945 0.7285565 0.05836725 -0.8751111 0.4835225 0.01966011 -0.9622562 -0.2578278 -0.08710896 -0.7069245 -0.7069302 -0.02252811 -0.03938728 -0.9975472 -0.05786615 0.1210245 -0.2136563 -0.9693834 0.09359019 -0.01792436 -0.9954495 -0.4359695 -0.32389 -0.8396581 -0.4308971 -0.4308962 -0.7928785 -0.2221901 0.3610761 -0.9056797 -0.2198296 0.08775591 -0.9715833 0.03775739 -0.1070259 -0.9935392 0.8365685 0.3259268 0.440369 0.6426933 0.3999847 0.65342 0.4825636 -0.7047803 0.5200166 -0.263019 -0.4438476 0.8566333 -0.2304904 0.9098105 0.3451362 0.8183774 -0.5676264 -0.08976954 0.63715 0.7622156 -0.114313 -0.6619568 0.7491929 0.0228731 -0.9371904 -0.3388728 -0.08270144 -0.1941772 -0.9797368 -0.04910457 0.989042 0.1475342 0.005455315 0.7044169 0.7044246 -0.08707988 0.001857638 0.9997803 0.02087903 -0.7297664 0.6832696 -0.02415984 0.006777226 -0.1483135 -0.9889172 -0.5672123 -0.2085797 -0.7967213 0.03611016 0.1563798 -0.9870368 0.02875739 -0.05855911 -0.9978697 -0.001987576 0.001040279 -0.9999975 -0.003163814 -0.01855909 -0.9998227 0.9330012 0.008899509 0.3597633 -0.3286247 -0.6563675 0.6791079 0.750889 -0.6494075 -0.1201487 0.7090505 0.704245 -0.03586709 -0.5798069 -0.8077495 -0.1066063 0.9931617 0.1161599 0.01169568 0.5353051 0.8387092 -0.1000777 -0.9645575 0.2584449 -0.05324506 -0.9322494 -0.3616721 -0.01021325 -0.107997 -0.9937201 0.02927511 0.07999247 -0.09236991 -0.9925065 0.01750713 0.02272331 -0.9995885 -0.2509412 0.06723946 -0.9656643 -0.09355777 -0.3840871 -0.9185445 -0.00989592 0.04171037 -0.9990808 0.004538774 0.02607572 -0.9996497 -0.4663714 -0.1205363 0.8763383 0.2783541 0.9436439 0.17904 0.5088396 0.3873571 0.7687892 0.9376761 -0.2239564 0.2657201 0.1605075 -0.6689617 0.7257601 -0.2260514 -0.1909973 0.9552072 -0.2019059 0.7940155 0.5733878 0.943284 0.3319754 -0.002770066 0.2376723 0.9688261 -0.06991511 0.8676606 0.4939302 -0.05655109 -0.9327696 -0.3556247 -0.05892366 -0.1699802 0.1229779 -0.9777439 -0.2163646 0.2962295 -0.9302874 -0.03346019 0.2510431 -0.9673974 -0.2359948 0.06468957 -0.9695987 -0.05670207 -0.03678393 -0.9977133 0.3373399 -0.9214188 -0.192845 -0.008616328 0.020343 -0.999756 0.3663182 0.7977712 0.478928 -0.5480188 -0.8175373 -0.1769416 0.388848 -0.4033181 0.8283306 -0.3312247 -0.1171959 0.9362454 -0.05655521 0.02413296 0.9981079 -0.574622 0.8174791 -0.0392121 -0.965557 0.2587156 -0.02767574 -0.9895365 -0.1419715 -0.02572196 -0.3706994 -0.9271022 -0.05534929 0.6149541 -0.783571 -0.0885902 0.3326897 -0.9427499 -0.02324306 0.9251835 -0.3793708 -0.01064729 0.9620196 0.2577819 -0.08981603 0.7068437 0.7068283 -0.0276733 0.0884636 0.9904683 -0.1055787 -0.03928512 0.05588841 -0.9976639 -0.093616 -0.2284201 -0.9690513 0.005951046 0.005286991 -0.9999684 0.1250371 -0.2944104 -0.9474642 -0.05743885 -0.2141989 -0.9750998 -0.1194007 0.02307754 -0.9925779 -0.004369258 0.03193998 -0.9994803 0.6752786 -0.04285115 0.736317 -0.9084208 0.1754683 0.3794505 -0.5819081 -0.3685298 0.7249613 -0.3433595 0.5860903 0.7338954 -0.5290217 -0.5845564 0.6151666 0.7124148 -0.7002466 -0.04604208 0.9576046 0.2794146 -0.07014936 -0.9408432 -0.3228641 -0.1028253 -0.2100829 -0.9752988 -0.06824535 0.4837484 -0.8752062 -0.001349985 0.9994264 0.03334712 -0.005910515 0.5282853 0.8490622 -0.00284779 0.1171104 0.9924339 -0.03688114 0.02206146 -0.06802171 -0.9974399 0.003231585 -0.182119 -0.9832712 0.2329577 -0.09065806 -0.9682521 0.1629109 0.04251009 -0.9857246 0.009204089 0.08892989 -0.9959955 -0.2287138 0.0401476 -0.9726655 0.008659482 -0.02943056 -0.9995294 -0.001181423 0.002264678 -0.9999968 0.3270332 -0.6391111 0.6961224 0.09792637 -0.993452 -0.0588541 -0.2764126 0.3770678 0.8839774 0.2106782 0.9771369 -0.02860271 0.3709318 0.9285924 0.01121276 -0.8552557 0.5181871 0.004474341 -0.9645495 -0.2584515 -0.05335849 -0.03881347 -0.9975688 -0.05788052 0.07926672 -0.05790078 -0.9951705 0.123696 0.02789324 -0.9919281 0.04889398 0.1215607 -0.9913791 0.009132802 0.2588462 -0.9658754 -1.22292e-4 0.002699196 -0.9999964 -5.96489e-4 -1.59908e-4 -0.9999998 -0.2129735 0.2595049 -0.9419658 -0.09234231 0.2293747 -0.968948 -0.2292937 0.07070904 -0.9707856 -0.747822 -0.1323372 0.650576 0.4158661 0.3826906 0.8249869 0.3933179 -0.7808637 0.4853382 0.3002912 0.7113603 0.6354461 -0.9920562 0.08132493 -0.09597373 -0.9645524 0.2584645 -0.05324476 -0.09795033 -0.04594552 -0.9941301 0.004286289 0.1559543 -0.9877551 -0.5371119 -0.2539092 -0.8043885 0.07787513 0.1018931 -0.9917426 -0.1431332 0.009820342 -0.9896547 0.1993827 -0.01913678 -0.9797348 -0.207429 -0.2823641 -0.9366129 -0.005289733 0.006444156 -0.9999653 0.1576132 0.9275494 0.3388364 0.4461 0.4822121 0.7539671 -0.2973161 -0.3965515 0.8685333 -0.5381231 0.4583178 0.7073673 -0.2094473 -0.4237596 0.8812261 0.755683 -0.6549371 -8.04438e-4 0.1355549 -0.9907416 0.00748986 -0.7414723 -0.6709016 0.01048111 -0.9517445 0.3067128 0.01047921 -0.2102493 0.9775917 0.01047909 0.2588209 0.965888 -0.008503317 0.2588254 -0.9659239 -8.22094e-4 -0.9658932 -0.2588014 -0.008499503 -0.7070785 0.707084 -0.008500874 -0.001965701 -0.001968502 0.9999961 -0.1833091 0.2740913 0.944072 -0.1978888 0.1978933 0.9600408 -5.75022e-6 4.75895e-5 1 -0.00203514 -0.004567563 0.9999876 0.02510786 0.01171237 -0.9996162 0.786428 -0.6171486 -0.02566665 0.4637315 0.7545101 -0.4644005 -0.3716284 0.03609955 -0.9276795 0.07399785 0.338171 -0.9381709 0.7070982 0.7070913 0.005842864 0.7414528 0.6709232 0.01047927 0.210255 -0.9775905 0.01048189 -0.7414759 -0.6708977 0.01047992 -0.9517462 0.3067073 0.01047867 0.9659054 -0.2588297 0.005843102 -0.2588101 -0.9658908 -0.008502721 -0.707099 -0.7070905 0.005842089 -0.707081 0.7070815 -0.008500397 0.05175191 0.1931293 0.9798076 5.47978e-4 -1.46236e-4 1 0.1417459 -0.06754624 0.987596 3.13556e-4 -0.001173734 0.9999993 0.001213312 0.003849089 0.9999919 -1.06201e-5 4.9137e-5 1 1.06198e-5 -4.91354e-5 1 -0.2320322 0.429674 -0.8726634 -0.241851 0.4281754 -0.8707318 -0.5009025 0.5748687 -0.6470106 -0.6737427 -0.6057507 -0.4232459 0.2893591 0.9278062 -0.2354719 0.6123684 -0.2867491 -0.736736 0.1855233 -0.6178696 -0.7640802 0.6577501 -0.07472968 -0.7495201 -0.9249052 0.215779 0.3130334 0.7070892 0.7071003 0.005842804 -0.7414603 -0.670915 0.01047837 0.2588211 0.965888 -0.008502125 0.9659097 -0.2588135 0.00584191 0.7070769 -0.7070856 -0.008497714 -0.7070915 -0.707098 0.005842387 -0.965888 -0.2588207 -0.008501768 -0.9659072 0.2588232 0.005838572 -0.7070778 0.7070848 -0.008502006 -0.258818 0.9659085 0.005839169 0.1142942 0.03062677 0.9929748 0.09862285 -0.02642601 0.994774 -0.006098687 0.01440215 0.9998777 -0.01442408 -0.0350154 0.9992827 -0.01304787 -0.04870265 0.9987281 0.001205325 0.003823578 0.999992 -1.06198e-5 4.91358e-5 1 1.06202e-5 -4.91376e-5 1 -0.3527612 0.7157866 -0.6026684 0.1547414 -0.3075947 -0.9388507 0.3830968 -0.2840416 -0.8789525 0.3785728 -0.2389022 -0.8942083 -0.04462558 0.9075769 -0.4175078 0.1665369 -0.1751559 -0.9703536 0.7071026 0.7070869 0.005844056 0.7414505 0.6709257 0.01047927 0.2102523 -0.977591 0.01048374 -0.7414568 -0.6709188 0.01047897 -0.9517554 0.3066791 0.01047492 0.2587959 0.9658947 -0.008503556 0.7070874 -0.7070752 -0.008495867 -0.2587962 -0.9658946 -0.008499741 -0.9658868 -0.2588254 -0.008502423 -0.9659055 0.2588292 0.00583738 0.01927763 0.07195806 0.9972214 -0.003388643 9.0818e-4 0.9999939 0.0321567 -0.06075036 0.9976349 -0.01579189 0.05894058 0.9981366 -1.062e-5 5.05013e-5 1 1.10623e-5 -5.05005e-5 1 -0.5948541 -0.1374387 -0.7919971 0.3434638 -0.9364169 0.07180625 0.4356567 -0.4702219 -0.7675249 0.8819912 0.09655594 -0.4612684 0.498808 0.4240272 -0.7559044 0.1883914 0.8483587 0.4947689 0.2783744 -0.7894923 -0.5470007 -0.7524566 0.3600565 0.5515147 0.707101 0.7070885 0.005842447 0.6549295 0.7556896 -8.07114e-4 0.9907387 0.1355758 0.007487535 0.1355644 -0.9907402 0.007491409 -0.9517479 0.3067021 0.01047778 0.7070972 -0.7070923 0.005842924 0.2588267 -0.9659234 -8.19662e-4 -0.9659084 0.2588183 0.005838811 -0.7070834 0.7070792 -0.008502006 -0.2588124 0.96591 0.005837619 -0.00366801 0.01566308 0.9998706 -0.003840863 -0.07354271 0.9972847 -0.02070093 -0.07725703 0.9967964 8.45585e-4 0.005543112 0.9999843 -0.002046704 -0.004591643 0.9999874 0 1.38529e-4 1 -0.230382 -0.6248264 -0.7460001 0.3416945 0.9015645 -0.2653796 0.3457408 -0.8290098 0.4395521 0.7174129 -0.1861176 -0.6713263 -0.4385851 -0.627606 -0.643237 0.6052947 -0.2634657 -0.7511352 0.7070946 0.707095 0.005842387 0.2588021 0.965893 -0.008504629 -0.2588177 -0.9658889 -0.008499622 -0.7071052 -0.7070842 0.005842924 -0.9659053 0.2588304 0.005836009 -0.006027936 -0.02251088 0.9997285 -0.01393318 -0.01393318 0.9998059 -0.002042055 -0.004586279 0.9999874 -1.04465e-4 -1.07434e-4 1 -1.41931e-6 1.38528e-4 1 -0.9732963 -0.01004368 -0.2293329 -0.5937073 0.6065096 -0.5288268 -0.367403 -0.5549278 -0.7463713 -0.3677365 -0.5514515 -0.7487798 -0.1101285 0.4058027 -0.9073015 -0.2684117 -0.121645 -0.9555928 0.9667116 0.2555899 -0.01194703 0.9986501 0.05090641 0.01031434 0.7047022 -0.7094026 -0.01195037 -0.262009 -0.9649915 -0.01195108 -0.938067 -0.3463221 -0.009559869 -0.9367682 0.3497428 -0.0120607 -0.3463342 0.9380869 -0.006760358 0.3497729 0.9368323 -0.002063333 5.9029e-4 5.93693e-5 0.9999998 -0.01343184 -0.04937052 0.9986903 -0.08883285 -0.1019744 0.9908128 -0.1402269 0.3768857 0.9155839 -0.1957468 0.02182251 0.9804117 -0.1646866 0.06264519 0.9843546 -0.110132 -0.04170602 0.9930416 0.1263727 -0.06200122 0.9900434 0.1068496 0.2835267 0.9529932 1.93029e-5 3.83689e-5 1 -0.6668293 -0.08704447 -0.7401095 0.7445786 0.3446183 -0.5717 0.3450151 0.122849 -0.9305229 -0.3358477 -0.7715251 -0.5403289 -0.1308273 0.6416972 -0.7557175 0.9883919 0.1519256 -1.75861e-4 0.2588151 -0.9658592 -0.01143848 -0.975515 -0.2193326 0.01623803 -0.1486166 0.9888923 0.00225234 0.003182411 -0.9998849 0.01483815 -0.6739904 -0.7386045 -0.01415801 0.08487886 -0.02084618 0.9961732 0.1896651 -0.04820615 0.9806648 0.3366129 0.05963659 0.9397528 -0.07799291 -0.03841227 0.9962137 -0.1240054 -0.2307727 0.9650734 -0.09050107 -0.3377474 0.9368758 -0.001180768 -0.004404485 0.9999896 0.001185595 0.002972424 0.9999949 -1.2984e-4 4.85366e-4 0.9999999 -0.7970608 -0.06462258 -0.6004316 0.3773352 -0.5592665 -0.7381323 0.7195015 0.05387026 -0.6923985 0.9547004 0.2794668 -0.1022029 -0.2082282 0.7133854 -0.6691206 -0.4692789 0.3026406 -0.8295699 0.04120665 0.8078814 -0.5879028 0.254961 0.9669257 -0.007052421 0.9839084 0.1722254 0.04757016 -0.6716688 -0.7406072 -0.01902949 -0.8917818 0.444011 0.08705997 0.3909 0.9184783 0.05995756 0.9997456 -0.01863086 -0.012721 0.3149395 -0.9484099 -0.03649407 -0.7248399 -0.6886727 0.01836359 -0.7691369 0.6390729 -0.003800451 -0.02640223 0.04562175 0.9986099 0.04063063 0.05094885 0.9978745 0.06140106 0.03140115 0.9976191 0.008287966 -0.04635256 0.9988908 0.2029688 -0.2437136 0.9483709 -0.1867002 -0.3310792 0.9249485 6.62047e-5 1.21411e-4 1 3.65979e-4 -4.59322e-4 0.9999998 0.05628913 -0.0013628 0.9984136 2.10625e-5 -9.04597e-5 1 2.06036e-5 -0.004149556 0.9999914 0.01050937 0.006690382 0.9999224 6.14754e-4 0.004163324 0.9999912 -0.7642167 0.1027541 -0.6367218 -0.8231017 0.3963736 -0.4066839 -0.7906304 -0.3861053 -0.4752118 -0.3314522 -0.7195045 -0.6102891 0.8329873 0.006006777 -0.5532595 0.7772527 -0.3742964 -0.5057474 0.430397 -0.683483 -0.5895841 0.1894347 0.8299764 -0.5246464 0.3452382 -0.4329098 -0.8327064 -0.6039132 0.757304 -0.2485551 -0.2100517 -0.7297408 -0.6506587 0.760915 0.05464404 -0.6465466 0.04609686 -0.5480016 -0.8352063 -0.5778983 -0.1456415 -0.8030081 0.2140762 0.9767438 -0.01195627 -0.9529901 -0.3030005 -8.51572e-4 -0.7373137 0.6723568 0.06561249 0 3.51204e-6 1 -1.11073e-6 5.63428e-6 1 9.41829e-4 -0.001882553 0.9999978 -1.68774e-5 -1.67853e-4 1 -1.43733e-6 -3.51224e-6 1 8.49769e-4 0.003853261 0.9999923 -7.92312e-5 0 1 -1.72553e-6 -2.45918e-6 1 -2.50347e-5 -6.39266e-5 1 1.76561e-4 -8.50687e-5 1 -3.21738e-4 -0.01707029 0.9998543 3.21738e-4 0.01707082 0.9998543 -0.8266124 -0.398069 -0.3978102 0.1910803 -0.8371656 -0.5124862 -0.02892148 -0.7754325 -0.6307679 0.8137257 -0.01898151 -0.5809391 0.831241 0.394153 -0.3920227 0.5772178 0.7238076 -0.3780506 -0.08263963 0.7109731 -0.6983467 0.5661008 -0.7098658 -0.419071 0.01243603 0.7892591 -0.6139344 0.8568814 0.5135106 0.04539769 -0.1822227 -0.132787 0.9742497 -0.6004951 -0.2645668 0.7545927 -0.7176304 -0.6562352 0.2331565 0.8742718 0.4836657 0.04142802 -0.5100106 -0.4235349 0.7486704 -0.8574632 -0.5128977 0.04114335 0.9481805 0.2726486 -0.1631458 0.5269929 0.416468 0.7408327 0.6970481 0.1603121 0.6988734 0.6105883 0.3688637 0.7008007 0.009919106 0.005726873 0.9999344 -0.6903666 -0.4707321 0.5493682 -0.4394595 0.5410591 0.7170289 0.040497 0.005526483 0.9991644 -0.3483403 0.2612781 0.9002182 -0.05750524 -0.06937378 0.9959319 -0.08966827 0.1477702 0.9849485 -0.09323936 -0.06678712 0.9934012 -0.2598 0.08519083 0.9618973 -0.06173658 -0.3066239 0.9498265 0.004631578 0.03656673 0.9993205 -0.674244 -0.3585766 0.6456144 -0.6114821 -0.3444586 0.7123468 -0.6072493 -0.216133 0.7645488 0.5763683 0.3433443 0.741562 0.58684 0.3871769 0.7111349 0.6368553 0.3831352 0.6690461 0.1968877 -0.9634907 0.1814417 0.3509975 -0.2937745 0.8890992 0.02286726 0.03037089 0.9992772 -4.09096e-4 -2.3769e-4 0.9999999 0.07274466 0.02723032 0.9969788 0.8585357 0.5120385 -0.02707594 0.86122 0.4189198 0.287761 -0.4043351 -0.2382684 0.8830296 -0.8715763 -0.487069 0.05584758 -0.8782166 -0.4319607 0.2052941 0.675334 0.4002761 0.6194377 0.8644297 0.4983389 0.06648117 0.002392053 0.001122832 0.9999966 -0.0096215 -0.009797453 0.9999057 -0.1321373 -0.03674131 0.9905503 0.01411616 0.004690527 0.9998894 -0.4533831 -0.2678975 0.8501027 0.08615803 0.08146756 0.9929451 0.008787512 0.003424286 0.9999556 0.4573478 -0.225267 0.8602837 -0.009743273 -2.66703e-5 0.9999526 0.002343893 0.001994729 0.9999954 0.05408114 0.01356124 0.9984445 -0.005046308 -3.27482e-4 0.9999873 -0.1186078 -0.1170761 0.986015 0.06642645 -0.1380433 0.9881961 0.6936436 0.4662127 -0.5490942 0.8989909 0.4014105 0.1751719 -0.9089186 -0.4157781 0.03155481 -0.8431294 -0.5264881 0.1092845 0 0 -1 0.5064104 -0.8575732 -0.09009283 0.4991229 -0.8642818 -0.06239658 0.1573752 -0.9684574 -0.1931923 -0.3093963 -0.947679 -0.07860356 -0.8639124 -0.4976071 -0.07773482 -0.9764143 0.1971051 -0.08811867 -0.9710625 0.2299982 -0.06433182 -0.5636799 0.8259825 -0.004261732 -0.497809 0.8625512 -0.09050917 -0.2391089 0.9694255 -0.05514663 0.3206173 0.9398289 -0.1180095 0.3095532 0.9475996 -0.07894223 0.3035184 0.9499297 -0.07423079 0.8629272 0.498012 -0.08567821 0.9762934 -0.1966538 -0.09043532 -0.3295408 -0.1745259 -0.9278705 -0.08917057 -0.05148392 -0.9946849 -0.3364756 -0.2149124 -0.9168407 -0.594883 -0.35495 -0.7211968 -0.5958567 -0.327573 -0.7332469 -0.6124175 -0.3529194 -0.7073845 -0.7070476 -0.3848192 -0.5932941 -0.7546947 -0.4169216 -0.5065695 0.6123977 0.35313 -0.7072965 0.8145296 0.4861984 -0.316469 0.6123939 0.3535518 -0.7070891 0.573692 0.2751581 -0.7714697 0.2491627 0.14329 -0.9578027 0.3046965 0.1660342 -0.9378661 0.08939808 0.05160224 -0.9946584 0.9901362 -0.1401054 -0.001046478 -0.4900656 -0.8201836 0.2951862 -0.8997161 -0.4090353 0.1523196 -0.8804604 -0.444977 0.1636618 0.8232051 0.5547703 0.1206785 0.9092185 0.2200327 0.3534223 0.565101 0.4049745 0.7187883 0.5345857 0.3749537 0.7573824 0.6082708 0.3597161 0.7075387 0.5398823 0.3694451 0.7563316 0.6674528 0.6034628 0.4362792 -0.1160348 0.2006787 -0.972761 -0.1141404 0.1977028 -0.9735941 0.8105894 0.4727126 -0.3456698 -0.8864735 -0.09405344 -0.453121 0.8877138 0.09240329 -0.4510276 0.8653305 0.1283909 -0.484478 0.5755394 -0.8176235 0.01569545 -0.5475577 -0.6685886 -0.50316 0.1141594 -0.1977303 -0.9735864 0.3610255 -0.6288334 -0.6886431 -0.5152094 -0.8364514 0.1868376 -0.8368072 -0.486329 -0.2514714 0.02265328 -0.4945211 -0.8688703 -0.6360996 -0.6532555 -0.4106514 -0.7936375 -0.4508687 -0.4084813 -0.5642676 0.4689655 -0.6794656 -0.3924375 -0.9119079 0.1200703 0.0971682 -0.9896482 -0.1056166 -0.8365888 0.5478315 2.86718e-4 -0.839735 0.5426444 0.01955389 0.8640422 0.4987256 -0.06858384 -0.3675168 -0.2264412 -0.9020287 -0.4025817 -0.4455603 -0.7996274 -0.3710379 -0.3621427 -0.8550928 0.8287665 0.4776496 -0.2915428 0.8309051 0.4783802 -0.2841641 0.0629059 0.9963769 -0.05723696 -0.00868988 0.9998645 -0.01398801 0.8926765 -0.45003 -0.0245344 0.8835304 -0.462005 -0.07697582 0.8658638 0.4981722 -0.04587638 -0.8639917 -0.4986734 -0.06959313 -0.07918071 -0.05816531 -0.9951619 0.2398957 0.1391769 -0.9607704 0.4621245 0.2276639 -0.857094 0.6796224 0.388692 -0.622119 0.5838574 0.382918 -0.7158803 0.1111502 -0.9778557 0.1773247 -0.6316646 -0.3742177 -0.6789411 0.3902872 -0.5732372 0.7204687 0.3972996 -0.5557808 0.7302471 -0.3292514 0.6062829 0.7238885 0.1295579 0.02821356 0.9911705 -0.09655958 0.0514664 0.9939957 7.43472e-6 8.32377e-5 1 0.2064306 0.1205806 0.9710029 0.2272667 0.1252549 0.9657438 2.73158e-4 0.01341325 0.9999101 -0.4796183 -0.2805346 0.8314246 -0.8647828 -0.4994951 0.05153107 0.8453705 0.4430484 0.2984239 0.1946682 0.8742558 0.4447258 -0.7998306 0.1692105 0.5758808 -0.284798 -0.9582172 -0.02664619 -0.4435126 -0.2628461 0.8568598 -0.5928968 -0.4248794 0.6840694 -0.9394684 0.3418568 -0.02308833 0.7019636 -0.67149 0.2373782 0.2767605 -0.874792 0.3976715 -0.3524786 -0.706546 0.6136382 -0.8465963 -0.5157064 0.1316117 -0.7882668 -0.5913823 0.1700072 0.8859043 0.4505733 0.1102599 0.8928623 0.4340118 0.1201277 0.8930513 0.4378051 0.1038562 0.5000904 -0.8655012 0.02859348 -7.92686e-5 -1.79989e-5 1 -4.32119e-4 9.51386e-4 0.9999995 0.495352 -0.8578342 0.13692 -0.4237977 0.8874269 0.1812983 -0.4988542 0.8655205 0.04493081 0.4955123 -0.8671513 0.05016213 0.4975693 -0.8658961 0.05146813 -0.53514 0.8369488 0.1146383 0.3993387 0.7421242 0.5383125 0.8271508 0.5522344 0.1042057 0.8457087 0.5198774 0.1204341 -0.8688937 -0.4794163 0.1232231 -0.892686 -0.4212242 0.1602563 -0.7001984 0.239899 0.6724363 -0.8914719 -0.4410306 0.1037788 -0.5566493 0.8187885 -0.1404531 -0.4992023 0.8661469 0.02422535 -0.4943222 0.8578808 0.1403068 -0.4941999 0.8686552 -0.03471213 -0.6365747 0.7547129 0.1586859 -0.3099099 0.9471839 -0.08245396 -0.6993125 0.7111274 0.07252526 0.5262377 -0.8467572 0.07794958 0.4720515 -0.8815378 -0.007662355 -0.6653099 0.74198 -0.08263504 -0.5015351 0.8637939 0.04819375 0.004847526 -0.6077307 0.7941285 -0.3868175 0.6930899 0.6082751 -0.1855099 -0.0574426 0.980962 -0.4947419 0.2981961 0.816278 -0.3857958 0.7053593 0.5946679 -0.007352054 -0.003511607 0.9999668 0.152561 -0.001580119 0.9882928 -0.2569881 -0.1535004 0.9541461 0.2523643 0.1382988 0.9576982 -0.1219835 -0.1709076 0.9777069 -0.03128743 0.1340968 0.9904742 -0.002955555 0.009434521 0.9999512 -0.2464846 -0.1391212 0.9591093 0.06045901 -0.01221764 0.998096 0.101688 -0.1925542 0.9760033 0.2669557 0.1531292 0.9514653 -0.4898729 0.8705633 0.04630517 0.4680413 -0.8827703 0.04066956 0.3838795 -0.9219188 0.05198448 -0.8599056 -0.5004861 0.10038 -0.8542357 -0.5084632 0.1083824 0.5609033 -0.8244537 0.07525914 0.6416545 -0.7655335 0.04730838 0.8330867 0.5512114 0.04618161 -0.5619339 0.8237406 0.07537758 -0.83243 -0.5458372 0.09551 -0.8663288 -0.4974736 0.04465854 -0.4184442 0.9055829 0.06945532 0.862109 0.4966883 0.1003447 -0.04157221 -0.07985979 0.9959389 0.1295612 0.121486 0.9841011 -0.09007185 -0.06965464 0.9934965 -0.1445032 0.9311796 0.334699 -0.4603895 -0.269496 0.8458213 0.08010447 -0.003525495 0.9967803 0.2153726 -0.3325839 0.9181517 0.3781291 -0.6769194 0.6315049 -0.1512547 0.1980144 0.9684587 -0.4021208 0.7578422 0.5137841 -0.1434073 0.1352038 0.9803848 -0.3397592 0.4385659 0.8319999 0.6364195 -0.7707111 -0.03122049 0.6512045 0.3480869 0.6743651 -0.2940243 -0.4616346 0.836925 -0.2911248 0.1941844 0.9367705 0.1815507 0.4237834 0.8873822 -0.8217486 -0.5096819 0.2548602 0.6639785 0.4500585 0.5971431 -0.1160447 -0.9908913 0.06832361 0.27108 -0.2234046 0.9362724 0.8189479 -0.5719565 0.04679805 -0.5302639 0.3859748 0.7548799 -0.5920937 0.7949942 -0.1319447 0.8424295 -0.4502197 -0.2959983 -0.787424 0.5405672 -0.2962276 -0.8221918 0.5671572 0.04830718 0.6126037 -0.3540503 0.7066577 0.6146405 -0.3458138 0.7089641 0.4811366 -0.2777842 0.8314707 -0.004934906 0.008205235 0.9999542 -0.5855873 0.4384956 0.6817691 0.1165009 -0.1122031 0.9868323 -0.2383911 -0.1696681 0.9562335 0.05917853 -0.0241937 0.9979543 -0.04634773 -0.06101137 0.9970604 -0.09776544 -0.5201246 0.8484765 -0.01964288 0.3410021 0.9398573 -0.8379452 0.4072969 0.3632589 0.08596056 -0.08616673 0.9925654 -0.6016682 0.3570809 0.7144848 -0.6123557 0.3544465 0.706674 -0.6597838 0.3033865 0.6874896 0.6718711 -0.4320814 0.6015771 0.6124693 -0.3552392 0.7061774 -0.8205426 -0.4232186 -0.3841822 0.1334805 -0.7170475 -0.6841242 0.06823313 0.03498286 0.9970559 0.9072617 -0.413937 -0.07438111 0.6519243 -0.7238893 0.2257856 -0.8426651 0.4258692 0.3294709 -0.8650808 0.4993187 0.04812586 0.3455988 -0.2002948 0.9167571 0.8613345 -0.4972637 0.104076 -0.009943366 0.004611194 0.99994 3.70395e-4 0.001091957 0.9999994 -0.1085724 0.1009244 0.9889522 0.009483635 -0.005648136 0.9999392 0.08780902 0.1737413 0.9808688 -0.1241853 0.04160851 0.9913863 -0.4778377 -0.7937045 -0.3764363 0.06368035 0.7328662 0.6773861 0.2118749 -0.9299963 0.3003597 0.06457704 -0.05622428 0.9963276 -0.002948462 0.002474308 0.9999927 0.1478832 -0.04559534 0.9879533 0.01242184 0.002023994 0.9999209 -0.009169459 0.01465106 0.9998506 0.09818011 -0.02825248 0.9947676 0.2255024 0.2168779 0.9497962 0.8838692 0.03374922 -0.466515 0.1280114 -0.1894583 0.9735085 -0.2911077 -0.5226187 0.8013277 0.7811361 0.6182193 0.08735769 0.6157543 -0.3562827 -0.7027869 0.8233307 0.1237431 0.5539082 0.8624154 -0.502862 0.05804663 -0.7213901 0.6422591 0.2590361 0 0 -1 -0.48762 -0.8678963 -0.09477734 -0.4077759 -0.9130755 0.003461778 -0.7501283 -0.6612504 0.007459223 -0.6710613 -0.7305418 -0.1264338 -0.8628286 0.4983414 -0.08475077 -0.3249378 0.9439656 -0.0578311 -0.1548591 0.987612 0.02532607 0.4888101 0.8710324 -0.04865664 0.5794607 0.8146775 -0.02293407 0.4982674 0.8627275 -0.08620363 0.9747399 0.1971977 -0.1048592 0.9753887 0.206039 -0.07851821 0.9740204 0.2146374 -0.07221591 0.8634555 -0.500506 -0.06275844 0.3485476 -0.9142792 -0.2064176 0.2773064 -0.9589247 -0.05970394 -0.08939605 0.05162346 -0.9946574 -0.3304311 0.1840146 -0.9257181 -0.6036405 0.330599 -0.7254809 -0.6124836 0.3535487 -0.7070128 -0.6123421 0.353809 -0.7070052 0.6120917 -0.3540588 -0.7070969 0.6128681 -0.356054 -0.7054207 0.22889 -0.1863908 -0.9554412 0.4029402 -0.2236211 -0.8874869 0.4605761 -0.2352267 -0.8558844 0.989997 0.1194912 0.07501822 -0.6958065 0.2669146 0.6667908 -0.8217145 0.5582562 0.1146096 0.8579047 -0.5081061 0.07634109 0.8604084 -0.4880994 0.1464796 0.688972 -0.3675449 0.6246826 0.6072614 -0.3508124 0.7128564 0.3603157 0.621887 -0.6952908 0.1134881 0.1965668 -0.9739004 -0.160829 0.8379372 -0.5215318 -0.5251746 0.7196375 -0.4542176 -0.8113903 0.4625055 -0.3573996 -0.8334853 0.4815569 -0.2709342 0.09276086 -0.9515315 -0.2932291 0.06176126 -0.9504169 -0.3047842 0.06348961 -0.9381735 -0.3402933 -0.8818282 0.1051149 -0.4597064 -0.8522462 0.1404718 -0.5039289 -0.3640533 -0.6270319 -0.6886916 0.02083289 -0.8171579 -0.5760373 -0.8015927 0.4722599 -0.3666331 -0.6669927 0.5277653 0.5259131 -0.8004273 -0.5985465 -0.03253287 -0.8692591 0.4937114 -0.02525436 -0.8644418 0.4991882 -0.05959624 0.05262881 0.9953338 0.08087664 -0.1564277 0.9862464 -0.0533716 0.2625805 0.2518166 -0.931472 -0.4320762 0.194673 -0.8805753 -0.6188131 0.3336816 -0.7111448 -0.7017464 0.4020108 -0.5881662 -0.7441006 -0.3765301 -0.5518509 0.9592122 0.1418555 -0.2445178 0.951753 0.278239 -0.1294193 0.8422579 -0.4890404 -0.2268062 0.8577944 0.5137214 -0.016707 -0.1351867 -0.9906687 -0.01732462 0.07874298 -0.987827 -0.1341546 -0.8637607 0.4988497 -0.07118034 0.231193 -0.1266921 -0.9646238 0.4166873 -0.3259159 -0.8486168 0.4401568 -0.2010409 -0.8751254 0.6749721 -0.3763784 -0.6346275 0.1730383 0.9797009 0.1012125 0.3688617 0.5627552 0.7397619 -0.04231441 0.02363491 0.9988248 -6.03909e-4 -2.10567e-4 0.9999999 0.1063713 -0.04300796 0.9933959 0.2032642 -0.1143311 0.9724259 -3.25438e-4 -7.31137e-5 1 -0.06662917 -0.05927985 0.9960154 0.01196831 0.007128357 0.999903 -0.4619774 0.2667229 0.8458343 -0.8822164 0.4672781 0.057841 0.9374072 0.3476797 -0.01966369 0.8755372 0.4591288 0.1504507 -0.9957242 -0.08451008 -0.03730136 0.8456441 -0.5303363 0.06024575 0.4381612 0.8915438 0.1147367 -0.5072849 -0.8527411 0.1244775 -0.7366448 -0.1901268 0.6490041 -0.8566619 0.5139948 0.0440461 -0.8193728 0.5683148 0.07514512 0.8877823 -0.456129 0.06155323 0.8709654 -0.4893703 0.04399979 -0.5455974 -0.8304928 -0.1122726 -0.5015293 -0.8639112 0.046108 -6.77046e-4 -0.001150429 0.9999991 0.3971295 0.7649813 0.5070425 -0.5007962 -0.8646345 0.04012823 -0.49443 -0.8680895 0.04426991 -0.4960779 -0.8673079 0.04103612 -0.5006704 -0.8643709 0.0468223 0.5255996 0.8489742 0.05466151 0.8423194 0.02506697 0.5383956 -0.1395078 0.721176 0.6785594 0.4306901 0.8915095 -0.1404166 0.5002815 0.8655344 0.02385014 -5.78015e-4 -6.782e-4 0.9999997 -1.5544e-5 8.58197e-4 0.9999997 -0.4796677 -0.8076347 0.3429945 0.4663684 0.8800649 0.08936691 0.6653063 0.7419766 -0.08269447 -0.4392871 -0.8974316 0.04053694 -0.4699712 -0.8790009 0.08052682 -0.499738 -0.8650738 0.04369801 6.99345e-4 -0.5871481 0.8094793 -0.1609206 0.02695143 0.9865994 0.4023448 0.6807585 0.6121165 9.79003e-4 0.5810592 0.8138608 0.416589 0.6873626 0.5949675 -0.2634819 0.1469981 0.9533987 0.2500139 -0.1515824 0.9563032 0.1723541 -0.1467199 0.9740469 0.006931304 0.007326126 0.9999492 -0.07776373 0.01207101 0.9968988 -0.0524131 0.1393669 0.9888528 0.01964825 -0.05847299 0.9980956 -0.1114946 -0.1802912 0.9772738 -6.96602e-4 3.38832e-4 0.9999998 -0.8642732 0.4999116 0.05585974 0.006749153 0.002732157 0.9999735 0.8606052 -0.5067691 0.05043876 0.8650799 -0.500581 0.03248882 -0.8660864 0.4962677 0.06010586 -0.4601052 -0.8829912 0.09289717 -0.7329049 -0.6803262 0.002586603 -0.5487214 -0.8329532 0.07137161 -0.861743 0.4979857 0.09700214 -0.4318831 -0.8987827 0.0752778 -0.1495124 -0.9887093 -0.01001054 0.8969855 -0.4414526 -0.02316999 0.8202341 -0.562556 0.1036667 0.341926 0.9381086 0.05512678 -0.8657377 0.4985913 0.04364585 0.7178106 0.6960974 0.01401656 0.5452944 0.8335289 0.08879047 0.8295882 -0.5482755 0.1057229 0.192462 -0.1066915 0.9754873 0.4397322 -0.3342121 0.8336294 0.1007432 0.03570246 0.9942716 -0.3604267 -0.6153586 0.7010181 0.1033301 0.2495145 0.9628425 -0.1898899 -0.2314858 0.954126 -0.3174328 -0.6120759 0.7242925 0.4236465 0.8498876 0.3133925 0.09483093 0.006358027 0.9954731 -0.3411704 -0.3507273 0.87212 0.5391993 -0.4613664 0.7045602 0.4017581 0.499462 0.767547 -0.4747267 0.08822208 0.8757005 0.7691168 -0.6073205 0.1990509 -0.7457197 -0.4416605 0.4988369 0.9048866 -0.4196256 0.07137697 0.6024692 -0.3785629 0.702653 0.1116883 0.1869595 0.9759979 0.7090784 -0.3424572 0.6163854 -0.2824233 0.2274732 0.9319298 -0.9441292 0.3270315 0.04087388 0.9325073 -0.3587678 0.04142481 -0.9112083 0.2992162 -0.2831416 -0.9327743 0.3583014 0.03940004 -0.8038945 0.5881287 -0.08864718 0.6577312 -0.1254259 0.7427369 0.8582916 -0.3906268 -0.3327856 -0.2091538 0.04703354 0.976751 -0.6901082 0.08546906 0.7186416 -0.5874084 0.213795 0.7805403 -0.5918111 0.2169285 0.7763386 -0.6527025 0.2406203 0.718388 0.6707037 -0.173049 0.7212563 0.02749067 -0.7478711 0.6632747 0.1245828 -0.4705098 0.8735557 0.03442883 0.0664317 0.9971968 0.0333358 0.06640952 0.9972354 -0.3097973 0.05519282 0.9491994 -0.6209916 0.2950245 0.726175 -0.6430594 0.2898905 0.7088287 -0.48273 0.1531713 0.8622705 0.0259025 -0.06943434 0.9972503 -0.06229728 0.04657512 0.9969704 -0.9458188 0.3197531 0.05643445 -0.8454883 0.380743 0.374412 0.3557386 -0.1814352 0.916805 0.8593072 -0.1949965 -0.4728293 0.9261608 -0.3743717 0.04552185 -0.6194091 0.2177275 0.7542726 -0.9135766 0.3554715 0.19753 0.007164716 -0.002572536 0.9999711 -0.007406711 -0.002922117 0.9999683 -0.09568136 -0.1205001 0.9880916 0.07778722 -0.01140826 0.9969048 0.07125914 0.2600626 0.9629588 4.16525e-4 -2.09485e-5 1 -3.02108e-4 5.91234e-4 0.9999999 -0.01384752 -0.002029478 0.9999021 -0.1076192 -0.2037654 0.9730868 0.1004701 0.2590807 0.960616 -0.8064679 0.2319199 -0.543896 -0.9295057 0.3612217 0.07441878 0.9557913 -0.2873365 0.06245601 0.8886394 -0.4272078 0.166774 -0.2813068 0.9461811 -0.1600247 0.2585297 0.9658725 -0.01589918 0.6235623 0.7790887 -0.0647363 0.9259971 0.3587989 -0.1174425 0.9246063 0.3738618 -0.07301151 0.9365595 -0.3421564 -0.07606136 0.428282 -0.9002386 0.07838898 0.476488 -0.8747807 -0.08785289 0.1605975 -0.9641147 -0.2114034 -0.3305398 -0.9424512 -0.05029356 -0.3407375 -0.935716 -0.09128856 -0.6196216 -0.7842266 0.03252404 -0.9248206 -0.3721802 -0.07866972 -0.936062 0.3407752 -0.08752238 -0.4501595 0.890501 -0.066064 0.2802369 -0.1019946 -0.9544969 0.3568153 -0.1462865 -0.9226502 0.09675556 -0.03521704 -0.9946849 0.3553525 -0.1151906 -0.9276075 0.8241506 -0.19867 -0.5303829 0.6644657 -0.2418272 -0.7071103 0.664444 -0.2418718 -0.7071154 0.6644988 -0.2418594 -0.7070682 0.6647442 -0.2413315 -0.7070179 0.6395338 -0.250803 -0.7267011 -0.6644814 0.2419122 -0.7070665 -0.6483818 0.2200351 -0.7288249 -0.5219044 0.129397 -0.8431325 -0.09182471 0.1337136 -0.9867568 -0.5251149 0.1909086 -0.8293421 -0.5423271 0.8373527 0.06871557 0.6837714 -0.1683247 0.7100165 0.5848681 -0.3326461 0.739781 0.9342458 -0.3521298 0.05647695 0.601542 -0.7470476 -0.2829614 0.8158585 0.08981561 0.5712339 0.9295603 -0.3682807 0.01694649 -0.5985113 0.643481 0.4771965 -0.9457351 -0.2523587 -0.2046953 -0.9428541 0.3276902 0.0603767 -0.6708512 0.1729742 0.7211371 -0.6780465 0.1969505 0.7081408 -0.6438006 0.2939088 0.7064974 -0.9674364 -0.04816913 0.2484887 -0.2468538 -0.675018 -0.6952797 -0.2400029 -0.6602391 -0.7116761 -0.8640012 -0.01015293 -0.5033875 -0.9018214 0.3284699 -0.280759 0.6418761 -0.6185336 -0.4532232 -0.6414397 0.6205952 -0.4510174 0.8793719 -0.3145821 -0.3574117 0.9047142 -0.3296787 -0.2698231 0.2259784 0.8981241 -0.3772361 -0.5969535 0.5816615 -0.5525545 0.8856952 0.05584293 -0.4608967 0.07809454 0.2145583 -0.9735841 0.07061171 0.1909625 -0.9790543 0.2540041 0.6806549 -0.6871615 0.2931401 0.8327493 -0.4696782 0.1901198 -0.001646876 -0.9817596 0.704671 0.6293581 -0.3276391 0.8781504 -0.05032378 -0.4757304 -0.4572426 -0.7130194 -0.5315378 0.7086941 0.7043052 -0.04131549 0.7130126 0.7007626 -0.02333873 0.9384529 -0.3419673 -0.04862612 0.9378154 -0.345598 -0.03262627 0.03865063 -0.9988798 -0.02730149 -0.9440364 0.329458 -0.01590251 -0.9368548 0.341801 -0.07399541 0.3976174 -0.1313586 -0.9081 0.4999882 -0.1709555 -0.8489912 0.6922963 -0.2291473 -0.6842641 0.8703116 0.4903352 -0.0461421 0.8240587 0.5627774 -0.06487607 -0.7805494 -0.3241063 -0.5345073 -0.9189858 -0.3143354 -0.2380307 -0.8889789 -0.439259 -0.1294921 -0.7575222 -0.647257 0.08496242 -0.7342534 -0.6775068 -0.04308867 -0.9405785 0.3386394 -0.02520513 -0.9391791 0.3412192 -0.03888684 -0.1020104 0.9946318 0.01736259 -0.1102206 0.9926169 0.05062806 0.9374569 -0.341219 -0.06887865 -0.2557319 0.08643996 -0.9628756 -0.7249332 0.2979761 -0.621033 0.8401921 0.1400032 -0.5239049 -0.7490574 0.2761554 -0.6022053 -0.7199767 0.25991 -0.6434908 -0.7300006 0.2547182 -0.6342064 0.6743074 -0.2449452 -0.6966429 0.7054399 -0.2437236 -0.6655474 0.5593608 -0.7672642 -0.3137218 0.2351472 0.6341541 0.736583 -0.2400364 -0.6518971 0.7193141 -0.2833024 -0.643088 0.7114616 -0.1111333 -0.9070594 0.4060699 -0.05291891 -0.07374131 0.9958724 0.2108385 -0.07220679 0.9748505 -0.04535043 -0.03280323 0.9984325 0.3020533 -0.108675 0.9470763 0.6633399 -0.2428651 0.7078112 -0.8869738 0.4193519 0.1934468 0.9347321 -0.2981443 0.1933545 -0.5498153 0.2181748 0.8062896 -0.9112239 0.3257575 0.2520976 -0.897598 0.4230064 -0.1240303 -0.9382974 -0.3322482 0.09596496 0.9327788 -0.1190198 -0.3402323 -0.8701283 0.2925003 0.3966363 0.745373 -0.2627185 0.6126975 -0.5695024 -0.7354201 0.3671846 -0.2186094 0.9593655 0.1784033 -0.08471608 0.9484064 0.30553 -0.3484085 -0.9319607 0.1003032 0.4809042 0.8572049 0.1842038 0.9542276 -0.2803645 0.1041417 0.9376717 -0.3243973 0.1246526 0.9529114 -0.2587318 0.1581696 -0.8951829 0.4188613 0.1523242 -0.5666632 0.6217492 0.5406671 -0.9130085 0.393413 0.1078979 0.3412762 0.9396339 0.02487838 0.3415098 0.9394838 0.02722764 3.11358e-4 6.81039e-4 0.9999998 5.68282e-4 0.001123487 0.9999992 0.3426983 0.9384713 0.04277336 0.3641628 0.9246039 0.1117724 0.3422797 0.9387092 0.04086303 0.3370369 0.9402664 0.04801386 0.4879404 0.8602808 0.1477532 0.3360093 0.9412188 -0.03471195 -0.3413094 -0.9378237 0.06320399 -0.2924852 -0.9495815 0.112905 -0.9063433 0.4159297 0.07446092 -0.957445 0.2332276 0.1700121 0.9295551 -0.3455362 0.1285777 -0.5021656 -0.4356406 0.7470255 -0.3432856 -0.9390462 0.01864039 -0.3484333 -0.9368963 -0.02863031 -0.3453841 -0.9374877 0.04273825 -0.3037658 -0.9526266 0.01513469 -0.3415896 -0.938584 0.04875248 0.3973637 0.910786 0.1121206 0.3418984 0.9388863 0.03997802 0.3402346 0.9392364 0.04555726 -0.4871901 -0.8601254 0.1510967 -0.3748506 -0.9270726 0.004846036 -0.1033838 0.5776605 0.8097037 0.1619306 0.002175331 0.9867998 -0.4153339 -0.3821597 0.825501 -0.2899811 -0.7465294 0.5988363 0.007416009 -0.003375589 0.9999668 -0.2615955 0.09814143 0.960175 -0.3043829 0.1053957 0.9467011 -0.1937354 0.118172 0.9739108 -0.1071709 -0.1423093 0.9840034 -0.005554199 -0.008418738 0.9999492 0.07688111 -0.1299923 0.98853 0.9382421 -0.3416951 0.0542792 0.3646656 0.9270734 0.08691293 -0.3811774 -0.9218939 0.06939363 -0.3520603 -0.9347804 0.04732143 -0.007879137 0.01017063 0.9999173 0.02865821 -0.01686787 0.999447 -0.3822258 -0.9182836 0.1032412 -0.9387453 0.3427932 0.0353567 0.9389102 -0.3389628 0.05959743 0.3754055 0.9259805 0.04038327 0.298931 0.9497046 0.09328216 0.009792804 -0.005306184 0.999938 -0.01872241 0.01577979 0.9997002 0.4587428 0.8866614 0.05819624 0.4219315 0.9039752 0.06930255 0.2600097 0.9553669 0.1402471 -0.9645897 0.2626146 0.02450299 -0.2691025 -0.9602041 0.07478022 -0.1713072 -0.9841337 0.04620528 0.9531754 -0.2868936 0.09564894 -0.4589486 -0.8869535 0.0517677 -0.3959568 -0.9154956 0.07131713 -0.9331126 0.3443532 0.103546 -0.1175725 -0.08576595 0.9893538 -0.1595696 0.0134254 0.9870954 -0.6803832 0.2681239 0.6820473 -0.4929958 0.252239 0.8326649 0.4763057 -0.165697 0.8635262 0.07627743 0.2003052 0.9767597 0.2460471 0.7794198 -0.5761646 0.09079927 0.2433715 0.9656738 -0.07343649 -0.2890555 0.9544915 -0.2487756 -0.6837637 0.6859869 0.3239547 0.4705166 0.8207726 -0.1534104 -0.9875888 0.03366971 0.4849263 -0.4440256 -0.7534505 0.3670639 0.4762869 0.7990087 0.109179 0.4930804 0.8631058 -0.9127925 0.4066462 -0.03806328 0.6117973 -0.485862 -0.6242133 0.1374815 -0.7395877 0.6588694 -0.9522787 0.3008754 -0.05137342 0.8574672 -0.4040085 0.3186334 -0.1989537 0.1947081 0.9604719 -0.1708941 0.08010703 -0.9820276 -0.9492233 0.2402209 0.2031484 0.933196 0.356418 0.04595333 0.964706 0.2163777 0.1500775 -0.7484926 -0.2724258 0.6046015 -0.9501749 -0.2529113 0.1822184 -0.9457387 -0.3225349 0.03936529 -0.9836273 0.09411162 -0.153689 0.9609115 0.2739127 0.0402643 0.6651409 0.6082432 0.4331604 -0.5735446 -0.3356519 0.7472513 -0.9350872 -0.3160466 0.1603949 0.1373755 0.1019307 0.9852604 0.1353933 0.7103304 0.6907238 0.5830386 0.4587188 0.6705543 0.6298015 0.2112708 0.7474722 0.6340838 0.2065277 0.7451739 0.6388445 0.2198143 0.7372649 0.002737522 -0.02174806 0.9997598 -0.6943964 -0.3044362 0.6520217 -0.6008287 -0.268931 0.7527823 -0.1462813 0.5646206 0.8122842 0.03781694 0.01876068 0.9991087 -0.1199827 0.1064921 0.987048 0.1365919 0.1243292 0.9827944 -0.01970857 -0.1753019 0.9843175 -0.1340455 -0.05392545 0.989507 0.0648508 0.01190465 0.997824 -0.5579514 -0.242106 0.7937726 0.6477805 0.1494781 0.7470185 0.6297132 0.2396485 0.7389384 0.6233953 0.2269142 0.7482569 0.610307 0.2355074 0.7563476 -0.06083822 -0.04616808 0.9970794 -0.01632517 0.07301992 0.9971969 -0.01714879 0.07230025 0.9972355 0.07017737 0.05056172 0.9962523 -0.7593981 -0.2102074 0.6157335 -0.4197574 -0.1636323 0.8927645 -0.9450345 -0.3072716 0.1117765 -0.9386559 -0.3417654 0.04606115 -0.9375225 -0.3435506 0.05499631 0.407342 0.1570947 0.8996631 0.9338599 0.3394441 0.1126211 -0.01477634 -0.01072132 0.9998334 -0.001348435 -4.89335e-4 0.9999991 0.1379675 0.08961111 0.9863746 0.3101812 -0.06078535 0.9487323 0.6020739 0.6821296 0.4149776 -0.8545688 0.1097241 0.5076149 -0.1071591 0.07933861 0.9910713 0.1797751 -0.1459256 0.9728241 0.519661 -0.6342945 0.5723836 -0.02613532 0.004694163 0.9996475 0.01103788 0.005414605 0.9999245 -0.03776252 0.006647765 0.9992647 -0.03280466 0.009956419 0.9994122 -0.250023 0.522334 0.8152643 0.4858442 -0.04685622 0.8727886 0.2078729 -0.5863126 0.7829601 -0.1104208 -0.3055425 0.9457542 0.6819397 0.2470675 -0.6884155 0.9428184 0.3212738 0.08875155 0.7347757 0.6764118 0.05071365 -0.9173847 -0.3356392 0.2138968 -0.9983191 -0.02777916 0.05086535 -0.8451216 -0.5106884 0.1580089 0 0 -1 0.3522155 -0.9308431 -0.09734117 0.3414678 -0.937843 -0.0620504 0.4412156 -0.8973919 0.004073381 -0.4789807 -0.8696199 -0.1197454 -0.9362642 -0.3406235 -0.08593595 -0.9287825 0.3569741 -0.09966254 -0.6119587 0.7852886 -0.09395974 -0.2846745 0.9578384 -0.03880685 0.4786863 0.8699729 -0.11835 0.4676986 0.8808769 -0.07289779 0.9361346 0.3405553 -0.08760333 0.9272583 -0.3607988 -0.100082 -0.2869058 -0.1047792 -0.9522113 -0.2802206 -0.1019961 -0.9545016 -0.5096638 -0.1923211 -0.8386034 -0.5751661 -0.1934409 -0.7948362 -0.09700405 -0.0352959 -0.9946579 -0.09675514 -0.03521585 -0.9946851 -0.3301393 -0.1309531 -0.9348044 -0.9090322 -0.356257 -0.2161977 -0.664467 -0.2418389 -0.7071051 -0.664464 -0.2418478 -0.7071049 -0.6642641 -0.2423136 -0.7071332 -0.6651606 -0.2438676 -0.7057549 0.6645308 0.241859 -0.7070382 0.6407997 0.2056819 -0.7396423 0.6647304 0.2412157 -0.7070704 0.476179 0.201502 -0.8559502 0.9599823 -0.1563951 0.2323241 0.657177 0.7019695 0.274513 -0.6239396 -0.7232471 0.2959951 -0.666068 -0.2280989 0.7101581 -0.6338521 -0.207871 0.7449974 -0.8305516 0.1291061 0.5417708 -0.9371508 -0.3445351 0.05517178 0.9807192 0.1895537 0.04753202 0.6234604 0.297109 0.7232037 0.3047879 0.6986923 -0.6472508 -0.07942628 0.2176489 -0.9727901 -0.2389417 0.6556568 -0.716255 0.6377273 0.6346725 -0.4364573 0.6414282 0.6180731 -0.4544839 -0.4871575 0.5587753 -0.6711541 0.9034045 0.328243 -0.2758926 -0.8475918 -0.03146535 -0.5297151 0.8910312 -0.06465208 -0.4493145 -0.8757457 -0.3242444 -0.3576802 0.927715 -0.3242636 -0.1849274 0.7684072 -0.5649673 -0.3006035 0.7591167 -0.5546045 -0.3408165 -0.6425819 -0.6120794 -0.46092 0.07808446 -0.2145375 -0.9735895 0.03865981 -0.03889816 0.9984951 -0.4656999 -0.709402 -0.5290297 -0.5644497 -0.3783898 -0.7336332 -0.9161072 0.3889554 -0.09726911 -0.01241904 0.5779576 -0.8159723 -0.9496265 0.2651454 -0.1670551 -0.1813164 -0.9828701 -0.03302991 -0.9364421 -0.3479524 -0.04477989 -0.9373819 -0.34018 -0.07478469 0.9373782 0.3411813 -0.07012617 -0.6929881 -0.2577809 -0.6732879 -0.7525431 -0.2778597 -0.5970536 -0.07618534 -0.3078939 -0.9483655 -0.9118233 0.3523461 -0.2107855 0.3237569 0.7961039 -0.5112729 0.5080116 0.8258579 -0.2447102 0.938991 0.343582 -0.01573121 0.7928482 -0.6093608 -0.008444249 0.9400725 0.3391804 -0.03493487 -0.9374907 -0.3410552 -0.06922757 0.2294296 0.08870488 -0.9692748 0.7441948 0.2364073 -0.6247286 0.486051 0.1338365 -0.8636217 0.7533822 0.2706074 -0.5993221 0.436927 0.2079461 -0.8751304 0.7190534 0.2641889 -0.6427803 0.7222357 0.2751329 -0.6345688 -0.6775525 -0.2475669 -0.6925557 -0.5607162 0.8117446 -0.1633042 0.2185598 -0.6551051 0.7232351 -0.3860858 0.6102347 0.6917741 -0.2124803 0.6538306 0.726194 -0.1724689 0.9406998 -0.2921278 -0.01185989 0.08781683 0.9960661 -0.2384358 -0.08678334 0.967273 -0.2097601 -0.07991647 0.9744815 0.04732501 -0.07483178 0.9960726 -3.74428e-5 -5.95704e-4 0.9999999 -0.2163692 -0.001739859 0.9763101 7.96235e-5 -1.16818e-4 1 0.008786141 0.003197669 0.9999564 -0.5294797 -0.1703876 0.8310351 0.941088 -0.313251 0.1273863 -0.9043917 -0.3307388 0.2696064 -0.9106817 -0.406046 0.07606321 0.3833256 0.1999484 0.9017107 0.2775045 0.9435104 0.1810512 0.9229097 0.3425461 0.1757839 -0.7238254 -0.3023363 0.6202175 -0.4608752 -0.1390214 0.8765085 -0.883593 -0.3441615 0.317516 0.3491763 -0.9313036 0.1036806 0.3197798 -0.8847233 0.3391248 -0.9098203 -0.4019346 0.1033238 -0.9055589 -0.4003933 0.1401727 0.9176746 0.3920798 0.06439596 0.820284 -0.1647642 0.5477105 0.9359492 0.3495509 0.04258304 0.3430679 -0.9390768 0.02096158 0.3422921 -0.9391931 0.02743303 5.60769e-4 -0.001424014 0.9999989 5.58193e-4 -0.001409053 0.9999989 0.3395635 -0.9393252 0.0486316 0.1407181 -0.986591 -0.08268386 0.5266029 -0.8466711 -0.07640331 0.1679988 -0.9730861 0.1577337 -0.3426977 0.9383683 0.04498064 -0.341481 0.9388805 0.04352253 0.4544767 0.668962 0.5881674 0.9433561 0.3290144 0.0427646 0.9611892 0.2659114 0.07353025 0.8829735 0.438205 0.1683281 -0.8997814 -0.4287087 0.08125585 -0.6527528 0.3462649 0.6738059 -0.9344458 -0.3535889 0.04226011 -0.3351921 0.9415212 -0.03441303 3.66438e-4 -0.001114666 0.9999994 -0.3796869 0.9206256 0.09103083 -0.3121886 0.9492394 0.03850913 -0.3517275 0.9346572 0.05199855 0.2675031 -0.9488422 0.1677517 0.3400585 -0.93833 0.0624265 0.3816817 -0.9171601 0.1146146 -0.5263352 0.8462586 -0.0825687 -0.3022836 0.9530735 0.01660341 0.4410794 -0.3842074 0.8110693 0.327023 -0.6541357 0.6820282 0.1035418 0.6074915 0.787549 -0.2181715 -0.1530388 0.9638363 -0.2393593 0.7807491 0.5771811 -0.2592747 0.7548841 0.6024339 -0.08156734 -0.03250652 0.9961377 0.2634544 0.09296357 0.960182 -0.0352391 -0.07344198 0.9966768 -0.2400606 -0.08086311 0.9673842 0.1323068 0.1307254 0.9825507 0.0607475 -0.02407646 0.9978628 0.08093315 0.02851909 0.9963116 -0.9383629 -0.3413704 0.05423468 0.937676 0.3428287 0.05685305 0.3729419 -0.9190356 0.1276249 -0.3006307 0.9512158 0.06935197 -0.3308674 0.9424784 0.04755508 0.01257646 -0.002726316 0.9999172 -0.03279656 -0.005499601 0.9994469 0.3075489 -0.9506881 0.04007488 0.05855089 0.004220366 0.9982755 -0.9363712 -0.336345 0.1004053 -0.9351308 -0.3389605 0.1031316 0.5140681 -0.8557538 0.05847489 0.9166714 0.3951734 0.05959492 -0.4578784 0.8866749 0.06446057 -0.5015714 0.8636544 0.05027115 0.9573901 0.2634953 0.118214 0.1502642 0.09151113 0.9844017 0.03389722 0.00114119 0.9994247 0.760661 0.285113 0.5831856 0.54765 0.1288009 0.8267344 0.07918417 -0.04701548 0.9957507 -0.1063455 0.03741967 0.9936249 -0.01333826 -0.0872991 0.9960929 0.014458 0.4596243 0.8879958 0.3276547 -0.9319668 0.1551784 -0.2186582 0.6870017 0.6929771 -0.1202867 0.3408809 0.9323795 0.2773256 0.4416158 0.8532679 -0.142355 0.5072686 0.8499492 0.6320418 -0.2183892 0.7435249 -0.9114584 -0.370185 0.1794627 -0.8083302 -0.2225673 -0.5450377 -0.9005945 -0.3196921 0.2944937 0.6184626 0.4397839 -0.6512251 -0.525004 -0.009394764 0.8510479 -0.05669361 -0.002684414 0.9983881 0.4162188 -0.01141625 0.9091929 0.9216579 -0.008114516 -0.3879189 -0.07829725 0.005065739 -0.9969173 0.5172622 0.007565319 -0.8557935 0.6110446 0.01180958 -0.7915082 0.9175524 0.004148364 -0.3975933 0.3794513 0.01023781 0.9251552 0.3519432 -0.008104741 0.9359863 0.8892776 -0.007064044 0.4573134 0.5076506 -0.006297588 -0.8615401 0.9983868 0.00334233 0.05668103 0.05671435 -0.002551853 -0.9983872 -0.6888444 0.0076586 -0.7248688 -0.4501196 0.002954363 -0.8929634 0.6289603 0.002581775 -0.7774332 -0.3554345 0.01241403 -0.9346188 -0.8073499 -0.005258262 -0.5900495 -0.9980691 5.6284e-4 -0.06211292 -0.999773 0.003526687 0.02101111 0.438704 -0.003255724 -0.8986259 0.05671191 0.002988576 -0.9983862 -0.9995326 -0.002718091 -0.03044819 -0.3855404 -0.001838684 -0.9226891 -0.9217075 -0.008111834 0.3878008 -0.5134468 0.002079367 0.858119 -0.5068374 -0.007048189 0.8620129 -0.05667316 0.01134121 0.9983285 -0.4223396 0.00489366 0.9064246 -0.05669063 -0.00266093 0.9983882 0.4500867 0.002937018 0.89298 -0.892968 -0.005171954 0.4500905 0.4500821 -0.009596765 0.8929357 0.836277 0.007598161 0.5482546 0.4079236 0.009131789 0.9129705 0.8362745 -0.005625724 0.5482823 -0.5482617 0.01229339 0.8362166 0.7688174 0.02162653 0.6391028 0.9983859 0.003606259 0.05668079 0.9983896 -0.002361774 0.05668097 0.8380501 0.002847313 -0.5455859 0.4115557 -0.009600818 -0.911334 0.05671882 0.003929138 -0.9983825 -0.5350325 0.002523422 -0.8448278 -0.9995458 0.002764046 -0.03001105 0.007121562 0.9986378 -0.0516901 -6.23336e-4 0.9985856 -0.05316454 0.4998945 0.5845258 0.6390893 0.02250897 -0.9993281 0.02892863 0.001782 -0.9999978 0.001170694 -0.00821346 -0.9998624 0.01441556 4.75985e-7 9.9305e-7 1 -8.80138e-7 8.86911e-7 1 0 0 1 -2.0259e-7 0 1 1.37848e-7 0 1 0 0 1 0 0 1 -1.64918e-6 -6.71179e-7 1 -1.0015e-6 3.37759e-6 1 -5.51403e-7 -5.21301e-6 1 7.89824e-7 0 1 8.07071e-7 0 1 2.78089e-5 -5.05832e-5 1 1.42132e-7 0 1 -1.38743e-7 0 1 1.67889e-7 0 1 1.44861e-7 0 1 -0.4764065 0.8505375 -0.2227617 -0.8072776 0.5637029 0.174763 -0.9667489 0.1866139 0.174848 -0.4336287 -0.8649128 -0.2527689 0.089257 -0.9707638 -0.222825 0.8072534 -0.5637126 0.1748434 0.6039828 0.7558901 -0.2526561 -0.7964646 0.5617994 0.2236647 -0.7556669 -0.5490317 0.3571159 -0.4670394 -0.8089299 0.3570808 0.2139275 0.6583915 0.721634 1.65983e-7 0 -1 2.31296e-7 0 -1 8.73549e-7 0 -1 6.95697e-7 0 -1 4.75343e-7 0 -1 2.6662e-7 0 -1 -0.1261391 0.9476296 -0.2934063 -0.2975155 0.9085109 0.2934153 -0.5247961 0.7990541 -0.2934309 -0.8658199 0.04239785 -0.4985563 -0.7873855 -0.4794691 -0.3874708 -0.08788442 -0.9519491 -0.2933757 0.8535495 0.1513317 -0.49855 0.6609521 0.6426684 -0.3874529 0.2975131 0.908518 -0.2933956 -0.6622502 0.6894503 0.2933993 0.08788806 -0.9519441 0.2933909 0.799057 -0.5248177 0.2933849 0.7616875 0.4138617 0.4985485 0.5248143 0.7990416 0.2934325 0.126141 0.9476298 0.2934048 -0.9482041 0.3060119 0.08524 0.7403682 -0.640763 -0.2031697 0.6473224 0.7479361 -0.146852 -0.2077482 0.968321 0.1385464 0.9481766 -0.3061091 0.08519583 0.7414966 0.6701028 -0.03383928 -0.8117859 -0.5837168 -0.01668691 -0.5055542 -0.861672 -0.04400366 -0.103513 -0.9922147 -0.06924641 0.8725675 0.389042 -0.295419 0.1791568 0.982608 -0.0488308 0.2907398 -0.9553115 0.05339002 0.8516365 -0.5235455 0.02481192 0.7890447 0.5509691 0.2717381 0.5938689 0.8041914 0.02441287 -0.2587769 0.77493 -0.5766438 -0.3014597 0.7229316 -0.6216848 -0.7197346 -0.3104619 -0.6209634 -0.6682215 -0.4767795 -0.5711054 -0.8091228 0.1458814 -0.5692445 -0.805068 -0.1814851 -0.5647379 -0.3842286 -0.7040463 -0.5972331 0 -0.7900857 -0.6129963 0.3736934 -0.6765497 -0.6345343 0.5857148 -0.6001631 -0.5447408 0.6287465 -0.4680832 -0.6209475 -0.08665072 -0.8254947 -0.5577189 0.2632306 -0.7868188 -0.5582346 0.5597142 -0.606482 -0.564712 0.6603576 0.3887728 -0.6424823 0.2651507 0.7204052 -0.6408677 0.1603193 0.7507535 -0.6408331 -0.066684 0.8119787 -0.5798653 0.8100199 0.02571964 -0.5858382 0.7562624 0.3368407 -0.560897 0.572347 0.596445 -0.5627365 0.3715178 0.6885653 -0.622778 0.2213783 0.7522193 -0.6206109 0 0 -1 -3.574e-7 0 -1 -2.6368e-4 -2.88402e-4 -1 -1.80784e-4 1.66985e-4 -1 -0.001794338 -0.001553297 -0.9999972 -0.002198159 -7.94107e-4 -0.9999973 -5.19995e-4 -4.34457e-4 -0.9999998 0 0 -1 -2.05047e-6 9.75177e-6 -1 9.05508e-7 4.60246e-7 -1 8.23103e-7 0 -1 6.12433e-7 0 -1 2.55423e-7 0 -1 -4.13478e-5 -4.09993e-5 -1 2.80583e-6 -1.27469e-5 -1 1.86772e-5 3.91656e-6 -1 5.59019e-7 0 -1 -0.02453339 0.02238118 -0.9994484 -1.20013e-5 9.18514e-6 -1 -0.1085277 0.04475206 -0.9930856 0.1086506 -0.05245167 0.9926953 0.07927763 0.2420915 0.9670092 0.2115736 -0.06928378 0.9749034 -0.2452955 0.1196468 0.9620369 2.74075e-7 0 1 -1.25655e-7 0 1 -0.02924108 0.2196744 0.975135 -0.08848416 0.04271584 0.9951612 -0.7511875 0.6600872 -0.001526236 -0.209688 -0.9774768 -0.02388012 0.09830904 -0.9943645 0.03968286 -0.9453703 0.3107125 -0.0986554 -0.950482 -0.3106639 0.008490264 0.9559786 -0.2892287 -0.04951649 0.1498873 0.9861399 -0.07114821 -0.4124213 -0.9087381 -0.06406116 -0.2311599 0.9728565 0.01074057 -0.9983607 -0.003663778 -0.05711936 0.9708073 0.239228 -0.01741981 -0.8123973 0.5827563 -0.02015209 0.9777098 0.2097473 -0.009471774 0.3072606 0.9516024 -0.006630182 -0.734337 0.6786727 0.01235103 0.8124504 -0.5826824 -0.02014267 -0.3070886 0.9513807 -0.02390348 -0.994359 0.09836131 -0.03968882 -0.5823241 0.8119876 0.03968322 0 0 1 6.44687e-7 0 1 0 0 1 1.23934e-7 0 1 0 0 1 -1.87822e-7 0 1 0 0 1 7.79613e-7 0 1 -2.15224e-7 0 1 0 0 1 -0.2883709 0.736812 -0.6115149 -0.7912771 0.5907877 0.1576408 0.9091928 0.2186906 -0.3543203 -0.4670158 -0.8088847 0.3572139 -0.02112776 -0.8160732 0.5775623 0.9779961 0.2078949 -0.01742053 0.2075981 0.576119 0.7905631 0 0 -1 -4.52616e-7 0 -1 -2.21436e-7 0 -1 6.44019e-7 0 -1 3.49576e-7 0 -1 -0.7188313 0.690468 0.0808435 -0.9476315 -0.1261289 -0.2934046 -0.7990681 -0.5248078 -0.293372 -0.08787977 -0.951949 -0.2933773 0.5729647 0.6504897 -0.4985727 -0.9085116 -0.2975301 0.2933981 -0.3338384 -0.8958039 0.2934066 0.08788347 -0.9519441 0.2933925 0.8490992 -0.5170358 -0.1081885 0.9254131 0.04532629 0.3762396 -0.7403758 0.6407462 -0.2031947 0.2078156 -0.9683101 0.1385225 0.9481776 -0.3061045 0.08520305 3.93738e-7 0 -1 -0.09958392 0.9948893 -0.0166862 -0.3835372 0.9234568 0.01125699 -0.7451978 0.6665323 -0.0203728 -0.8175731 0.5456318 -0.1840114 -0.9364711 0.1906587 -0.2943999 -0.8133977 -0.5470204 -0.197871 0.008563399 -0.9993485 -0.03506368 0.3158674 -0.9444848 -0.09042328 0.8768636 -0.4802096 -0.02256298 0.9594967 -0.2398084 0.1478441 0.9833819 0.03413587 -0.1783115 0.8743126 0.3949669 -0.2820972 -0.8716756 0.4078339 0.2717597 -0.8814948 -0.3728241 0.2897743 -0.6717203 -0.7184441 0.1806374 -0.4269874 -0.9041611 0.01320981 0.9725385 -0.2258672 0.05615186 -0.3873859 0.7240282 -0.5707149 -0.5903339 0.5132082 -0.6229954 -0.7829108 0.04557436 -0.6204626 -0.7909873 -0.1394416 -0.5957309 -0.719748 -0.3104738 -0.6209419 -0.6772363 -0.4531561 -0.5796556 -0.5290617 0.6201613 -0.5792182 -0.1848135 -0.7797485 -0.5981943 0.3205484 -0.7138512 -0.6226277 0.5163104 -0.6152785 -0.5956979 0.6461774 -0.4810687 -0.592476 -0.06851136 -0.8188624 -0.5698866 0.7196661 -0.3104348 -0.6210564 0.7918225 -0.201317 -0.5766183 0.7914915 -0.1986096 -0.57801 0.6653251 0.3914271 -0.6357101 0.4295739 0.6413121 -0.6357556 -0.07875823 0.8170897 -0.5711056 0.7576497 0.3380037 -0.5583195 0.5699592 0.5940222 -0.5677008 0.3846944 0.7149953 -0.5837739 7.00882e-6 7.60533e-4 -0.9999998 0 0 -1 -4.40868e-5 3.2532e-6 -1 2.09307e-7 0 -1 -8.05383e-6 8.06534e-6 -1 7.65067e-5 -2.44887e-4 -1 7.17665e-7 0 -1 0 0 -1 -4.20835e-4 -8.68042e-4 -0.9999996 -3.34114e-4 -2.99126e-4 -1 5.09306e-7 0 -1 2.92872e-6 -3.13174e-6 -1 4.37573e-6 1.00912e-5 -1 6.08689e-7 0 -1 1.52064e-6 -8.68449e-7 -1 2.61917e-6 -3.16266e-7 -1 0.002296507 -5.92275e-4 -0.9999972 3.88525e-5 1.73633e-5 -1 -0.09487777 0.03729557 0.9947901 -0.1326057 0.2412165 0.961369 2.32668e-7 0 1 1.63175e-7 0 1 6.91647e-7 0 1 0.7416574 -0.670353 -0.02389985 0.9431824 -0.3271953 0.05788272 0.9508761 0.3070972 -0.03906559 -0.976803 -0.209532 -0.04418385 -0.2205983 -0.9752866 0.0123527 -0.3070276 0.9514006 -0.0238977 -0.6702519 -0.7415441 -0.02957797 -0.5823733 0.8119517 0.0396983 -0.9773256 -0.2096675 0.02957111 -0.7343738 -0.6786328 -0.01235276 0.9949432 0.09840029 0.02014005 -0.8124128 -0.5827346 0.02015072 0.9103443 -0.4119445 0.03968805 0.855823 0.514885 -0.04960262 -0.9415319 -0.3364931 -0.01703524 -0.2826815 -0.9591395 0.0119394 -0.9777011 -0.2097363 0.01054275 -0.2205164 -0.9753699 -0.005108296 0 0 1 -1.47992e-7 0 1 -3.18886e-7 0 1 2.5025e-7 2.37376e-6 1 -6.44893e-7 -2.77918e-7 1 0 0 1 2.34293e-7 0 1 2.1196e-7 0 1 1.02193e-6 4.05185e-5 1 0 5.61011e-7 1 1.61359e-4 5.52759e-5 1 -0.3725059 0.6740956 0.6378358 -0.9072903 -0.3898762 0.1575467 -0.2866377 -0.9419785 0.1746867 0.1208639 -0.9738177 -0.1925387 0.4683172 -0.7109401 -0.5246363 0.7127348 -0.2948696 -0.6364442 0.4762218 0.8617824 0.1747685 0.006723582 0.9205932 0.390465 -0.5858504 -0.1966627 0.7861954 -0.6250007 -0.6941319 0.3571487 0.9779991 0.2078826 -0.01739984 0.4670051 0.8088751 0.3572499 0 0 -1 -8.25508e-7 0 -1 6.27756e-7 0 -1 8.02427e-7 0 -1 3.31698e-7 0 -1 3.15128e-7 0 -1 -0.8544559 0.5132054 0.08078044 -0.7732166 -0.5172128 -0.3669157 -0.2629289 -0.8263444 -0.4980195 0.2895202 -0.8662379 -0.4071977 0.6894447 -0.6622459 -0.2934221 -0.9532749 -0.046669 0.298478 -0.8544539 -0.5132054 -0.08080023 -0.08950346 -0.90894 0.4072067 0.7990624 -0.5248016 0.2933984 0.121682 0.9142183 0.3865211 -0.7424752 0.642584 -0.1892523 -0.9303929 0.3554229 0.08968669 0.7424053 -0.6424943 -0.1898302 -0.2568865 0.963532 0.0749368 -0.6847988 -0.7274479 -0.0432468 -0.06921994 0.9867204 0.1469406 -0.9951333 0.08799266 -0.04435032 -0.8117924 -0.5837071 -0.01670706 -0.1035273 -0.9922108 -0.06928288 0.9942313 0.1049745 -0.02201396 0.6600433 0.7457725 -0.09036791 0.3016921 0.9513822 -0.06207954 -0.8184256 -0.5714818 0.05990135 -0.1230837 -0.9917284 0.03640365 0.2906861 -0.9553302 0.05334734 0.9423873 -0.3336591 0.02404004 0.9204056 0.3892647 0.03642344 0.681976 0.7294249 0.05336809 0.3259516 0.9426851 0.07141733 -0.09260344 0.7922722 -0.6031 -0.2487003 0.7653725 -0.5935936 -0.5483437 0.6040353 -0.5783258 -0.7513071 0.2586561 -0.6071529 -0.7829147 0.0455873 -0.6204566 -0.7197482 -0.3104375 -0.6209598 -0.668235 -0.4767743 -0.571094 -0.8091357 0.1458801 -0.5692262 -0.3842542 -0.70403 -0.5972357 0 -0.7900874 -0.6129943 0.5162811 -0.615288 -0.5957136 -0.4166697 -0.7079967 -0.5701991 0.2631958 -0.7868415 -0.5582192 0.5429229 -0.6101315 -0.5770393 0.791239 -0.1395181 -0.5953786 0.7763989 0.0790925 -0.6252594 0.1277331 0.7667137 -0.6291536 -8.02075e-5 6.87919e-4 -0.9999998 2.89373e-7 0 -1 0 0 -1 1.46813e-7 0 -1 0.003795087 -0.002556681 -0.9999896 0.002082586 4.46941e-4 -0.9999977 9.7891e-4 4.82348e-4 -0.9999995 -2.63318e-4 -2.88654e-4 -1 7.64986e-5 -2.45091e-4 -1 1.03969e-4 -8.9239e-4 -0.9999997 0.01702111 -0.0645886 -0.9977668 -0.1542815 -0.1987756 -0.9678252 0.001849591 -0.001758217 -0.9999968 -3.34091e-4 -2.99345e-4 -1 -0.00295943 0.001993715 -0.9999937 -0.003555834 -0.002913713 -0.9999895 0.150622 0.1739591 -0.9731656 -0.0159657 0.05622243 -0.9982906 -0.08041805 -0.01275241 -0.9966797 0.0249201 -0.1051428 -0.9941449 -0.01360803 -0.09287941 -0.9955844 -0.01000815 0.04076576 -0.9991187 0.09399294 0.06204897 -0.9936375 -0.08117127 0.08350104 -0.9931963 -0.1107244 0.02561146 -0.9935212 0.00220102 -5.09326e-4 -0.9999975 0.1611467 -0.1547892 0.9747164 -0.1184097 0.1802915 0.97646 -0.2607929 0.05916672 0.96358 -0.2453153 0.1196509 0.9620312 1.32952e-7 0 1 0.0584802 -0.1487526 0.9871438 0.2739404 -0.004699885 0.9617352 0.2535526 -0.0651201 0.9651272 0.3945031 -0.9176361 -0.04807657 0.8629691 -0.5042677 0.03159934 -0.4333481 0.9008823 -0.02491009 0.7091832 0.7049833 0.007603883 -0.4780371 0.8783097 -0.007261455 0.20977 0.977694 -0.01053887 -0.7316749 0.6816517 -0.001716792 -0.9105337 -0.409161 -0.05929225 0.9777018 0.2097842 -0.009480297 0.3071196 0.9516125 0.01054346 -0.7043056 -0.7098768 0.005345284 -0.8124598 0.5826694 -0.02013981 0.2967025 -0.9548901 0.0123521 0.3071135 0.9516499 -0.006621479 -0.8124883 -0.5826295 0.02014219 0.8124505 -0.5826818 -0.0201503 -0.9943669 0.09828573 -0.03968089 0.7559273 0.6542645 0.02262604 0.06125593 -0.2724395 -0.9602211 -0.1604351 0.7597686 -0.6300893 0.7899839 -0.1351118 -0.5980554 -0.3047938 -0.6007121 -0.7390844 0.2752333 -0.3261709 0.9043558 -0.4404983 0.0390644 0.8969032 0.9998477 -3.03472e-4 -0.01745188 0.9998477 -3.04963e-4 -0.01745188 -0.01745259 -0.01744824 -0.9996955 -0.01745241 -0.01744824 -0.9996954 0.01745319 0.01745063 0.9996954 0.01745319 0.01744967 0.9996955 0.9998477 -3.04275e-4 -0.01745331 0.9998477 -3.03903e-4 -0.01745331 -0.01745617 -0.01744836 -0.9996954 -0.01745247 -0.01744985 -0.9996954 1.46905e-6 -0.9998477 0.01745265 2.03809e-6 -0.9998477 0.017452 -1.83623e-7 -0.9998478 0.01745223 9.15513e-7 -0.9998478 0.01745104 0.9998477 -3.04489e-4 -0.01744949 0.9855284 -0.09388273 0.1411377 0.9998477 -3.07219e-4 -0.01745045 0.9998486 9.57435e-5 -0.01740407 0.9998447 -5.97823e-4 -0.01761662 0.9998527 1.96572e-4 -0.01717036 0.9997778 -2.41301e-4 -0.02108091 0.9998478 -3.0095e-4 -0.01745098 0.999846 -3.07309e-4 -0.01755183 0.9998477 -3.04299e-4 -0.01744991 -0.01745307 -0.01744937 -0.9996954 -0.9998478 3.04268e-4 0.01744866 -0.9279648 0.04589724 0.3698309 -0.9972825 0.03131186 -0.06668728 -0.8305453 0.02522736 -0.5563797 -0.435086 0.02200382 -0.9001201 0.6740599 -0.0128901 -0.7385643 0.8129443 -0.01016283 -0.5822529 0.9904525 -0.002406537 -0.137834 0.4278535 -0.005078077 0.9038339 -0.2221854 -0.01971989 0.974805 -0.8322781 0.02493399 -0.5537975 0.4488901 -0.05227988 -0.8920563 0.8129442 -0.01016283 -0.5822529 0.9410679 0.005903065 0.3381661 0.6760867 0.01286125 0.7367098 0.2562205 0.01687109 0.9664711 -0.6009625 -0.02036464 -0.7990177 -0.9084008 -0.004519701 -0.4180762 -0.9233506 -0.007918357 -0.3838762 -0.9482912 0.01124566 0.3172027 -0.7289413 0.02025681 0.6842765 -0.1898841 0.03769814 0.9810826 0.7053463 0.008589386 0.7088109 0.9231271 0.005588352 0.3844546 0.9999967 0.002333164 -0.00115782 0.9244219 -3.73964e-4 -0.3813713 0.6347825 0.02082413 -0.7724103 0.2750976 0.02061134 -0.9611954 -0.2561306 0.009627699 -0.9665943 -0.8931323 -0.00908184 0.4497024 -0.6096448 -0.004677176 0.792661 -0.2054244 0.03935688 0.9778814 0.6370342 0.01860857 0.7706109 0.893248 -0.01206368 -0.4494022 -0.1446038 -0.9463603 -0.2889499 -0.2460598 -0.9171598 -0.3134843 -0.1959815 -0.9606441 -0.1968611 -0.6656576 -0.7109348 -0.226874 9.16821e-6 -0.9998478 0.01744645 -0.4600356 -0.8270149 0.3231308 0.09035116 -0.8886967 0.4495054 0.270829 -0.9625413 0.0128827 0.1968827 -0.9756466 -0.09670042 8.73262e-5 -0.9998423 0.01776438 1.10808e-4 -0.9998423 0.01776176 4.21108e-4 -0.9998401 0.01788127 1.53037e-4 -0.9998465 0.01752483 4.67997e-6 -0.9998477 0.01745533 7.23081e-4 -0.9999015 0.01401776 -1.41733e-5 -0.9998475 0.01747173 0.5159812 -0.8535929 -0.0717132 -8.49517e-4 -0.9999015 0.01401233 1.30253e-4 -0.9998469 0.01750397 9.7808e-5 -0.9998453 0.0175898 1.19758e-4 -0.9998474 0.0174784 -8.29001e-6 0.9998477 -0.01746141 -0.8282172 -0.1353036 -0.5438284 -0.3870427 -0.1400561 0.911363 0.05502766 0.3808754 0.9229875 0.763263 0.5531265 0.3338876 0.3623399 0.7441285 -0.5612332 -5.02481e-7 -0.9998478 0.01745063 8.39909e-6 -0.9998477 0.01745283 3.98841e-6 -0.9998477 0.01745271 -6.53506e-6 -0.9998477 0.01745229 -7.72784e-5 -0.9998478 0.01745456 0 -0.9998478 0.01745271 0.01745229 0.01744979 0.9996954 -8.63955e-7 0.9998478 -0.01745241 -7.39416e-7 0.9998478 -0.01745235 -0.09221744 -0.01737809 -0.9955873 -3.36054e-7 -0.9998477 0.01745295 0.01743274 0.01744979 0.9996958 -1.25135e-6 0.9998478 -0.01744747 -4.56994e-6 0.9998477 -0.01745223 -9.90574e-7 0.9998477 -0.01745522 2.89411e-7 0.9998477 -0.01745212 -4.32665e-6 0.9998478 -0.01745289 -9.4872e-7 0.9998478 -0.01745259 -1.19162e-6 0.9998477 -0.01745229 -0.01745212 -0.01744991 -0.9996955 -0.01745092 -0.01744955 -0.9996954 -0.9982709 0.00300312 0.05870527 -0.9984716 0.02869123 0.04723763 -0.9998389 -0.003923833 0.01752233 -0.9960225 0.03903299 0.08009946 -0.9998478 3.04033e-4 0.01745045 -0.9992735 0.03688907 -0.009582281 -0.9990732 -7.51109e-4 -0.04304111 -0.9998477 3.02301e-4 0.01744967 -0.9997889 -0.001638531 0.02048105 0.2225369 0.9749243 0 -3.72681e-6 0 1 -5.15754e-6 0 1 2.8438e-6 0 1 0.2225294 -0.974926 0 -0.2225073 -0.9749311 0 5.43963e-6 3.45214e-6 1 4.18666e-6 1.39656e-6 1 -0.6235365 -0.7817944 0 -1.56512e-6 1.7568e-6 1 -0.4033931 -0.9117683 -0.07715505 -0.4607969 -0.8291631 0.3164724 -3.03409e-6 2.5394e-6 1 0.153959 -0.8873456 0.4346429 0.03489404 -0.9933259 -0.1099368 -3.13329e-5 -3.60484e-6 -1 5.16778e-6 1.30758e-5 -1 2.82986e-5 -3.13369e-5 -1 -2.85293e-5 1.91963e-5 -1 -0.8508066 -0.5212122 -0.06682902 -0.9465049 -0.317723 0.05639725 -0.9937967 -0.1000533 -0.04855573 -0.989247 -0.1462553 0 -0.9984911 -0.05412614 -0.009272634 0.3006862 -0.9537232 0 -0.9966801 -0.08133065 -0.003760635 0.2100649 -0.8173528 0.5364767 0.2562537 -0.795502 0.5490999 -0.2312986 0.9727312 -0.01717787 0.845946 0.5332656 -0.00181353 0.3428606 -0.7763062 0.528957 0.8344394 0.5510928 -0.002777755 0.8440103 0.5363271 1.46041e-4 0.3097882 -0.9507845 0.006346225 -0.1185353 0.823318 -0.555065 -0.06495285 0.8579342 -0.5096371 -0.4381901 0.8987828 0.01337635 0.8344441 0.5510926 -1.17798e-4 1.74612e-7 0 1 0.8343921 0.5511714 0 1.67197e-4 8.40173e-5 1 -1.48515e-7 0 1 -6.11781e-5 4.65502e-5 1 -8.54835e-5 -1.17969e-4 1 3.27343e-6 6.09114e-5 1 -0.0459184 -0.9986318 -0.02501922 0.7957675 -0.6050851 -0.0250222 0.04591232 -0.9986322 0.02501696 0.8479396 -0.5295023 0.02501696 -1.16379e-4 7.26791e-5 -1 2.46453e-4 4.27894e-4 -0.9999999 -5.34148e-5 0.001163184 -0.9999994 1.95535e-4 4.55283e-4 -1 0.66378 -0.7462134 -0.05061262 -4.49537e-4 -2.21807e-4 -1 -0.3053135 -0.9473968 0.09603762 2.2554e-4 0.0010311 -0.9999995 -0.9258513 0.3570531 -0.1237441 -0.9435458 0.312962 -0.1085181 2.28729e-4 0.0014894 -0.9999989 -0.02086257 0.004175126 -0.9997736 -0.7501829 0.6591172 0.05282276 -0.5215808 0.8531323 -0.01090395 -0.5736846 0.8163605 -0.0666446 -0.02705568 0.01711463 -0.9994875 0.6889203 0.5032998 -0.5216113 0.7022396 0.4961521 -0.5105807 0.8680731 -0.4963606 -0.008688271 0.8784385 -0.4778532 0.001470863 0.8450498 -0.5345503 0.01211845 -0.6370444 -0.7708272 0 0.863238 -0.5047973 0 -0.5352609 -0.6416366 0.5493618 -0.4978882 -0.681203 0.5367214 0.8943754 -0.4472932 -0.004645824 -0.606229 -0.5940915 0.5287172 -0.7096354 -0.7045692 0 -0.710267 -0.7039313 0.001313805 -0.5957297 -0.8031851 0 -0.594518 -0.8040797 0.002066373 -0.6691147 -0.7431441 -0.004749238 -0.5000082 -0.866011 -0.004111528 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.3090196 -0.9510509 -0.003031909 -0.2823711 -0.9593043 0.001396894 -0.1045327 -0.9945203 -0.001562476 -1.20364e-4 1.44242e-5 1 -2.7149e-5 -2.78878e-4 1 -2.76838e-7 0 1 -0.09728449 -0.9952567 -2.67028e-4 0.09127163 -0.995826 2.63994e-4 3.29449e-5 -3.58659e-4 1 -0.9969447 -0.07811141 0 0.2553581 -0.9668465 0 0.1045332 -0.9945194 -0.002031445 0.2544749 -0.9670786 0.001317441 0 0 -1 0 0 -1 0.3090284 -0.9510409 -0.004749894 0.5000082 -0.8660109 -0.004112899 0.3991002 -0.9169051 0.002065539 0.6691237 -0.7431449 -0.003040194 0.5414068 -0.8407565 0.002667605 0.6896085 -0.7241811 0.001395583 0.8090094 -0.5877937 -0.001568019 0.813282 -0.5818698 -2.67024e-4 0.9080392 -0.4188854 2.63237e-4 1.2334e-7 0 -1 0.9135429 -0.4067372 -0.002037107 -0.4294908 -0.9030713 0 3.5359e-4 -1.62816e-4 1 0.9649931 -0.2622754 0 0.9647589 -0.2631322 0.00131303 0.8388808 -0.09056401 0.5367282 0.8232991 -0.1427216 0.5493716 0.8176136 -0.2279585 0.5287184 0.9936125 -0.1128268 0.002061843 0.9934442 -0.114319 0 0.97814 -0.2078932 -0.004751324 -0.3976825 -0.9175173 0.003294765 -0.392927 -0.9195694 6.23367e-4 0.977661 -0.2099168 0.01067906 0.9936479 -0.1076854 -0.03267681 0.9860615 -0.1662966 0.00533241 -0.4280896 -0.9037342 -0.002001941 0 -2.95063e-6 1 4.89942e-7 0 1 0.9961661 0.06925767 0.05344563 0.926627 -0.3028775 0.2227726 -2.1411e-6 0 1 0.9923477 0.09716892 -0.07618677 0.8428012 0.5268679 -0.1099848 -1.05391e-6 -4.35962e-6 1 0.7526904 0.5823286 0.3071655 -1.32709e-6 -7.87229e-7 1 -9.21631e-6 2.35708e-5 -1 0.6231149 -0.7821303 0 0.6756223 0.737248 0 0.6809126 0.7323492 -0.004769146 0.6155153 -0.7880557 -0.01044398 0.5675559 -0.8233213 -0.004736959 0.5956234 -0.8032624 0.001529276 0.6027951 0.5906228 0.5364727 0.5608087 0.6196686 0.5490943 0.7096078 0.7045969 0 0.5675634 -0.8233297 0 0.7102508 0.7039476 0.001312017 0.5689996 -0.8223341 0.002512574 0.8167939 0.5769296 2.59438e-4 0.8090161 0.587783 -0.002039432 0.6691146 0.7431442 -0.004749238 0.5000106 0.8660095 -0.004112899 0.59456 0.8040487 0.002065241 0.4573773 0.8892688 0.002673625 -0.8945296 0.4470087 0 0.595768 0.8031566 0 -0.8902192 0.4555215 0.00320518 -0.892709 0.4505967 -0.005770504 0.5009071 0.6850497 0.5289604 0.08864629 -0.1909675 -0.9775854 -0.8458525 0.5332726 0.01240789 -0.5716339 -0.6127068 -0.5457336 -0.4856556 -0.8068842 -0.3362685 -0.8669799 0.498281 -0.007866263 -8.21684e-6 2.71202e-5 -1 -0.8632404 0.5047921 -0.001038551 -0.6571586 0.7524257 -0.04470294 -3.0686e-5 1.62776e-5 -1 -0.04792433 0.9862701 0.1580331 -0.0640425 0.9948233 0.0788992 0.4124018 0.904358 0.1098239 0.4116137 0.9042855 0.1133223 7.99503e-5 -3.39496e-6 -1 1.67112e-5 5.28837e-5 -1 0.9895294 0.1443287 -9.82816e-4 -0.2332164 0.9722833 0.0165928 0.9942585 0.08982414 -0.05815178 0.9993808 0.03386861 -0.009540438 -0.349049 0.9371045 0 -0.3531069 0.9355787 -0.002872228 -0.2880451 0.7843592 0.5493732 0.9967008 0.08113896 -0.00202465 -0.2114034 0.8220491 0.5287193 -0.3977194 0.9175072 0 -0.3409883 0.7717851 0.5367261 -0.2553741 0.9668424 0 -0.3090162 0.9510449 -0.004748523 -0.2544937 0.9670736 0.001315712 -0.3990932 0.9169081 0.002070307 -0.5000059 0.8660123 -0.004107415 -0.5414096 0.8407548 0.00267136 2.81335e-7 0 1 -1.91827e-4 -1.11933e-4 1 -0.834632 -0.5508033 0.00227946 0.4082164 -0.9116883 0.0467329 -0.8345533 -0.5509077 -0.004652559 0.09208953 -0.8487748 -0.5206735 0.08477842 -0.8533828 -0.5143448 -0.842036 -0.539417 -0.002233505 -0.8878155 -0.4599624 -0.01478099 -0.8396015 -0.5432031 0 0.02284717 0.01156872 -0.9996721 -0.9085243 -0.4169276 0.02748215 -0.99399 -0.1052131 0.0302338 -0.001686811 -0.001765727 -0.9999971 0.004186213 0.0113359 -0.9999271 0.8521214 0.5189856 -0.06740367 0.3052175 0.9474281 0.09603309 -5.1315e-4 -0.001103401 -0.9999994 -0.001373648 -0.002023756 -0.9999971 0.9452117 0.3219879 0.05383986 -0.1836392 0.9787396 0.09135383 0.2824146 0.954674 -0.09401899 0.8696494 0.4871258 0.08011573 0.001528739 -0.002227962 -0.9999964 -0.001370251 -7.67673e-4 -0.9999988 3.20387e-4 0.001146972 -0.9999993 3.49085e-4 -7.49736e-4 -0.9999998 0.001442849 -8.68364e-4 -0.9999986 0.9263849 -0.3572303 -0.1191539 0.9980566 -0.03226512 0.05331051 0.6697048 -0.741936 0.03203999 2.92391e-6 -1.91986e-5 -1 0.1386833 0.9877981 -0.07086521 0.3030584 0.9525467 0.02846693 -1.0778e-5 1.2431e-5 -1 -1.76629e-4 -5.30182e-4 -0.9999999 2.96792e-4 -8.94183e-4 -0.9999996 0.001757383 0.002095758 -0.9999963 0.04583758 0.9989467 0.002118766 -0.06246912 0.9978735 0.0186066 -0.03005355 0.9995462 0.002077877 -0.8499032 0.1470152 -0.5060151 -0.06148672 0.9980916 -0.005711257 -3.00057e-4 -5.8312e-4 0.9999999 -0.8571239 0.2899956 -0.4257243 0.002057075 9.98806e-5 0.999998 -0.06735831 0.9977289 0 0.001487553 3.60111e-4 0.9999989 -2.64359e-4 5.69157e-4 0.9999999 1.30792e-7 0 1 -5.53651e-7 0 1 0.9719626 0.2351312 0.001399993 0.9135427 0.40674 -0.001561105 0.9105652 0.4133656 -2.73093e-4 0.9781461 0.2078964 -0.003036081 0.9988185 0.04852533 0.00266993 0.9999915 0 -0.004113912 0.2576388 -0.954599 0.1495429 4.36199e-4 -7.36092e-4 -0.9999997 -0.3255527 -0.9449549 -0.03279697 7.71144e-6 -1.93622e-6 -1 0.8672938 -0.4615117 -0.1865702 -1.16589e-4 -7.03074e-5 -1 -0.3081204 -0.9512552 -0.01323896 8.82415e-6 -7.57697e-7 -1 0.5392104 -0.8147895 -0.213003 0.8331334 -0.5199984 -0.1883895 0.676378 -0.6061058 0.4185076 0.9274776 0.3662586 0.07510101 0.8878155 0.4599624 -0.01477628 -0.00220263 6.72014e-4 -0.9999974 0.9500073 0.3112236 -0.02502089 -2.25145e-5 -7.71959e-5 1 1.37461e-4 -1.0324e-5 1 0.1045076 0.9945229 -0.001565217 0.09729051 0.995256 -2.73082e-4 2.90996e-5 2.95635e-4 1 4.27076e-7 0 1 0.2823756 0.9593029 0.00140357 -0.09127163 0.995826 2.5489e-4 -3.42679e-5 3.71085e-4 1 -3.93257e-7 0 -1 0.3090261 0.9510487 -0.00303477 2.18584e-7 0 -1 -0.1045076 0.9945221 -0.002033174 -0.6638084 0.7461881 -0.05061495 -0.8590387 0.4571464 -0.2303689 -0.04721546 0.9950942 0.08693742 0.00115174 0.00100106 -0.9999989 -0.6827149 0.7179073 -0.1360499 -0.9684764 0.2375109 0.07511413 5.73028e-4 2.29501e-4 -0.9999998 1.78384e-4 5.32672e-4 -1 0.3255711 0.9449486 -0.03279703 -0.001756548 -0.002096712 -0.9999963 0.3068791 0.951675 -0.01183462 0.8192223 -0.1418694 -0.5556511 0.4049403 0.9143354 0.00380057 0.4010131 0.9160707 0.001725375 0.8493827 -0.3045409 -0.43105 0.9934507 -0.09439802 0.06437891 0.02505493 -0.9996814 0.003051936 0.06006336 -0.9981908 -0.002765715 0.06005567 -0.9981911 0.00282526 -0.8437278 0.09128344 0.5289527 -0.993437 0.1143808 0 0.05817294 -0.9983066 0 -0.9647619 0.2631216 0.001313149 -0.9781392 0.2078974 -0.004748463 -0.9936053 0.1128901 0.002065479 -0.81704 0.1758603 0.5491073 -0.8128754 0.2267376 0.5364921 -0.9649959 0.2622652 0 -3.74448e-4 1.72828e-4 1 0.4295908 0.9030238 0 -0.9135399 0.4067442 -0.00203824 -0.9080346 0.4188954 2.59443e-4 -2.66187e-4 1.90785e-4 1 -0.813282 0.5818699 -2.71576e-4 -0.809022 0.5877764 -0.001565217 -0.669121 0.7431473 -0.00303471 -0.6895964 0.7241926 0.001398026 0.4272406 0.904132 -0.003302931 0 0 -1 -0.9999915 0 -0.004114449 -0.9988184 -0.048527 0.002670228 -0.9781459 -0.2078974 -0.003035426 -0.9719673 -0.2351118 0.001398146 -6.64435e-5 1.39866e-4 1 -3.03585e-4 -1.3761e-4 1 -0.9105525 -0.4133936 -2.68548e-4 -0.8167777 -0.5769526 2.65503e-4 -3.41121e-4 -2.40946e-4 1 -7.20813e-6 -2.40244e-4 1 -0.9945411 0.1022285 0.02091515 0.0499649 -0.9986079 0.01690739 -0.9552972 0.2911958 -0.05111038 -0.9762799 0.2165128 -5.72553e-5 7.83809e-6 4.05062e-6 1 7.59065e-6 -3.37701e-6 1 -0.9359811 -0.08461838 0.3417296 4.25979e-6 -9.45873e-6 1 7.66768e-6 0 1 -0.9670019 -0.07028979 0.2448815 -0.8790968 0.4662558 0.09896707 -0.8260898 0.4813622 0.2930291 -1.00634e-5 -2.41657e-5 -1 1.09623e-5 -8.30211e-6 -1 -0.5812968 0.7952041 -0.1724668 2.2814e-5 1.66608e-5 -1 -6.86709e-7 0 1 -1.89106e-6 7.3022e-6 1 -0.8274699 -0.5201177 0.2115925 -0.9009729 0.4338753 0 -0.9009615 0.4338991 0 -0.6234953 0.7818271 0 6.71501e-6 0 1 -0.6235291 -0.7818003 0 1.93426e-6 0 1 -0.9009594 -0.4339033 0 -0.9009708 -0.4338797 0 1.34267e-6 -1.43509e-6 1 -0.2225181 0.9749286 0 1.18544e-6 -4.28886e-6 1 -2.19598e-6 -4.91848e-6 1 0 -6.70195e-7 1 0.2225401 0.9749236 0 5.95068e-6 -2.24426e-6 1 -0.4636942 0.8501543 0.24945 -4.12621e-6 -3.24322e-5 -1 -1.6537e-5 1.02863e-5 -1 -0.8301819 -0.53464 0.1579819 -1.82424e-5 -7.44293e-7 -1 -0.7254002 -0.6881273 0.01659065 -0.6231153 0.7821297 -9.20025e-4 -0.04582607 -0.9989472 0.002102375 -0.1385239 -0.9878128 -0.07097303 1.26746e-4 1.16229e-4 1 -0.3194378 -0.9468166 0.03870147 7.14881e-5 3.50955e-5 1 -0.8907775 -0.4369983 -0.1246922 0.9968294 0.07956916 0 -2.88764e-7 0 -1 -6.20637e-6 -1.67979e-7 1 0.5450254 0.8382341 0.01764059 -0.6722871 -0.7375443 0.06370705 -9.40769e-6 0 1 0.6234939 -0.7818282 0 0.6234937 -0.7818285 0 4.6581e-6 0 1 -1.68613e-6 3.06402e-6 1 0.2225264 -0.9749268 0 -1.36347e-6 0 1 2.41149e-6 4.84457e-6 1 0 -3.24346e-6 1 0 0 -1 2.52069e-4 -1.80282e-4 1 2.03293e-4 -1.4026e-4 1 0.585469 0.8093499 0.046678 0.8936403 -0.4487841 0 0.8943243 -0.4474134 0.002278506 -0.4573991 -0.8892576 0.002673327 -0.8090113 -0.5877896 -0.002035796 -0.5673397 0.823484 0 -0.5686187 0.8225988 -0.002004444 -0.6337206 -0.7735568 -0.002854704 -0.7336342 -0.679258 0.01973664 0.6571363 -0.7524453 -0.04469865 0.006997585 -0.008831262 -0.9999366 -0.02575427 -0.01109814 -0.9996067 0.3977181 -0.9175077 0 0.2225212 0.9749279 0 0.6234886 0.7818325 0 -3.72645e-6 0 1 0.6234815 0.7818382 0 1.55104e-6 0 1 3.72675e-6 0 1 0.222518 -0.9749286 0 -0.2225339 -0.974925 0 -0.2225369 -0.9749243 0 -0.6234529 -0.7818611 0 -1.28938e-6 0 1 -0.9009992 -0.4338207 0 -0.9009879 -0.4338443 0 -0.6234461 0.7818665 0 9.40929e-6 0 1 -0.9010161 0.4337858 0 -0.9010047 0.4338096 0 7.24492e-6 -3.37635e-6 1 0 -1.43524e-6 1 8.21524e-6 4.05109e-6 1 -0.9360362 -0.0845924 0.3415851 -0.9945489 0.102151 0.0209245 -0.9552892 0.2912204 -0.05112022 -0.8790971 0.4662538 0.09897375 -0.9669637 -0.07031387 0.2450248 7.66786e-6 0 1 3.95562e-6 -9.45897e-6 1 -0.82611 0.4813536 0.2929863 6.86716e-7 0 1 -1.89104e-6 7.30199e-6 1 -0.8274756 -0.5200935 0.2116292 -0.7253773 -0.6881517 0.01658499 -0.8301797 -0.5346235 0.1580489 2.71976e-6 3.4524e-6 1 4.18658e-6 1.39668e-6 1 -0.4607826 -0.8291965 0.316406 -0.6336741 -0.7735949 -0.002860486 -0.5736913 0.8163558 -0.06664562 -0.6231201 0.7821256 -9.07638e-4 -0.5216122 0.853113 -0.01090228 -0.6370169 -0.7708499 0 -0.535236 -0.6416542 0.5493655 -0.5686011 0.8226109 -0.002022087 -0.606211 -0.5941097 0.5287175 -0.7096181 -0.7045866 0 -0.5957623 -0.8031609 0 -0.5945491 -0.8040568 0.002063155 -0.7102667 -0.7039315 0.001310229 -0.4979203 -0.6811695 0.5367343 -0.6691138 -0.7431448 -0.004751741 -0.5000059 -0.8660123 -0.004111528 0 0 -1 0 0 -1 0 0 -1 0.09127104 -0.9958261 2.57923e-4 0.1045435 -0.9945183 -0.002039313 -0.1045424 -0.9945192 -0.001570701 -0.09728723 -0.9952563 -2.73089e-4 3.52175e-7 0 -1 -1.73256e-7 0 -1 0.3089784 -0.9510573 -0.004747271 0.2544837 -0.9670763 0.001306891 0.2100645 -0.8173506 0.5364801 0.2553526 -0.9668481 0 0.3990247 -0.9169379 0.002070188 0.397649 -0.9175377 0 0.2562292 -0.7955063 0.5491051 0.342787 -0.7763397 0.5289553 0.3006457 -0.953736 0 -0.9906893 -0.1358498 -0.00891751 -0.9895242 -0.1443674 0 -0.9966784 -0.08135235 -0.003760993 -0.993686 -0.1121697 0.002497673 0.3097662 -0.9507915 0.006353616 2.85205e-5 -4.62641e-5 -1 0.03490018 -0.99332 -0.109988 0.1539648 -0.8873762 0.4345785 1.80859e-6 4.55957e-6 1 0.6764021 -0.6061288 0.4184353 -1.34906e-6 2.88387e-6 1 0 3.74322e-6 1 -0.2312682 0.9727383 -0.01718759 0.5391775 -0.8148012 -0.2130411 -2.02277e-6 2.47326e-6 1 -1.16582e-4 -7.02897e-5 -1 8.87221e-6 -2.21054e-6 -1 8.12081e-6 -5.03676e-7 -1 0.8331013 -0.5200131 -0.1884902 0.8871876 0.4612085 -0.01359546 0.9274674 0.3660793 0.07609504 0.8687958 -0.4580876 -0.1880148 1.95667e-4 -0.001034736 -0.9999995 -1.09819e-4 6.92287e-5 -1 -0.002206563 6.70752e-4 -0.9999974 -8.32847e-4 -6.44229e-4 -0.9999995 0.2576102 -0.9546117 0.1495109 4.36601e-4 -7.38885e-4 -0.9999997 -3.91811e-4 5.56422e-4 -0.9999998 0.98544 0.1608538 0.05508393 -0.001452863 -6.29076e-4 -0.9999988 2.97199e-4 -8.96248e-4 -0.9999996 0.3030088 0.9525628 0.02845823 0.1386779 0.9877983 -0.07087296 2.92373e-6 -1.92206e-5 -1 0.9258567 -0.3570369 -0.1237506 -1.13174e-5 1.20367e-5 -1 -8.44973e-6 2.3573e-5 -1 0.9923377 0.09719675 -0.07628023 0.8427815 0.5268889 -0.1100341 -9.03349e-7 -4.35967e-6 1 0.7526693 0.582353 0.3071709 0.996163 0.06924891 0.05351752 0 -2.95053e-6 1 -1.99044e-6 -7.87155e-7 1 0.9009708 -0.4338797 0 0.6234883 -0.7818328 0 0.6234953 -0.7818271 0 5.59009e-6 0 1 -6.71501e-6 0 1 0.9009876 0.4338448 0 0.900982 0.4338568 0 0.926629 -0.3028666 0.2227795 0.9776661 -0.2098938 0.0106613 0.9936393 -0.1077744 -0.03264671 -0.3976842 -0.9175165 0.003277957 -0.3930236 -0.9195282 6.19707e-4 0.9860534 -0.1663441 0.005337297 0.8232992 -0.1427394 0.549367 -0.4280864 -0.9037356 -0.002032279 0.8176093 -0.2279669 0.5287213 0.9649911 -0.262283 0 0.9647568 -0.2631399 0.001306772 0.9934365 -0.1143854 0 0.9936054 -0.1128898 0.0020653 0.8388738 -0.09064233 0.536726 0.9781318 -0.207932 -0.00475192 0.9999915 0 -0.004114925 0 0 -1 0.9988185 0.04852533 0.002669751 0.9781407 0.2079226 -0.003037452 0.9719669 0.235114 0.001392424 0.913552 0.406719 -0.001568675 0 0 -1 0.9105606 0.4133756 -2.71574e-4 0.816772 0.5769607 2.59433e-4 0.8090139 0.587786 -0.002037644 0.5690134 -0.8223132 -0.005002319 0.5733289 -0.8193253 0 0.7096557 0.7045487 0 0.7102881 0.7039099 0.001308858 -5.53658e-7 0 1 1.33666e-7 0 1 -0.74444 -0.5879061 -0.3165052 -0.6735904 -0.7389907 0.01299166 -0.8944914 0.4470767 -0.002760589 -0.8770205 0.4804404 0.003505051 -0.8944995 0.447069 -1.18852e-4 -0.5278123 -0.6508939 -0.5456659 -0.2167856 0.0586 -0.9744589 -5.54726e-4 2.75443e-4 -0.9999999 -0.8667584 0.4986723 -0.007471263 -0.817443 0.5749513 0.03490376 -0.6541976 0.7490574 -0.1045873 5.83103e-4 -7.17282e-4 -0.9999996 1.31575e-4 6.65262e-4 -0.9999998 -4.73904e-4 9.47376e-4 -0.9999995 0.1338452 0.9822286 0.1315771 -7.61325e-4 7.26806e-4 -0.9999995 0.8508062 0.5212137 -0.06682366 0.9464997 0.3177377 0.05640369 -0.005074501 7.65098e-4 -0.9999869 0.004833996 0.01278454 -0.9999067 -0.001855015 -0.002135932 -0.9999961 0.02564883 0.01285445 -0.9995884 -0.908519 -0.4169401 0.02746188 -0.994611 -0.09916305 0.03025984 -0.8878185 -0.4599567 -0.01477515 2.25364e-5 1.66595e-5 -1 -0.8616995 0.4586253 -0.2171102 1.06814e-5 -8.7604e-6 -1 -0.08085846 0.9919771 0.09717708 0.325563 0.9449515 -0.03279525 0.3068737 0.9516768 -0.01183104 -9.58493e-6 -2.4294e-5 -1 0.4049008 0.9143528 0.00378865 0.4010266 0.9160647 0.001759827 0.8493793 -0.3045479 -0.4310515 0.8192223 -0.1418653 -0.5556522 -0.001753151 -0.002094566 -0.9999964 1.7802e-4 5.27729e-4 -1 -0.04580533 -0.9989482 0.002110779 -0.1385226 -0.9878129 -0.07097339 -0.3030198 -0.9525595 0.02845048 -3.07782e-4 9.0077e-4 -0.9999996 -0.9854465 -0.1608097 0.05509585 0.001940131 0.001474559 -0.999997 0.002000093 0.002108037 -0.9999958 2.18574e-4 -5.84765e-4 -0.9999999 0.001202106 0.002609968 -0.999996 -0.925859 0.3570374 -0.1237314 -0.750187 0.6591124 0.05282425 -0.02088123 0.004179835 -0.9997733 -4.46624e-4 -2.21298e-4 -1 2.24494e-4 0.001028358 -0.9999995 0.6637902 -0.7462045 -0.05061221 -0.4951021 -0.8608306 0.1176633 -5.24812e-5 0.001159965 -0.9999994 6.25946e-4 -7.67646e-4 -0.9999996 5.74145e-6 1.3136e-5 -1 0.6571693 -0.7524154 -0.04472053 -0.8504292 -0.5179909 -0.0919547 -4.71875e-5 2.28926e-5 -1 0.8450585 -0.5345367 0.01211398 -3.13398e-5 -4.0876e-6 -1 0.8680675 -0.4963704 -0.0086838 0.8632392 -0.5047952 0 -0.02707546 0.01712679 -0.9994868 0.7023 0.4960753 -0.5105723 0.8784256 -0.4778771 0.001459419 0.6889305 0.5032471 -0.5216485 0.5854608 0.8093559 0.04667729 0.894331 -0.4474003 0.00228393 0.8943855 -0.4472729 -0.004669547 2.03824e-4 -1.40444e-4 1 0.8936448 -0.448775 0 1.38426e-7 0 1 7.14887e-5 3.51409e-5 1 -0.8948739 -0.4390684 -0.08012372 2.61874e-6 6.09113e-5 1 -0.04590529 -0.9986322 -0.0250287 -0.7957558 -0.6051008 0.02501881 -1.20296e-4 1.44258e-5 1 -2.97024e-7 0 1 1.67644e-4 8.40169e-5 1 -8.53512e-5 -1.17967e-4 1 0.7957985 -0.6050444 -0.02502077 -6.11802e-5 4.6547e-5 1 0.0459187 -0.9986316 0.02502983 0.6895934 -0.7241954 0.001402974 0.809022 -0.5877764 -0.001563847 0.8132684 -0.5818888 -2.70067e-4 2.51445e-4 -1.8028e-4 1 3.52024e-4 -1.62809e-4 1 0.9080439 -0.4188751 2.59434e-4 0.9135521 -0.4067168 -0.002041041 1.23346e-7 0 -1 0.669121 -0.7431473 -0.003030657 0.5000082 -0.866011 -0.004110157 0.5414559 -0.840725 0.0026744 0 0 1 0.8343636 0.5512146 0 0.8344165 0.5511344 -1.23817e-4 -0.4382165 0.8987691 0.01343327 0.8344135 0.5511322 -0.002782881 0.8485383 0.5291318 0.001560211 -0.2963163 0.7703759 -0.5645509 -0.1881962 0.868395 -0.4587727 -6.64438e-5 1.4004e-4 1 1.27193e-4 1.16381e-4 1 -7.20793e-6 -2.40545e-4 1 -0.6888851 0.7242792 -0.02927613 2.81333e-7 0 1 -0.9750413 0.2101385 0.07166838 -0.3301045 0.8994892 -0.2862698 -2.61007e-7 0 1 -3.04819e-4 -1.37779e-4 1 5.53698e-7 0 1 -0.9719651 -0.2351211 0.00139904 -0.9135427 -0.40674 -0.001564562 -0.910557 -0.4133835 -2.70054e-4 -3.41883e-4 -2.41217e-4 1 -0.8168035 -0.5769162 2.59443e-4 -0.9781459 -0.2078974 -0.003036141 -0.9988184 -0.04852503 0.002669632 0.05818229 -0.998306 0 -0.9934425 0.114333 0 -0.9936122 0.1128296 0.002062559 -0.9999915 0 -0.004114925 -0.9781423 0.2078824 -0.004749417 -0.96476 0.2631281 0.001315414 -0.8437342 0.09121489 0.5289543 -0.8170422 0.1758538 0.5491061 -0.8128845 0.2267466 0.5364745 -0.9649997 0.2622511 0 -3.76042e-4 1.73057e-4 1 0.4295226 0.9030562 0 -0.913537 0.4067507 -0.002034187 -0.9080346 0.4188954 2.63994e-4 -2.67454e-4 1.91035e-4 1 -0.813282 0.5818698 -2.65507e-4 -0.8090094 0.5877937 -0.001566648 -0.6691437 0.7431268 -0.003038763 -0.6896116 0.7241782 0.00139594 -0.5414313 0.8407409 0.002672433 -0.3976603 0.9175328 0 -0.3990398 0.9169313 0.002064406 -0.4999786 0.8660281 -0.0041157 1.7327e-7 0 -1 -0.3090308 0.9510402 -0.004753649 -0.2544575 0.967083 0.001310646 -0.1045321 0.9945195 -0.002041339 -3.64314e-7 0 -1 3.42372e-7 0 -1 0.1045333 0.9945202 -0.001562476 0.09729641 0.9952554 -2.6703e-4 -0.09123796 0.9958291 2.62479e-4 -3.34883e-5 3.71078e-4 1 2.91028e-5 2.9565e-4 1 1.37657e-4 -1.03239e-5 1 -2.25133e-5 -7.71939e-5 1 0.9967018 0.08112609 -0.002004981 0.9968276 0.07959163 0 -1.91822e-4 -1.11928e-4 1 0.08635038 -0.8445684 -0.5284392 0.9983775 0.05663585 -0.005905151 0.4081957 -0.9117017 0.0466516 -0.8345589 -0.5508992 -0.004662692 -0.8420361 -0.5394167 -0.002227962 0.06489056 -0.8579015 -0.5097002 -0.8346319 -0.5508036 0.00228846 -0.349008 0.9371197 0 -0.8395926 -0.5432167 0 -0.3409389 0.7718099 0.5367217 -0.2880318 0.7843662 0.5493699 0.9892473 0.1462499 -9.47853e-4 0.9935976 0.1025635 -0.0473777 -0.2333115 0.9722609 0.01657062 -0.3530456 0.9356018 -0.002871751 -0.2113703 0.8220551 0.528723 1.18553e-6 -4.28885e-6 1 -1.46376e-6 -4.9182e-6 1 -0.4636713 0.8500943 0.2496974 -0.06402784 0.9948274 0.07885998 5.95112e-6 -2.24454e-6 1 -0.0479092 0.986276 0.1580015 -2.9552e-5 1.63394e-5 -1 6.16098e-5 2.7711e-7 -1 1.63206e-5 3.80667e-5 -1 0.4116041 0.9042898 0.1133237 -9.12862e-6 2.66419e-5 -1 0.4124102 0.9043593 0.1097831 -0.8632339 0.5048031 -0.001038372 0.5450792 0.8381993 0.01762646 0 -6.70181e-7 1 0.2225181 0.9749286 0 -0.2225371 0.9749243 0 -0.2225338 0.974925 0 -6.38942e-6 -1.67892e-7 1 -0.2553344 0.9668528 0 2.84691e-7 0 1 0.2823202 0.9593192 0.001398205 -1.48988e-7 0 1 0.3090164 0.951052 -0.003040075 0.457404 0.8892551 0.002667665 0.5957762 0.8031505 0 0.5945727 0.8040393 0.002069056 0.4999786 0.8660281 -0.004111588 0.6691339 0.7431267 -0.00475037 0.427195 0.9041537 -0.003257513 0.06006509 -0.9981907 -0.002769172 0.06005841 -0.998191 0.002804696 0.9934478 -0.09444296 0.06435811 0.2835524 0.9586303 -0.02502381 0.1943998 0.9806033 0.02501916 -0.4573818 -0.8892665 0.002671301 -0.308995 -0.9510589 -0.00303477 -0.2823756 -0.9593029 0.00139445 -4.95174e-6 -3.20396e-5 -1 -1.93153e-5 -7.45334e-7 -1 0.04982632 -0.998615 0.01690047 0.02497816 -0.9996833 0.003062427 -0.976283 0.2164986 -5.45316e-5 -0.5813272 0.7951796 -0.1724767 0.8078271 -0.5893775 0.007055759 0.6460674 -0.7631526 0.01396632 0.5009266 0.6850488 0.5289432 0.6756623 0.7372112 0 0.5608283 0.6196303 0.5491174 0.6809219 0.7323406 -0.004757702 0.6157574 -0.7878713 -0.01009196 0.6231084 -0.7821355 0 0.5731478 -0.819452 -3.74566e-4 0.6028254 0.5905783 0.5364876 0.9174502 0.397063 0.02502405 0.9500124 0.3112085 -0.02501791 -2.64354e-4 5.69155e-4 0.9999998 -3.00032e-4 -5.83141e-4 0.9999999 0.8479627 -0.5294653 0.02501761 -0.8499104 0.1470196 -0.5060018 -0.8571238 0.2899746 -0.4257389 0.002056002 9.98806e-5 0.999998 -0.06736719 0.9977283 0 0.001487553 3.60086e-4 0.9999989 -0.06149178 0.9980912 -0.005711138 -0.0301277 0.999544 0.002048075 0.001754224 0.002095878 -0.9999963 0.04583245 0.998947 0.002091705 -0.06258201 0.9978665 0.01859927 -0.4295109 -0.9030617 0 -0.3081444 -0.9512475 -0.01324027 -0.3255692 -0.9449493 -0.03279727 -1.76621e-4 -5.3018e-4 -1 -2.69742e-6 -3.24345e-6 1 0.002809345 8.47728e-4 -0.9999958 -0.9773712 -0.2089505 0.03294676 0.8514309 0.5244643 -0.001639306 0.2225213 -0.9749279 0 -0.4034026 -0.9117683 -0.07710307 3.29458e-5 -3.58669e-4 1 -2.76549e-5 -2.78891e-4 1 -0.9969448 -0.0781098 0 -0.8090161 -0.587783 -0.002040505 -0.5673123 0.8235028 0 -1.76882e-5 9.71814e-6 -1 -1.48285e-6 1.75679e-6 1 0.6234953 0.7818271 0 0.6234883 0.7818328 0 -5.15807e-6 0 1 2.84378e-6 0 1 0.2225231 -0.9749275 0 0 3.7433e-6 1 -1.56509e-6 1.75679e-6 1 -2.5285e-6 2.4733e-6 1 0.5392183 -0.814777 -0.2130308 0.6763344 -0.6060966 0.4185914 0.1539676 -0.8873983 0.4345323 0.309754 -0.9507955 0.006361246 1.80852e-6 4.55941e-6 1 -1.34907e-6 2.88382e-6 1 -0.2312104 0.9727519 -0.01719307 0.8485041 0.5291862 -0.001743137 0.2562204 -0.7955033 0.5491137 0.3006333 -0.9537398 0 0.8457961 0.533505 0.001270413 0.8351538 0.5500133 -0.001926958 0.3428568 -0.7763093 0.5289547 0.928016 0.3649793 0.07467645 0.8878206 0.4599432 -0.01506614 7.66727e-4 -0.001251935 -0.999999 0.004061162 0.001114487 -0.9999912 -0.4252569 0.7854484 -0.4496972 -0.3068617 0.7843353 -0.5391235 -0.9934597 -0.1141728 0.001546204 -0.9967938 -0.07987529 -0.004711449 -0.9968039 -0.07988893 0 -0.99666 -0.08162504 0.002490282 -0.2320322 0.9705752 0.06438148 -4.15286e-7 0 1 6.87607e-7 0 1 -2.39429e-4 -3.42377e-5 1 -0.04592329 -0.9986314 -0.02503287 -6.08418e-5 4.64914e-5 1 -8.535e-5 -1.17809e-4 1 9.93692e-5 1.37475e-4 1 0.7924893 -0.6025962 -0.09401339 0.1470194 -0.9858826 0.08013075 -0.003663659 4.29993e-4 -0.9999932 -0.001383244 2.33396e-4 -0.9999991 0.9782821 -0.1884725 0.08626979 -9.48628e-4 -7.49437e-5 -0.9999997 -1.83387e-4 0.001228988 -0.9999993 6.07081e-4 -8.03324e-4 -0.9999995 -4.51309e-4 -2.21311e-4 -1 0.6637881 -0.746206 -0.05061566 -0.4950876 -0.8608363 0.1176828 2.25546e-4 0.001035392 -0.9999995 -0.9258795 0.3569859 -0.1237273 -0.9435504 0.3129451 -0.1085266 2.2649e-4 0.001488983 -0.9999989 -0.02087473 0.004177391 -0.9997734 -0.7501981 0.6590988 0.05283534 -0.5737022 0.8163473 -0.06665569 -0.5216066 0.8531165 -0.01090264 -0.02706772 0.01712191 -0.9994871 0.68892 0.5032621 -0.5216479 0.7023258 0.496072 -0.51054 0.868067 -0.4963714 -0.008666872 0.8784228 -0.4778821 0.001476705 0.8450493 -0.5345509 0.01213115 -3.13426e-5 -3.87574e-6 -1 0.8632463 -0.5047831 0 0.6571704 -0.7524135 -0.04473406 5.16707e-6 1.32421e-5 -1 3.00287e-5 -4.66574e-5 -1 -4.83655e-5 2.28928e-5 -1 -0.4034071 -0.9117619 -0.07715618 0.03490298 -0.9933145 -0.1100379 -0.9895253 -0.14436 0 -0.9906938 -0.1358179 -0.008908569 -0.9773699 -0.2089551 0.03295415 -0.8504365 -0.5179795 -0.0919519 -0.6370398 -0.7708309 0 -0.4608061 -0.8291608 0.3164649 -0.6337114 -0.7735643 -0.002854347 -1.51295e-6 7.30271e-6 1 -0.8274821 -0.520102 0.2115831 4.48537e-6 1.39664e-6 1 2.71993e-6 3.45229e-6 1 -0.7253971 -0.6881309 0.01658529 -0.830192 -0.5346419 0.1579227 -1.76865e-5 9.71828e-6 -1 -1.93165e-5 -7.47475e-7 -1 -0.9359712 -0.08459645 0.3417624 -4.95169e-6 -3.20392e-5 -1 -0.9669797 -0.07028418 0.2449702 7.24556e-6 -3.37706e-6 1 8.0645e-6 4.05087e-6 1 -0.9945392 0.1022464 0.02091968 -0.9553055 0.2911725 -0.05108857 -0.8790888 0.4662703 0.09896987 8.36437e-6 0 1 4.25969e-6 -9.4585e-6 1 -0.8260825 0.4813678 0.2930406 -0.9009594 0.4339033 0 -0.9009652 0.4338915 0 3.86853e-6 0 1 -0.6234953 -0.7818271 0 0 -6.7019e-7 1 0.2225339 0.974925 0 1.18543e-6 -4.28884e-6 1 5.95109e-6 -2.24446e-6 1 -0.06403213 0.9948273 0.07885861 0.4123845 0.9043688 0.1098001 -6.57261e-6 -1.67852e-7 1 0.7526136 0.5823199 0.3073701 0.6808621 0.7323963 -0.004751384 0.4116066 0.9042982 0.1132469 -7.52696e-7 -4.35935e-6 1 -2.69737e-6 -3.24338e-6 1 0.5450811 0.8381982 0.01761937 -0.8632475 0.5047798 -0.00103867 0.5607872 0.6196737 0.5491104 0.6756024 0.7372663 0 0.5009567 0.6850134 0.5289605 -0.8944648 0.44713 -0.002755343 -0.8770061 0.4804667 0.003499507 -0.8667713 0.4986504 -0.007438898 -0.8450623 0.5345305 0.01212471 -0.6571746 0.7524105 -0.0447219 -3.12516e-5 1.65465e-5 -1 -9.13112e-6 2.73332e-5 -1 -0.6351619 0.7719565 -0.02554607 0.7614449 0.6474769 -0.03123223 0.852099 0.5190233 -0.06739497 8.11347e-5 -3.21927e-6 -1 0.9452177 0.3219685 0.05384922 0.9942527 0.08989536 -0.05814135 0.989524 0.1443655 -9.81818e-4 1.65063e-5 5.29365e-5 -1 -0.04790973 0.9862717 0.1580281 -0.2333359 0.9722549 0.0165807 0.9993798 0.03390854 -0.009513795 -0.3490302 0.9371115 0 -0.353062 0.9355955 -0.00287187 -0.2880468 0.7843611 0.5493694 0.996701 0.08113825 -0.002001523 -0.2113981 0.8220468 0.5287249 -0.3976551 0.917535 0 -0.3409272 0.7718085 0.5367312 -0.3990226 0.9169388 0.002062797 -0.3090146 0.9510455 -0.00475353 -0.2553718 0.966843 0 -0.2544969 0.9670727 0.00130856 -0.4999809 0.8660266 -0.004117071 -3.37124e-7 0 1 -0.8354609 -0.5495499 0 -0.5414394 0.8407357 0.002672433 5.53661e-7 0 1 -0.6691382 0.7431319 -0.003034651 -0.6896146 0.7241753 0.001396954 -0.8090112 0.5877912 -0.001566648 -0.8132684 0.5818888 -2.71585e-4 -2.66193e-4 1.91034e-4 1 1.27044e-4 1.1638e-4 1 0.8493773 -0.3045415 -0.43106 0.4009938 0.9160792 0.001751124 0.4272075 0.9041478 -0.003262639 0.4295319 0.9030517 0 -3.74449e-4 1.73045e-4 1 0.9934496 -0.09440565 0.0643863 -7.208e-6 -2.40545e-4 1 0.404849 0.9143758 0.00377959 -0.9762849 0.2164898 -5.45314e-5 -0.8170471 0.1758478 0.5491006 -0.8128841 0.2267539 0.5364719 -0.8437259 0.09129178 0.5289543 -0.9934372 0.1143792 0 -0.9781405 0.2078909 -0.004749894 -0.964755 0.2631468 0.001313805 -0.9936041 0.112902 0.002064704 -0.9649932 0.2622753 0 0.05818057 -0.9983062 0 -0.9999915 0 -0.004114925 -0.9988182 -0.04853105 0.002670109 5.5368e-7 0 1 -0.9781451 -0.2079017 -0.003035426 -0.9719666 -0.2351153 0.001398682 -0.9135398 -0.4067465 -0.001563847 -3.0358e-4 -1.37778e-4 1 -0.9105628 -0.4133705 -2.71575e-4 -6.67018e-5 1.40038e-4 1 -0.8167939 -0.5769296 2.57921e-4 -0.809023 -0.5877735 -0.002039968 -0.5673218 0.8234962 0 -3.41866e-4 -2.41205e-4 1 -0.7096129 -0.7045919 0 -0.7102504 -0.7039479 0.001312017 -0.669114 -0.7431447 -0.00475049 -0.5945531 -0.8040539 0.002064347 -0.4979093 -0.6811755 0.5367369 -0.5352554 -0.6416289 0.5493762 -0.606206 -0.5941121 0.5287202 -0.5957534 -0.8031674 0 0.8943721 -0.4472997 -0.004648983 0.89363 -0.4488044 0 0.8943157 -0.4474309 0.002283096 0.5854504 0.8093617 0.04670506 2.0382e-4 -1.40437e-4 1 6.74247e-7 0 1 1.38414e-7 0 1 -0.4573818 -0.8892665 0.002672433 -0.3089837 -0.9510626 -0.003037452 -0.2823641 -0.9593064 0.001393675 -0.1045333 -0.9945202 -0.001567959 -0.09724968 -0.9952601 -2.70062e-4 0.09123629 -0.9958292 2.63991e-4 0 0 -1 0.1045372 -0.9945189 -0.00203973 1.23348e-7 0 -1 0 0 -1 -2.10562e-7 0 -1 0.5000097 -0.8660101 -0.004111468 0.5414367 -0.8407372 0.002670943 0.6691154 -0.7431524 -0.00303471 2.24181e-4 -3.48643e-4 1 2.27286e-4 -2.38676e-4 1 0.6895995 -0.7241896 0.001397192 0.83433 0.5512653 0 0.3977214 -0.9175062 0 0.3990927 -0.9169083 0.002066493 0 0 -1 0 0 -1 0 0 -1 0.4999762 0.8660294 -0.004117012 0.3090165 0.9510519 -0.003040134 0.4573797 0.8892675 0.002667903 0.5958061 0.8031284 0 0.5945971 0.8040212 0.002067089 -0.8945087 0.4470507 0 -6.98402e-7 0 1 -0.8944664 0.4471352 -1.2235e-4 -0.673588 -0.7389931 0.01297998 7.1178e-7 0 1 1.48989e-7 0 1 1.37589e-4 -1.03241e-5 1 0.9466398 0.3100498 -0.08799064 0.6743612 0.7366492 0.05084365 0.2820616 0.9534699 -0.106473 -2.32641e-5 -7.71948e-5 1 -0.6827421 0.7178817 -0.1360481 -0.2811058 0.9582716 0.05191457 -1.91308e-4 -1.11931e-4 1 -0.8590198 0.45718 -0.2303727 -0.04724293 0.9950927 0.08694142 0.001152992 0.001002252 -0.9999989 -0.9939841 -0.1052669 0.03024315 -0.001688361 -0.001767575 -0.9999971 -0.968471 0.237533 0.07511436 -5.67224e-4 -0.002693057 -0.9999963 -0.8878232 -0.4599478 -0.01476347 2.28124e-5 1.66598e-5 -1 -0.9085184 -0.4169412 0.02746641 1.04003e-5 -8.76034e-6 -1 -0.8396535 -0.5431226 0 -0.8420701 -0.5393637 -0.002222418 0.08476549 -0.8533837 -0.5143454 0.02283936 0.01156485 -0.9996723 0.4082289 -0.9116857 0.04667598 -0.8346056 -0.5508434 0.00228095 -0.8345264 -0.5509483 -0.004665911 0.09209573 -0.8487668 -0.5206854 0.004184722 0.01133245 -0.9999271 0.3255726 0.9449481 -0.03279721 1.78027e-4 5.30776e-4 -1 5.71506e-4 2.28271e-4 -0.9999998 -0.00175482 -0.002095103 -0.9999964 -0.1385228 -0.9878132 -0.07096838 -0.04581981 -0.9989476 0.002099752 -0.3194258 -0.9468207 0.03870183 0.0498597 -0.9986132 0.0169 0.02499169 -0.999683 0.003062486 0.8192201 -0.1418681 -0.5556545 0.3068738 0.9516767 -0.01183241 -9.58455e-6 -2.45751e-5 -1 0.2823389 0.9593137 0.001394629 0.1045481 0.9945187 -0.001565277 0.09728038 0.9952571 -2.63983e-4 2.93353e-5 2.95659e-4 1 -0.0912249 0.9958303 2.63991e-4 -3.42679e-5 3.71091e-4 1 -3.37145e-7 0 1 0.5689648 -0.8223467 -0.005010664 -0.7444344 -0.5879117 -0.3165082 -0.5278032 -0.6509049 -0.5456617 -0.2167974 0.05860197 -0.9744561 0.6157705 -0.7878609 -0.01009845 0.6460706 -0.7631499 0.01396161 0.5732884 -0.8193537 0 0.5731037 -0.8194829 -3.55385e-4 0.6028309 0.590595 0.536463 -2.65212e-4 3.64224e-4 -1 -3.49421e-4 2.20244e-4 -1 0.838184 -0.5453602 0.005457758 -1.18567e-5 1.20367e-5 -1 0.9223858 -0.3556518 -0.1507189 0.6231263 -0.7821213 0 -8.83175e-6 2.35709e-5 -1 2.92383e-6 -1.92216e-5 -1 0.9923383 0.09717804 -0.07629632 0.8428013 0.5268667 -0.1099886 0.04583698 0.9989468 0.002093076 -0.06258392 0.9978664 0.01859986 0.1386788 0.987798 -0.07087486 0.9860602 -0.1663038 0.005335867 0.9961651 0.06922471 0.05350661 0.9936406 -0.1077618 -0.03264677 -1.80814e-4 -5.34558e-4 -1 2.96258e-4 -9.01322e-4 -0.9999997 0.00175774 0.002097368 -0.9999963 0.3030006 0.9525656 0.02845132 -0.3081367 -0.9512499 -0.01325136 -0.3255482 -0.9449566 -0.0327959 -0.3930265 -0.9195271 6.16385e-4 -0.3977218 -0.9175004 0.003269612 -0.8499163 0.1470005 -0.5059973 -0.8571292 0.2899734 -0.4257287 -3.00285e-4 -5.83438e-4 0.9999999 -0.0301302 0.9995439 0.002062976 -0.06148302 0.9980918 -0.005710899 0.002056002 9.98968e-5 0.999998 -0.06735521 0.9977291 0 0.001488268 3.60105e-4 0.9999989 -2.64356e-4 5.69154e-4 0.9999999 0.9988178 0.0485391 0.002669394 0.9781475 0.20789 -0.003036677 0.9719701 0.2351004 0.00139898 0.8388694 -0.09065926 0.5367301 0.9934343 -0.1144046 0 0.8233012 -0.1427327 0.5493657 0.9649947 -0.2622696 0 0.8176171 -0.2279612 0.5287116 0.9647552 -0.2631456 0.001313865 0.993603 -0.1129109 0.0020653 0.9781402 -0.2078923 -0.004748642 3.52018e-4 -1.62587e-4 1 -0.4294921 -0.9030707 0 0.9080426 -0.4188778 2.58673e-4 0.913537 -0.4067507 -0.00203675 2.52061e-4 -1.80041e-4 1 0.813282 -0.5818698 -2.73093e-4 -0.4280779 -0.9037396 -0.002022147 0.9999915 0 -0.004115879 -1.16602e-4 -7.06923e-5 -1 0.8331438 -0.5199829 -0.1883863 0.9266276 -0.3028376 0.2228247 0.9776736 -0.2098593 0.0106545 8.30431e-6 -1.65075e-6 -1 0.867264 -0.4615579 -0.1865945 0.2576303 -0.9546051 0.149519 4.39206e-4 -7.38987e-4 -0.9999997 -3.60682e-7 -2.95071e-6 1 -2.1409e-6 0 1 -1.32707e-6 -7.87217e-7 1 0.9009652 0.4338915 0 0.9009594 0.4339033 0 -6.71483e-6 0 1 0.5231459 0.8513496 0.03901576 0.8167749 0.5769567 2.59445e-4 0.9105652 0.4133656 -2.72334e-4 0.9135386 0.4067491 -0.001565217 0.8090209 0.5877764 -0.00203818 0.7102828 0.7039152 0.001310765 0.6691354 0.7431253 -0.004751026 -1.23344e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.1045435 0.9945183 -0.002041399 0.3089848 -0.9510551 -0.004751086 0.8090237 -0.5877739 -0.001566588 0.2544788 -0.9670776 0.001309931 -0.5000121 -0.8660088 -0.00411427 -0.568603 0.8226097 -0.002001821 0 0 -1 -0.9135399 0.4067442 -0.002035319 0.06006407 -0.9981907 0.002796649 0.06007069 -0.9981904 -0.002772569 -0.9080404 0.4188829 2.60948e-4 7.14899e-5 3.51384e-5 1 -0.8907817 -0.4369928 -0.1246805 0.9968274 0.07959425 0 -0.5813132 0.7951884 -0.1724836 -0.4636665 0.8501155 0.2496337 -8.99081e-4 5.61163e-4 -0.9999995 -1.46388e-6 -4.9183e-6 1 0 -1.43515e-6 1 -0.6231342 0.7821145 -9.06504e-4 -0.6234883 -0.7818328 0 -0.7336537 -0.6792372 0.01972979 0.2553606 -0.966846 0 0.2100616 -0.817356 0.5364731 8.82239e-6 -4.97372e-7 -1 + + + + + + + + + + + + + + +

0 0 3 0 1 0 0 1 1 1 2 1 2 2 6 2 0 2 0 3 4 3 3 3 0 4 5 4 4 4 0 5 6 5 5 5 9 6 6 6 2 6 7 7 5 7 6 7 7 8 6 8 8 8 8 9 6 9 9 9 10 6 9 6 2 6 10 10 12 10 9 10 8 11 9 11 11 11 11 12 9 12 12 12 11 13 12 13 13 13 13 13 12 13 14 13 12 6 15 6 14 6 10 6 15 6 12 6 18 14 15 14 16 14 16 15 15 15 10 15 14 16 15 16 17 16 18 17 17 17 15 17 19 18 17 18 18 18 21 19 19 19 18 19 18 20 16 20 20 20 20 21 21 21 18 21 24 22 22 22 21 22 21 23 22 23 25 23 21 24 23 24 24 24 21 25 26 25 23 25 21 26 25 26 27 26 20 27 26 27 21 27 27 28 13 28 21 28 13 29 19 29 21 29 27 30 11 30 13 30 28 31 11 31 27 31 27 32 25 32 28 32 28 33 25 33 29 33 28 34 29 34 32 34 8 35 11 35 28 35 30 36 8 36 28 36 28 37 31 37 30 37 32 38 31 38 28 38 33 39 35 39 32 39 33 40 32 40 29 40 32 41 34 41 31 41 34 42 32 42 38 42 32 43 35 43 36 43 37 44 32 44 36 44 37 45 38 45 32 45 37 46 39 46 38 46 39 47 42 47 38 47 41 48 38 48 40 48 38 49 43 49 40 49 34 50 38 50 41 50 42 51 43 51 38 51 43 52 44 52 40 52 42 53 45 53 43 53 43 53 45 53 44 53 48 54 45 54 46 54 45 55 49 55 46 55 47 53 45 53 48 53 54 53 45 53 47 53 45 53 42 53 53 53 45 56 50 56 49 56 50 57 45 57 51 57 44 53 45 53 52 53 51 58 45 58 53 58 54 59 52 59 45 59 54 60 58 60 55 60 57 61 54 61 55 61 56 62 52 62 54 62 57 63 56 63 54 63 47 64 58 64 54 64 55 65 58 65 60 65 47 66 59 66 58 66 58 67 59 67 60 67 61 68 55 68 60 68 65 69 61 69 60 69 64 70 60 70 62 70 60 71 59 71 62 71 65 72 60 72 63 72 64 73 63 73 60 73 67 74 65 74 63 74 66 75 68 75 65 75 66 76 65 76 67 76 65 77 68 77 69 77 61 78 65 78 69 78 69 79 71 79 70 79 73 80 69 80 70 80 71 81 69 81 68 81 61 82 69 82 55 82 55 83 69 83 57 83 72 84 56 84 69 84 69 85 56 85 57 85 72 86 69 86 73 86 73 87 70 87 75 87 73 88 77 88 72 88 73 89 75 89 74 89 73 90 74 90 76 90 76 91 78 91 73 91 73 92 78 92 77 92 78 93 79 93 77 93 78 94 81 94 79 94 76 95 80 95 78 95 82 96 78 96 80 96 81 97 78 97 82 97 81 98 82 98 83 98 83 99 82 99 84 99 84 100 82 100 85 100 85 101 82 101 86 101 82 102 87 102 86 102 80 103 87 103 82 103 87 104 88 104 90 104 88 105 87 105 80 105 86 106 87 106 89 106 89 107 87 107 90 107 90 108 91 108 89 108 90 109 92 109 91 109 93 110 92 110 90 110 90 111 88 111 93 111 88 112 96 112 93 112 93 113 96 113 94 113 93 114 94 114 95 114 92 115 93 115 95 115 88 116 99 116 96 116 94 117 96 117 97 117 98 118 97 118 96 118 98 119 96 119 99 119 100 120 98 120 99 120 100 121 99 121 101 121 88 122 102 122 99 122 99 123 102 123 101 123 102 124 106 124 101 124 105 125 103 125 102 125 106 126 102 126 103 126 88 127 80 127 102 127 102 128 80 128 104 128 102 129 104 129 105 129 101 130 106 130 108 130 106 131 103 131 107 131 106 132 107 132 109 132 106 133 109 133 108 133 109 134 110 134 108 134 110 135 109 135 113 135 111 136 112 136 109 136 109 137 107 137 111 137 112 138 113 138 109 138 112 139 114 139 113 139 114 140 105 140 113 140 115 141 110 141 113 141 115 142 113 142 116 142 116 143 113 143 118 143 113 144 117 144 118 144 104 145 117 145 113 145 105 146 104 146 113 146 118 147 117 147 119 147 118 148 119 148 116 148 119 149 120 149 48 149 117 150 120 150 119 150 46 151 121 151 119 151 119 152 48 152 46 152 121 153 116 153 119 153 121 154 122 154 116 154 121 155 123 155 122 155 46 156 123 156 121 156 123 53 46 53 124 53 123 157 124 157 125 157 122 158 123 158 125 158 114 6 125 6 127 6 125 159 114 159 126 159 126 160 122 160 125 160 125 161 124 161 127 161 127 162 124 162 128 162 127 163 128 163 129 163 114 6 127 6 129 6 132 164 130 164 129 164 133 165 129 165 130 165 114 6 129 6 133 6 129 166 128 166 131 166 132 167 129 167 131 167 133 168 130 168 134 168 133 169 134 169 136 169 114 6 133 6 105 6 72 170 135 170 133 170 133 171 135 171 103 171 133 172 36 172 72 172 133 173 103 173 105 173 133 174 136 174 36 174 134 6 137 6 136 6 137 175 51 175 136 175 136 176 51 176 53 176 138 177 136 177 53 177 36 178 136 178 138 178 138 179 53 179 39 179 39 180 36 180 138 180 139 181 137 181 134 181 139 182 50 182 137 182 137 183 50 183 51 183 139 184 134 184 140 184 140 185 141 185 139 185 141 186 49 186 139 186 49 187 50 187 139 187 142 188 49 188 141 188 144 189 142 189 141 189 143 190 141 190 145 190 143 191 144 191 141 191 24 192 141 192 140 192 145 193 141 193 24 193 145 194 146 194 130 194 146 195 145 195 23 195 23 196 145 196 24 196 143 197 145 197 130 197 149 198 146 198 147 198 146 199 151 199 147 199 150 200 146 200 23 200 130 201 146 201 148 201 146 202 149 202 148 202 151 203 146 203 150 203 147 204 151 204 135 204 135 205 151 205 103 205 150 206 103 206 151 206 150 207 26 207 152 207 152 208 103 208 150 208 150 209 23 209 26 209 153 210 152 210 26 210 152 211 153 211 111 211 111 212 107 212 152 212 107 213 103 213 152 213 110 214 154 214 153 214 153 215 154 215 111 215 20 216 153 216 26 216 155 217 153 217 20 217 110 218 153 218 155 218 156 219 155 219 157 219 156 220 159 220 155 220 20 221 16 221 155 221 155 222 16 222 157 222 155 223 158 223 110 223 155 224 159 224 158 224 108 225 159 225 101 225 159 226 100 226 101 226 108 227 158 227 159 227 161 228 160 228 159 228 160 229 100 229 159 229 161 230 159 230 156 230 1 231 3 231 161 231 1 232 161 232 156 232 161 233 3 233 163 233 162 234 161 234 95 234 163 235 95 235 161 235 162 236 160 236 161 236 164 237 91 237 163 237 164 238 163 238 166 238 163 239 3 239 165 239 92 240 95 240 163 240 163 241 91 241 92 241 163 242 165 242 166 242 165 243 167 243 166 243 166 243 167 243 169 243 166 244 170 244 168 244 164 245 166 245 168 245 166 246 169 246 170 246 170 247 169 247 172 247 171 248 170 248 173 248 168 249 170 249 171 249 170 250 172 250 173 250 173 251 172 251 5 251 173 252 7 252 171 252 173 253 5 253 7 253 167 6 172 6 169 6 4 254 5 254 172 254 167 6 4 6 172 6 63 255 174 255 171 255 171 256 174 256 175 256 171 257 67 257 63 257 171 258 175 258 168 258 171 259 7 259 30 259 30 260 67 260 171 260 85 261 176 261 175 261 85 262 175 262 84 262 174 263 84 263 175 263 168 264 175 264 176 264 85 265 177 265 176 265 177 266 178 266 176 266 164 267 176 267 178 267 164 268 168 268 176 268 178 269 177 269 74 269 178 270 179 270 91 270 178 271 91 271 164 271 179 272 178 272 181 272 180 273 178 273 74 273 180 274 181 274 178 274 180 275 182 275 181 275 182 276 185 276 181 276 181 277 186 277 183 277 184 278 181 278 183 278 179 279 181 279 184 279 185 280 186 280 181 280 186 281 187 281 183 281 185 282 47 282 186 282 48 283 187 283 186 283 48 284 186 284 47 284 183 285 187 285 188 285 188 286 187 286 189 286 187 287 48 287 189 287 188 288 189 288 190 288 190 289 189 289 191 289 189 290 48 290 191 290 193 291 190 291 191 291 193 292 191 292 192 292 191 293 194 293 192 293 48 53 194 53 191 53 194 53 48 53 195 53 194 294 195 294 196 294 192 295 194 295 196 295 198 296 196 296 197 296 196 297 195 297 197 297 94 298 199 298 196 298 94 299 196 299 162 299 198 300 162 300 196 300 199 301 192 301 196 301 199 302 94 302 97 302 199 303 97 303 192 303 197 304 200 304 198 304 198 305 200 305 98 305 198 306 98 306 162 306 197 6 202 6 200 6 98 307 200 307 97 307 201 308 97 308 200 308 104 309 201 309 200 309 200 310 202 310 117 310 104 311 200 311 117 311 197 312 203 312 202 312 202 313 203 313 120 313 202 314 120 314 117 314 195 53 48 53 203 53 195 315 203 315 197 315 203 53 48 53 120 53 192 6 201 6 193 6 201 316 190 316 193 316 76 6 201 6 104 6 76 6 190 6 201 6 97 317 201 317 192 317 204 318 188 318 190 318 76 319 204 319 190 319 183 320 188 320 204 320 183 321 204 321 184 321 184 322 204 322 179 322 74 323 204 323 76 323 177 324 205 324 204 324 74 325 177 325 204 325 179 326 204 326 205 326 89 327 205 327 177 327 89 328 91 328 205 328 179 329 205 329 91 329 206 330 185 330 182 330 206 331 47 331 185 331 208 332 206 332 182 332 47 53 206 53 207 53 75 333 207 333 206 333 208 334 75 334 206 334 182 335 74 335 208 335 74 336 75 336 208 336 209 53 47 53 207 53 210 337 209 337 207 337 210 338 207 338 75 338 62 339 210 339 70 339 62 340 209 340 210 340 70 6 210 6 75 6 59 341 209 341 62 341 59 53 47 53 209 53 180 342 74 342 182 342 86 343 177 343 85 343 86 344 89 344 177 344 174 345 63 345 83 345 84 346 174 346 83 346 165 347 4 347 167 347 3 348 4 348 165 348 160 349 162 349 100 349 94 350 162 350 95 350 162 351 98 351 100 351 108 352 110 352 158 352 1 353 156 353 157 353 1 354 157 354 2 354 16 355 10 355 157 355 157 356 10 356 2 356 126 357 154 357 122 357 126 358 112 358 154 358 154 359 112 359 111 359 122 360 154 360 110 360 147 361 22 361 149 361 24 362 149 362 22 362 24 363 148 363 149 363 134 364 130 364 148 364 140 365 148 365 24 365 140 366 134 366 148 366 211 367 22 367 147 367 147 368 135 368 211 368 211 369 25 369 22 369 135 370 212 370 211 370 211 371 212 371 33 371 33 372 25 372 211 372 212 373 135 373 77 373 212 374 35 374 33 374 213 375 212 375 79 375 212 376 77 376 79 376 212 377 213 377 35 377 214 378 216 378 213 378 214 379 213 379 215 379 213 380 79 380 215 380 216 381 35 381 213 381 34 382 216 382 214 382 35 383 216 383 217 383 34 384 217 384 216 384 217 385 218 385 36 385 41 386 218 386 217 386 41 387 217 387 34 387 36 388 35 388 217 388 40 389 218 389 41 389 40 390 219 390 218 390 218 391 219 391 56 391 72 6 218 6 56 6 36 392 218 392 72 392 40 393 44 393 219 393 219 394 44 394 52 394 219 395 52 395 56 395 220 396 214 396 215 396 79 397 81 397 215 397 215 398 81 398 66 398 66 399 220 399 215 399 31 400 214 400 220 400 220 401 67 401 30 401 30 402 31 402 220 402 66 403 67 403 220 403 31 404 34 404 214 404 144 405 130 405 132 405 143 406 130 406 144 406 131 407 142 407 144 407 132 408 131 408 144 408 49 409 142 409 46 409 131 410 46 410 142 410 72 411 77 411 135 411 46 53 131 53 128 53 124 53 46 53 128 53 126 412 114 412 112 412 122 413 115 413 116 413 110 414 115 414 122 414 104 415 80 415 76 415 63 416 71 416 83 416 68 417 81 417 83 417 83 418 71 418 68 418 66 419 81 419 68 419 64 420 70 420 71 420 64 421 71 421 63 421 62 422 70 422 64 422 53 423 42 423 39 423 37 424 36 424 39 424 25 425 33 425 29 425 30 426 7 426 8 426 13 427 14 427 19 427 19 427 14 427 17 427 221 428 222 428 223 428 228 53 229 53 227 53 229 429 226 429 231 429 232 430 223 430 233 430 234 53 235 53 224 53 236 431 234 431 224 431 223 53 224 53 238 53 238 432 224 432 235 432 241 433 242 433 243 433 241 434 243 434 244 434 245 435 239 435 247 435 248 436 249 436 250 436 249 437 251 437 252 437 253 438 252 438 254 438 255 439 252 439 251 439 251 440 257 440 256 440 251 441 249 441 248 441 258 442 259 442 260 442 261 443 249 443 253 443 262 444 249 444 261 444 263 445 264 445 265 445 266 446 267 446 268 446 269 447 268 447 270 447 272 448 273 448 271 448 259 449 264 449 263 449 276 450 278 450 263 450 280 451 281 451 282 451 280 452 275 452 281 452 280 453 283 453 275 453 284 454 283 454 280 454 285 455 286 455 287 455 288 456 267 456 289 456 289 457 290 457 288 457 266 458 268 458 269 458 294 459 266 459 269 459 297 460 271 460 298 460 271 461 273 461 299 461 271 462 297 462 269 462 296 463 300 463 266 463 266 464 300 464 292 464 267 465 288 465 286 465 286 466 302 466 303 466 286 467 285 467 281 467 305 468 306 468 277 468 278 469 260 469 263 469 259 470 307 470 308 470 307 471 259 471 258 471 311 53 307 53 310 53 313 472 277 472 306 472 314 473 258 473 260 473 310 474 309 474 315 474 315 475 279 475 276 475 312 476 313 476 306 476 307 477 316 477 317 477 318 53 307 53 317 53 318 53 319 53 307 53 319 53 318 53 320 53 320 478 318 478 321 478 322 479 321 479 304 479 317 480 316 480 323 480 317 481 323 481 324 481 320 482 321 482 322 482 321 483 282 483 304 483 307 484 325 484 326 484 327 53 307 53 326 53 327 485 328 485 307 485 333 486 332 486 285 486 329 487 330 487 331 487 331 488 303 488 302 488 307 489 328 489 334 489 334 490 335 490 336 490 339 53 334 53 336 53 340 53 339 53 341 53 341 491 339 491 342 491 342 492 343 492 341 492 343 493 293 493 291 493 340 53 344 53 334 53 334 494 344 494 345 494 346 495 334 495 345 495 346 496 347 496 334 496 347 497 346 497 348 497 347 498 348 498 349 498 349 499 348 499 296 499 345 500 344 500 350 500 345 501 350 501 351 501 347 502 352 502 334 502 354 503 334 503 353 503 354 504 355 504 334 504 354 505 356 505 355 505 298 506 355 506 356 506 353 53 357 53 358 53 360 507 295 507 297 507 359 508 360 508 297 508 361 509 362 509 363 509 362 510 365 510 363 510 365 511 366 511 363 511 370 512 371 512 372 512 373 513 374 513 375 513 376 514 373 514 375 514 377 515 371 515 378 515 378 516 375 516 374 516 378 517 374 517 377 517 370 518 376 518 379 518 380 519 379 519 376 519 374 520 373 520 377 520 383 521 385 521 386 521 383 522 386 522 381 522 388 523 389 523 390 523 387 524 389 524 388 524 391 525 392 525 393 525 395 526 384 526 382 526 398 527 382 527 399 527 382 528 381 528 399 528 399 529 381 529 400 529 384 530 391 530 383 530 384 531 394 531 392 531 385 532 389 532 387 532 405 533 407 533 408 533 407 534 402 534 408 534 405 535 409 535 407 535 401 536 411 536 405 536 409 537 405 537 411 537 411 538 401 538 403 538 404 539 406 539 402 539 412 540 413 540 414 540 416 541 418 541 417 541 420 542 416 542 421 542 422 543 421 543 416 543 423 544 416 544 424 544 425 545 424 545 415 545 418 546 420 546 417 546 426 547 427 547 428 547 428 548 427 548 429 548 430 549 431 549 432 549 432 550 433 550 430 550 427 551 436 551 434 551 436 552 427 552 437 552 437 553 427 553 438 553 433 554 429 554 430 554 443 555 444 555 445 555 447 556 413 556 419 556 422 557 420 557 421 557 451 558 450 558 452 558 453 559 432 559 454 559 455 560 454 560 431 560 435 561 455 561 434 561 449 562 457 562 458 562 457 563 460 563 458 563 461 564 442 564 441 564 259 565 308 565 462 565 259 566 441 566 264 566 264 567 441 567 440 567 467 568 468 568 464 568 463 569 465 569 469 569 469 570 465 570 470 570 474 571 475 571 476 571 480 572 481 572 482 572 483 573 484 573 485 573 486 574 487 574 488 574 489 575 490 575 491 575 492 576 493 576 494 576 499 577 497 577 493 577 493 578 492 578 499 578 498 579 497 579 499 579 500 580 501 580 502 580 506 581 460 581 507 581 507 582 460 582 511 582 516 583 503 583 512 583 513 584 502 584 517 584 519 585 501 585 520 585 521 586 505 586 507 586 522 587 507 587 523 587 522 588 521 588 507 588 524 589 527 589 528 589 524 590 526 590 527 590 528 591 527 591 529 591 534 592 535 592 533 592 536 53 532 53 537 53 541 53 540 53 542 53 541 593 539 593 540 593 543 594 538 594 539 594 546 53 547 53 552 53 553 53 549 53 554 53 554 53 549 53 555 53 537 53 532 53 555 53 531 595 556 595 532 595 556 596 558 596 532 596 532 597 558 597 555 597 559 598 560 598 561 598 559 599 562 599 560 599 564 600 565 600 561 600 567 601 564 601 560 601 560 602 564 602 561 602 564 603 569 603 570 603 570 604 569 604 571 604 571 605 565 605 570 605 570 606 565 606 564 606 524 607 571 607 525 607 524 608 572 608 571 608 571 609 572 609 565 609 525 610 571 610 573 610 574 611 525 611 573 611 557 612 576 612 573 612 557 613 577 613 576 613 571 614 568 614 573 614 575 615 578 615 556 615 564 616 580 616 568 616 568 617 580 617 575 617 583 618 584 618 582 618 556 619 578 619 582 619 582 620 578 620 575 620 580 621 582 621 575 621 583 622 582 622 580 622 555 623 558 623 581 623 581 624 584 624 554 624 553 625 584 625 585 625 555 626 581 626 554 626 584 627 583 627 567 627 584 628 566 628 585 628 584 629 560 629 566 629 586 630 585 630 566 630 551 631 586 631 550 631 550 632 586 632 587 632 587 633 586 633 563 633 588 634 587 634 563 634 563 635 590 635 589 635 594 636 591 636 593 636 596 637 595 637 597 637 577 638 596 638 579 638 576 639 579 639 598 639 592 640 596 640 599 640 577 641 599 641 596 641 531 642 600 642 557 642 598 643 602 643 576 643 576 644 602 644 573 644 573 645 602 645 574 645 606 646 605 646 604 646 605 647 608 647 607 647 613 648 611 648 614 648 616 649 617 649 612 649 616 650 618 650 617 650 616 651 619 651 618 651 619 652 620 652 621 652 622 653 620 653 624 653 624 654 620 654 625 654 627 655 628 655 624 655 629 656 630 656 625 656 629 657 631 657 630 657 629 658 633 658 632 658 636 659 635 659 637 659 638 660 639 660 633 660 638 661 640 661 641 661 642 662 646 662 647 662 643 663 642 663 647 663 648 664 647 664 646 664 640 665 651 665 641 665 641 666 652 666 653 666 654 667 638 667 655 667 639 668 656 668 633 668 657 669 658 669 659 669 660 670 661 670 662 670 660 671 662 671 663 671 630 672 666 672 667 672 630 673 626 673 625 673 411 674 617 674 618 674 618 675 672 675 411 675 604 676 378 676 371 676 606 677 604 677 674 677 676 678 380 678 607 678 674 679 371 679 370 679 402 680 407 680 609 680 672 681 409 681 411 681 609 682 612 682 617 682 609 683 403 683 402 683 605 684 679 684 608 684 615 685 680 685 679 685 615 686 681 686 680 686 615 687 673 687 681 687 682 688 683 688 684 688 685 689 682 689 684 689 686 690 689 690 687 690 686 691 671 691 689 691 687 692 689 692 690 692 690 693 691 693 692 693 690 694 692 694 693 694 694 695 690 695 693 695 698 696 699 696 700 696 712 697 714 697 715 697 716 698 712 698 715 698 717 699 711 699 712 699 718 700 719 700 713 700 720 701 721 701 722 701 722 702 723 702 724 702 725 703 722 703 724 703 727 704 658 704 728 704 727 705 728 705 729 705 731 706 732 706 655 706 733 707 731 707 734 707 728 708 731 708 733 708 734 709 653 709 652 709 740 710 734 710 735 710 741 711 744 711 743 711 747 712 746 712 748 712 750 713 751 713 748 713 751 714 752 714 753 714 754 715 755 715 756 715 751 716 750 716 752 716 750 717 757 717 752 717 759 718 767 718 768 718 772 719 762 719 773 719 776 720 773 720 777 720 776 721 780 721 781 721 782 722 783 722 781 722 783 723 782 723 720 723 780 724 777 724 784 724 785 725 784 725 786 725 785 726 786 726 787 726 716 727 787 727 788 727 716 728 715 728 787 728 784 729 789 729 790 729 786 730 784 730 791 730 703 731 702 731 701 731 795 732 792 732 796 732 797 733 795 733 796 733 793 734 799 734 800 734 702 735 704 735 705 735 803 736 706 736 804 736 807 737 804 737 676 737 676 738 809 738 379 738 688 739 687 739 813 739 686 740 683 740 678 740 808 741 815 741 810 741 696 742 692 742 695 742 694 743 693 743 816 743 708 744 816 744 705 744 717 745 798 745 797 745 795 746 794 746 792 746 817 747 772 747 775 747 740 748 821 748 733 748 763 749 760 749 761 749 739 750 738 750 824 750 756 751 824 751 754 751 820 752 818 752 821 752 769 753 755 753 759 753 775 754 725 754 817 754 719 755 714 755 713 755 717 756 710 756 711 756 701 757 792 757 793 757 812 758 813 758 811 758 828 759 829 759 830 759 828 760 830 760 834 760 836 761 826 761 825 761 837 762 825 762 827 762 837 763 827 763 838 763 839 764 827 764 840 764 843 765 844 765 845 765 847 766 848 766 849 766 849 767 848 767 850 767 855 768 856 768 857 768 857 769 856 769 858 769 861 770 860 770 862 770 865 771 864 771 866 771 867 772 868 772 869 772 869 773 868 773 870 773 873 774 872 774 874 774 879 775 880 775 881 775 881 776 880 776 882 776 883 777 884 777 885 777 887 778 888 778 889 778 891 779 892 779 602 779 602 780 892 780 603 780 897 781 898 781 899 781 907 782 906 782 908 782 911 783 910 783 912 783 913 784 914 784 915 784 919 785 918 785 920 785 927 786 926 786 928 786 929 787 930 787 931 787 937 788 938 788 235 788 235 789 938 789 939 789 942 790 941 790 943 790 946 791 945 791 238 791 947 53 514 53 948 53 945 792 949 792 950 792 238 793 950 793 237 793 225 794 952 794 940 794 888 795 225 795 940 795 227 796 230 796 225 796 225 797 230 797 953 797 224 798 955 798 236 798 937 799 235 799 956 799 888 800 957 800 954 800 937 53 956 53 938 53 938 801 956 801 958 801 889 802 959 802 887 802 939 803 958 803 960 803 889 804 890 804 959 804 962 805 939 805 960 805 890 806 884 806 961 806 961 807 884 807 963 807 933 808 935 808 964 808 883 809 965 809 884 809 885 53 967 53 883 53 934 810 966 810 936 810 936 811 966 811 968 811 885 812 886 812 967 812 886 813 880 813 969 813 969 814 880 814 971 814 929 815 931 815 972 815 972 816 931 816 970 816 879 817 973 817 880 817 880 818 973 818 971 818 929 53 972 53 930 53 930 819 972 819 974 819 879 820 975 820 973 820 881 821 882 821 975 821 927 53 932 53 978 53 882 822 876 822 977 822 980 823 927 823 978 823 876 824 981 824 979 824 926 825 980 825 982 825 875 53 983 53 981 53 926 826 982 826 928 826 928 827 982 827 984 827 877 828 878 828 983 828 986 829 928 829 984 829 878 830 872 830 985 830 985 831 872 831 987 831 872 832 989 832 987 832 922 53 988 53 990 53 922 833 990 833 924 833 924 834 990 834 992 834 873 835 874 835 991 835 919 53 924 53 994 53 874 836 868 836 993 836 993 837 868 837 995 837 996 838 919 838 994 838 867 839 997 839 868 839 917 53 996 53 918 53 867 840 999 840 997 840 869 841 870 841 999 841 1002 842 920 842 1000 842 1004 843 915 843 1002 843 863 844 1005 844 864 844 864 845 1005 845 1003 845 914 846 1004 846 1006 846 865 53 1007 53 863 53 863 53 1007 53 1005 53 1007 847 866 847 1009 847 911 848 916 848 1010 848 1010 849 916 849 1008 849 866 850 860 850 1009 850 1009 851 860 851 1011 851 1012 852 911 852 1010 852 859 853 1013 853 860 853 860 854 1013 854 1011 854 909 53 1012 53 910 53 859 855 1015 855 1013 855 910 856 1014 856 912 856 861 857 862 857 1015 857 907 858 912 858 1018 858 856 859 1021 859 1019 859 906 53 1020 53 1022 53 855 860 1023 860 1021 860 908 861 1022 861 1024 861 1023 862 858 862 1025 862 1025 863 852 863 1027 863 901 864 903 864 1028 864 852 865 1029 865 1027 865 901 53 1028 53 902 53 902 825 1028 825 1030 825 902 866 1030 866 904 866 1031 867 854 867 1033 867 899 858 904 858 1034 858 854 868 848 868 1033 868 1036 869 899 869 1034 869 848 870 1037 870 1035 870 897 53 1036 53 898 53 898 53 1036 53 1038 53 849 53 1039 53 847 53 898 871 1038 871 900 871 849 872 850 872 1039 872 895 858 900 858 1042 858 1042 873 900 873 1040 873 850 874 844 874 1041 874 893 875 895 875 1044 875 1044 876 895 876 1042 876 843 877 1045 877 844 877 844 878 1045 878 1043 878 845 53 1047 53 843 53 843 879 1047 879 1045 879 574 880 1048 880 527 880 842 881 601 881 1049 881 1049 882 601 882 531 882 1050 883 1049 883 531 883 894 884 1046 884 896 884 896 885 1046 885 1051 885 1047 886 846 886 1052 886 892 887 891 887 1048 887 842 888 1049 888 841 888 891 889 896 889 1053 889 1053 890 896 890 1051 890 1055 891 1057 891 594 891 508 892 1056 892 509 892 888 893 1056 893 890 893 890 894 1056 894 884 894 876 895 1056 895 878 895 872 896 593 896 874 896 850 897 848 897 593 897 593 898 848 898 854 898 593 899 858 899 856 899 862 896 860 896 593 896 600 900 841 900 599 900 599 901 841 901 846 901 844 902 599 902 846 902 238 903 1058 903 946 903 1058 904 235 904 939 904 935 905 1058 905 939 905 1058 906 936 906 931 906 594 907 928 907 923 907 924 908 594 908 923 908 912 909 594 909 911 909 903 910 594 910 908 910 903 911 904 911 594 911 900 912 895 912 594 912 598 913 896 913 891 913 602 914 598 914 891 914 510 915 509 915 1059 915 514 916 1061 916 948 916 460 917 510 917 458 917 828 918 833 918 829 918 829 919 833 919 1062 919 1062 920 1063 920 829 920 513 921 1065 921 512 921 1065 922 1064 922 443 922 444 923 1066 923 1067 923 1068 924 1067 924 1069 924 1072 925 1073 925 1074 925 1073 926 479 926 472 926 472 927 1075 927 1073 927 475 928 1077 928 1076 928 1077 929 475 929 468 929 1077 930 468 930 1078 930 1078 931 1079 931 1077 931 1079 932 1078 932 470 932 470 933 1081 933 1080 933 1080 934 1081 934 1082 934 1084 935 1083 935 1085 935 835 936 1086 936 1085 936 1087 937 1084 937 1088 937 1089 938 1090 938 1087 938 1089 939 1091 939 1090 939 1092 940 1091 940 1093 940 1094 941 1092 941 1093 941 1094 942 1096 942 1095 942 1097 943 836 943 839 943 1084 944 1085 944 1086 944 835 945 1085 945 832 945 835 946 832 946 831 946 1082 947 1084 947 1087 947 1095 948 1096 948 1098 948 1098 949 1096 949 1099 949 1100 950 1099 950 1101 950 1102 951 1101 951 1103 951 1105 952 1104 952 484 952 1107 953 1105 953 482 953 482 954 491 954 1107 954 491 955 1109 955 1108 955 488 956 1109 956 491 956 457 957 1114 957 1115 957 511 958 460 958 457 958 1100 959 1101 959 1102 959 1102 960 1103 960 1104 960 1114 961 1116 961 1115 961 826 962 840 962 827 962 1063 963 1065 963 513 963 1111 964 452 964 459 964 1109 965 1110 965 459 965 1112 966 452 966 1111 966 1117 967 1068 967 1069 967 1118 968 1119 968 1120 968 1118 969 1121 969 1119 969 1121 970 1122 970 1123 970 1125 971 1124 971 1126 971 1139 972 1138 972 1140 972 1141 973 1140 973 1142 973 1145 974 1144 974 1146 974 1151 975 1150 975 1152 975 1153 976 1152 976 1154 976 1125 977 1126 977 1127 977 1127 978 1128 978 1129 978 1129 979 1130 979 1131 979 1131 980 1132 980 1133 980 1133 981 1134 981 1135 981 1135 982 1136 982 1137 982 1137 983 1138 983 1139 983 1139 984 1140 984 1141 984 1141 985 1142 985 1143 985 1143 986 1144 986 1145 986 1145 987 1146 987 1147 987 1149 988 1150 988 1151 988 1153 989 1154 989 1155 989 1155 990 1156 990 1157 990 1157 991 1158 991 1159 991 1159 992 1160 992 508 992 1162 993 1163 993 1057 993 1057 994 1163 994 1058 994 1058 995 1163 995 1164 995 516 996 1164 996 1165 996 1164 997 1166 997 1165 997 1165 998 1166 998 1167 998 1171 999 1170 999 1172 999 1169 1000 1170 1000 1171 1000 1173 1001 1174 1001 1175 1001 833 1002 1177 1002 1062 1002 1177 1003 833 1003 832 1003 1176 1004 1177 1004 832 1004 1097 1005 839 1005 1178 1005 1178 1006 839 1006 840 1006 1179 1007 1178 1007 840 1007 829 1008 1086 1008 835 1008 477 1009 1180 1009 1181 1009 1182 1010 1181 1010 1183 1010 1182 1011 1183 1011 1184 1011 477 1012 1181 1012 1182 1012 1181 1013 474 1013 466 1013 463 1014 469 1014 1187 1014 463 1015 1188 1015 1183 1015 463 1016 1183 1016 466 1016 1189 1017 1190 1017 1191 1017 1190 1018 1189 1018 1192 1018 1193 1019 1192 1019 1189 1019 1185 1020 1186 1020 1195 1020 1186 1021 1198 1021 1195 1021 1195 1022 1198 1022 1200 1022 480 1023 1201 1023 1202 1023 480 1024 1202 1024 1203 1024 1202 1025 486 1025 498 1025 498 1026 486 1026 495 1026 1202 1027 498 1027 1204 1027 1203 1028 1204 1028 485 1028 1209 1029 1211 1029 1210 1029 490 1030 1212 1030 1213 1030 1214 1031 1215 1031 1216 1031 1213 1032 1215 1032 1214 1032 483 1033 485 1033 1218 1033 499 1034 1219 1034 1204 1034 499 1035 1204 1035 498 1035 1220 1036 1221 1036 1222 1036 1223 1037 1220 1037 1222 1037 1220 1038 1207 1038 1206 1038 1221 1039 1206 1039 504 1039 1207 1040 1223 1040 1208 1040 1217 1041 499 1041 492 1041 1204 1042 1222 1042 485 1042 1229 1043 1227 1043 1230 1043 1231 1044 1232 1044 1233 1044 1233 1045 1226 1045 1228 1045 1070 1046 1185 1046 1196 1046 1072 1047 1070 1047 1196 1047 1234 1048 477 1048 1182 1048 1070 1049 1182 1049 1185 1049 478 1050 477 1050 1234 1050 1235 1051 474 1051 1181 1051 480 1052 1203 1052 481 1052 484 1053 483 1053 1215 1053 482 1054 1105 1054 480 1054 480 1055 1105 1055 1213 1055 1215 1056 1213 1056 1105 1056 1236 1057 1203 1057 485 1057 494 1058 1209 1058 492 1058 494 1059 1112 1059 1209 1059 1209 1060 1112 1060 496 1060 495 1061 1211 1061 496 1061 1237 1062 469 1062 470 1062 1205 1063 1217 1063 1209 1063 1217 1064 492 1064 1209 1064 1201 1065 480 1065 489 1065 1212 1066 480 1066 1213 1066 483 1067 1218 1067 1215 1067 1215 1068 1218 1068 1216 1068 1212 1069 490 1069 489 1069 1116 1070 1239 1070 1238 1070 493 1071 1114 1071 1113 1071 1113 1072 494 1072 493 1072 488 1073 487 1073 1110 1073 1236 1074 487 1074 1201 1074 1201 1075 482 1075 481 1075 1236 1076 1201 1076 481 1076 1239 1077 1236 1077 1240 1077 484 1078 1240 1078 1236 1078 1101 1079 1240 1079 1103 1079 1241 1080 1099 1080 1096 1080 467 1081 476 1081 1237 1081 1237 1082 1242 1082 469 1082 1194 1083 1187 1083 1242 1083 1187 1084 469 1084 1242 1084 1085 1085 1243 1085 1062 1085 1085 1086 1083 1086 465 1086 465 1087 1083 1087 1081 1087 1081 1088 470 1088 465 1088 464 1089 1234 1089 1244 1089 1235 1090 464 1090 475 1090 1234 1091 1235 1091 1180 1091 1180 1092 479 1092 478 1092 479 1093 1180 1093 472 1093 1067 1094 1245 1094 1069 1094 1246 1095 1066 1095 1064 1095 1246 1096 1062 1096 1243 1096 1244 1097 1247 1097 1248 1097 1244 1098 1248 1098 1249 1098 1246 1099 1249 1099 1250 1099 1244 1100 1249 1100 1243 1100 1252 1101 1253 1101 1247 1101 1248 1102 1253 1102 1254 1102 1249 1103 1255 1103 1250 1103 1248 1104 1254 1104 1249 1104 1250 1105 1255 1105 1256 1105 1257 1106 1241 1106 1258 1106 1099 1107 1257 1107 1259 1107 1239 1108 1260 1108 1261 1108 1241 1109 1257 1109 1099 1109 1099 1110 1259 1110 1101 1110 1239 1111 1258 1111 1238 1111 1257 1112 1262 1112 1264 1112 1259 1113 1264 1113 1265 1113 1260 1114 1259 1114 1265 1114 1257 1115 1264 1115 1259 1115 1258 1116 1266 1116 1263 1116 1258 1117 1263 1117 1257 1117 1260 1118 1265 1118 1261 1118 1187 1119 1188 1119 463 1119 1193 1120 1242 1120 1267 1120 1267 1121 1242 1121 1237 1121 1267 1122 476 1122 471 1122 471 1123 473 1123 1197 1123 1272 1124 1200 1124 1198 1124 1199 1125 1191 1125 1273 1125 1269 1126 1274 1126 1275 1126 1275 1127 1191 1127 1190 1127 1276 1128 1192 1128 1277 1128 1277 1129 1192 1129 1226 1129 1226 1130 1232 1130 1277 1130 1277 1131 1232 1131 1278 1131 1279 1132 1232 1132 1137 1132 1226 1133 1192 1133 1227 1133 1282 1134 1224 1134 1221 1134 1283 1135 1221 1135 1284 1135 1278 1136 1283 1136 1284 1136 1214 1137 1225 1137 1137 1137 1282 1138 1221 1138 1283 1138 1284 1139 1221 1139 1285 1139 1281 1140 1280 1140 1137 1140 500 1141 1271 1141 1270 1141 1271 1142 1256 1142 1255 1142 1274 1143 1255 1143 1254 1143 1270 1144 1255 1144 1274 1144 1282 1145 1266 1145 1265 1145 1283 1146 1279 1146 1263 1146 1282 1147 1265 1147 1281 1147 1086 1148 829 1148 1084 1148 1063 1149 517 1149 1084 1149 1093 1150 523 1150 1094 1150 1115 1151 826 1151 1094 1151 1060 1152 942 1152 1287 1152 943 1153 1288 1153 942 1153 942 1154 1288 1154 1287 1154 1052 1155 361 1155 1043 1155 1052 1156 1054 1156 361 1156 361 1157 1054 1157 1289 1157 363 1158 987 1158 993 1158 363 1159 985 1159 987 1159 363 1160 979 1160 985 1160 363 1161 977 1161 979 1161 363 1162 963 1162 969 1162 363 1163 961 1163 963 1163 363 1164 231 1164 954 1164 363 1165 953 1165 231 1165 363 1166 366 1166 1060 1166 361 1167 995 1167 1001 1167 1003 1168 1009 1168 361 1168 1009 1169 1011 1169 361 1169 1019 1170 361 1170 1017 1170 1019 1171 1025 1171 361 1171 1025 1172 1027 1172 361 1172 1033 1173 1035 1173 361 1173 1048 1174 1290 1174 527 1174 1061 1175 442 1175 461 1175 1028 1176 1026 1176 1030 1176 1030 1177 1026 1177 1032 1177 1018 1178 1022 1178 1020 1178 1012 1179 1010 1179 1014 1179 1002 1180 1006 1180 1004 1180 998 1181 994 1181 1000 1181 986 1182 990 1182 988 1182 982 1183 978 1183 984 1183 970 1184 974 1184 972 1184 966 1185 962 1185 968 1185 960 1186 958 1186 234 1186 234 1187 958 1187 956 1187 232 1188 233 1188 955 1188 955 1189 233 1189 236 1189 1044 1190 1042 1190 1046 1190 1289 1191 1049 1191 1050 1191 449 1192 1059 1192 369 1192 1029 1193 1031 1193 1027 1193 1009 1194 1003 1194 1007 1194 997 1195 999 1195 995 1195 995 1196 999 1196 1001 1196 993 1197 987 1197 991 1197 977 1198 971 1198 975 1198 975 1199 971 1199 973 1199 963 1200 967 1200 969 1200 959 1201 954 1201 957 1201 953 1202 229 1202 231 1202 952 1203 1287 1203 951 1203 951 1204 1287 1204 1288 1204 1043 1205 1047 1205 1052 1205 1041 1206 1035 1206 1039 1206 1039 1207 1035 1207 1037 1207 941 53 951 53 943 53 1291 1208 453 1208 454 1208 456 1209 453 1209 1291 1209 1293 1210 1294 1210 456 1210 435 1211 436 1211 1295 1211 1296 1212 435 1212 1297 1212 1296 1213 1297 1213 1298 1213 1297 1214 435 1214 1295 1214 1299 1215 1300 1215 1298 1215 1301 1216 438 1216 1302 1216 1302 1217 1303 1217 1304 1217 1303 1218 1305 1218 1306 1218 1303 1219 1306 1219 1308 1219 422 1220 648 1220 448 1220 648 1221 646 1221 447 1221 447 1222 448 1222 648 1222 423 1223 649 1223 422 1223 446 1224 414 1224 413 1224 1312 1225 1313 1225 1314 1225 1315 1226 1316 1226 1314 1226 1314 1227 1313 1227 1315 1227 1318 1228 1317 1228 1319 1228 1318 1229 1315 1229 1317 1229 1314 1230 1320 1230 1312 1230 1312 1231 1320 1231 1321 1231 1322 1232 1323 1232 1324 1232 1319 1233 1327 1233 1318 1233 1328 1234 1317 1234 1330 1234 1313 1235 1312 1235 1317 1235 1332 1236 1333 1236 1334 1236 1333 1237 1335 1237 1336 1237 1332 1238 1338 1238 1335 1238 1338 1239 1340 1239 1343 1239 1343 1240 1340 1240 1344 1240 1342 1241 1345 1241 1340 1241 1340 1242 1345 1242 1344 1242 1346 1243 1347 1243 1348 1243 1347 1244 1341 1244 1334 1244 1347 1245 1334 1245 1348 1245 1350 1246 1351 1246 1352 1246 1351 1247 1350 1247 1353 1247 1350 1248 1354 1248 1353 1248 1355 1249 1350 1249 1352 1249 1355 1250 1356 1250 1350 1250 1358 1251 1354 1251 1359 1251 1360 1252 1356 1252 1362 1252 1362 1253 1363 1253 1360 1253 1360 1254 1363 1254 1361 1254 1362 1255 1364 1255 1363 1255 1363 1256 1364 1256 1365 1256 1364 1257 1366 1257 1365 1257 1365 1258 1366 1258 1367 1258 1352 1259 1357 1259 1368 1259 1369 1260 1370 1260 1371 1260 1372 1261 1369 1261 1371 1261 1369 1262 1373 1262 1374 1262 1371 1263 1375 1263 1372 1263 1376 1264 1372 1264 1375 1264 1370 1265 1369 1265 1378 1265 1369 1266 1374 1266 1379 1266 1379 1267 1374 1267 1380 1267 1373 1268 1381 1268 1380 1268 1376 1269 1382 1269 1377 1269 1382 1270 1376 1270 1384 1270 1382 1271 1384 1271 1383 1271 1383 1272 1384 1272 1385 1272 1384 1273 1376 1273 1375 1273 1385 1274 1375 1274 1386 1274 1387 1275 1388 1275 1375 1275 1387 1276 1370 1276 1388 1276 1388 1277 1370 1277 1378 1277 1392 1278 1389 1278 1391 1278 1389 1279 1393 1279 1394 1279 1396 1280 1393 1280 1392 1280 1389 1281 1394 1281 1399 1281 1400 1282 1394 1282 1393 1282 1397 1283 1401 1283 1393 1283 1396 1284 1402 1284 1397 1284 1402 1285 1396 1285 1404 1285 1403 1286 1404 1286 1405 1286 1404 1287 1396 1287 1395 1287 1404 1288 1395 1288 1405 1288 1407 1289 1408 1289 1395 1289 1408 1290 1390 1290 1398 1290 1409 1291 1410 1291 1411 1291 1412 1292 1409 1292 1411 1292 1409 1293 1413 1293 1414 1293 1413 1294 1416 1294 1417 1294 1410 1295 1409 1295 1418 1295 1409 1296 1414 1296 1419 1296 1420 1297 1414 1297 1413 1297 1417 1298 1421 1298 1413 1298 1417 1299 1422 1299 1421 1299 1421 1300 1422 1300 1423 1300 1422 1301 1416 1301 1424 1301 1422 1302 1424 1302 1423 1302 1425 1303 1415 1303 1426 1303 1415 1304 1428 1304 1426 1304 1411 1305 1410 1305 1427 1305 1428 1306 1410 1306 1418 1306 1429 1307 1430 1307 1431 1307 1433 1308 1429 1308 1432 1308 1436 1309 1432 1309 1435 1309 1436 1310 1433 1310 1432 1310 1438 1311 1429 1311 1439 1311 1429 1312 1434 1312 1439 1312 1439 1313 1434 1313 1440 1313 1437 1314 1441 1314 1433 1314 1444 1315 1436 1315 1435 1315 1445 1316 1435 1316 1446 1316 1447 1317 1448 1317 1435 1317 1435 1318 1448 1318 1446 1318 1431 1319 1430 1319 1447 1319 1447 1320 1430 1320 1448 1320 1448 1321 1430 1321 1438 1321 1449 1322 1453 1322 1454 1322 1453 1323 1456 1323 1457 1323 1450 1324 1449 1324 1458 1324 1460 1325 1454 1325 1453 1325 1457 1326 1461 1326 1453 1326 1453 1327 1461 1327 1460 1327 1462 1328 1464 1328 1463 1328 1464 1329 1456 1329 1455 1329 1465 1330 1455 1330 1466 1330 1455 1331 1468 1331 1466 1331 1455 1332 1451 1332 1467 1332 1451 1333 1450 1333 1467 1333 1468 1334 1450 1334 1458 1334 1469 1335 1470 1335 1471 1335 1472 1336 1469 1336 1471 1336 1473 1337 1469 1337 1472 1337 1471 1338 1475 1338 1472 1338 1476 1339 1472 1339 1475 1339 1476 1340 1473 1340 1472 1340 1478 1341 1469 1341 1479 1341 1479 1342 1474 1342 1480 1342 1480 1343 1474 1343 1473 1343 1477 1344 1481 1344 1473 1344 1476 1345 1482 1345 1477 1345 1481 1346 1482 1346 1483 1346 1482 1347 1476 1347 1484 1347 1482 1348 1484 1348 1483 1348 1484 1349 1475 1349 1485 1349 1485 1350 1475 1350 1486 1350 1487 1351 1488 1351 1475 1351 1475 1352 1488 1352 1486 1352 1487 1353 1470 1353 1488 1353 1488 1354 1470 1354 1478 1354 1489 1355 1490 1355 1491 1355 1492 1356 1489 1356 1491 1356 1489 1357 1493 1357 1494 1357 1491 1358 1495 1358 1492 1358 1496 1359 1492 1359 1495 1359 1496 1360 1493 1360 1492 1360 1490 1361 1489 1361 1498 1361 1498 1362 1489 1362 1499 1362 1489 1363 1494 1363 1499 1363 1497 1364 1501 1364 1493 1364 1493 1365 1501 1365 1500 1365 1496 1366 1502 1366 1497 1366 1497 1367 1502 1367 1501 1367 1501 1368 1502 1368 1503 1368 1502 1369 1496 1369 1504 1369 1503 1370 1504 1370 1505 1370 1504 1371 1496 1371 1495 1371 1504 1372 1495 1372 1505 1372 1505 1373 1495 1373 1506 1373 1495 1374 1491 1374 1507 1374 1507 1375 1490 1375 1508 1375 1509 1376 1510 1376 1511 1376 1510 1377 1509 1377 1512 1377 1509 1378 1513 1378 1512 1378 1510 1379 1512 1379 1516 1379 1512 1380 1513 1380 747 1380 1518 1381 1513 1381 1515 1381 1515 1382 1513 1382 1509 1382 1517 1383 1518 1383 1519 1383 1518 1384 1515 1384 1520 1384 1520 1385 1521 1385 1518 1385 1518 1386 1521 1386 1519 1386 1514 1387 1522 1387 1515 1387 1515 1388 1522 1388 1520 1388 1522 1389 1524 1389 1523 1389 1523 1390 1524 1390 1525 1390 1524 1391 1514 1391 1511 1391 1524 1392 1511 1392 1525 1392 1525 1393 1511 1393 1526 1393 1527 1394 1528 1394 1529 1394 1530 1395 1527 1395 1529 1395 1531 1396 1527 1396 1530 1396 1532 1397 1531 1397 1530 1397 1529 1398 1533 1398 1530 1398 1534 1399 1530 1399 1533 1399 1537 1400 1534 1400 1539 1400 1540 1401 1539 1401 757 1401 1533 1402 1529 1402 1541 1402 439 1403 1294 1403 752 1403 1542 1404 606 1404 1543 1404 1545 1405 1543 1405 1544 1405 1544 1406 677 1406 379 1406 1544 1407 379 1407 809 1407 1543 1408 1545 1408 1547 1408 1547 1409 1545 1409 1548 1409 1548 1410 1549 1410 1547 1410 1549 1411 1548 1411 1550 1411 1550 1412 1551 1412 1549 1412 1550 1413 802 1413 1551 1413 1549 1414 1552 1414 1547 1414 1547 1415 1552 1415 1553 1415 1557 1416 1556 1416 1555 1416 1557 1417 1558 1417 1556 1417 1559 1418 1555 1418 1560 1418 1563 1419 1562 1419 1564 1419 1565 1420 1563 1420 1564 1420 1567 1421 1563 1421 1566 1421 778 1422 1561 1422 779 1422 1556 1423 1562 1423 1563 1423 1565 1424 1564 1424 1569 1424 1570 1425 1566 1425 766 1425 1570 1426 766 1426 765 1426 1567 1427 1571 1427 1572 1427 1573 1428 1567 1428 1572 1428 1571 1429 768 1429 767 1429 1291 1430 1293 1430 456 1430 261 1431 1294 1431 1293 1431 1291 1432 1292 1432 1573 1432 744 1433 423 1433 424 1433 744 1434 425 1434 1307 1434 425 1435 1310 1435 1307 1435 745 1436 1535 1436 743 1436 744 1437 1306 1437 745 1437 1302 1438 438 1438 757 1438 1535 1439 746 1439 743 1439 749 1440 746 1440 1538 1440 749 1441 1540 1441 750 1441 757 1442 750 1442 1540 1442 1577 1443 1578 1443 1579 1443 1585 1444 1584 1444 1586 1444 1587 1445 1586 1445 1588 1445 1309 1446 1592 1446 1593 1446 1307 1447 1593 1447 1308 1447 1295 1448 1594 1448 1595 1448 1300 1449 1595 1449 1579 1449 1578 1450 1300 1450 1579 1450 1300 1451 1299 1451 1595 1451 1299 1452 1295 1452 1595 1452 1295 1453 1301 1453 1594 1453 1591 1454 1596 1454 1590 1454 1596 1455 1597 1455 1590 1455 1589 1456 1598 1456 1588 1456 1598 1457 1599 1457 1588 1457 1600 1458 1587 1458 1588 1458 1587 1459 1601 1459 1586 1459 1601 1460 1585 1460 1586 1460 1585 1461 1602 1461 1584 1461 1604 1462 1102 1462 1605 1462 1604 1463 1100 1463 1102 1463 1098 1464 1604 1464 1606 1464 1095 1465 1606 1465 1607 1465 1090 1466 1608 1466 1609 1466 1080 1467 1610 1467 1611 1467 1075 1468 1076 1468 1597 1468 1098 1469 1606 1469 1095 1469 1095 1470 1607 1470 1092 1470 1092 1471 1607 1471 1090 1471 1597 1472 1076 1472 1589 1472 1616 1473 1617 1473 1598 1473 1598 1474 1617 1474 1599 1474 1618 1475 1599 1475 1617 1475 1619 1476 1601 1476 1587 1476 1601 1477 1619 1477 1620 1477 1622 1478 1583 1478 1623 1478 1603 1479 1622 1479 1624 1479 1580 1480 1625 1480 1626 1480 1106 1481 1626 1481 1104 1481 1106 1482 1578 1482 1577 1482 1106 1483 1107 1483 1578 1483 1589 1484 1615 1484 1598 1484 1602 1485 1623 1485 1583 1485 1597 1486 1596 1486 1075 1486 1298 1487 1578 1487 1627 1487 1174 1488 1590 1488 1120 1488 1593 1489 1170 1489 1168 1489 1593 1490 1168 1490 1166 1490 1308 1491 1166 1491 1164 1491 1303 1492 1163 1492 1162 1492 1593 1493 1166 1493 1308 1493 1304 1494 1161 1494 1160 1494 1594 1495 1160 1495 1158 1495 1595 1496 1152 1496 1150 1496 1581 1497 1142 1497 1140 1497 1584 1498 1138 1498 1136 1498 1304 1499 1160 1499 1594 1499 1594 1500 1156 1500 1595 1500 1595 1501 1150 1501 1579 1501 1584 1502 1136 1502 1586 1502 1588 1503 1130 1503 1128 1503 1588 1504 1126 1504 1124 1504 1590 1505 1122 1505 1118 1505 1573 1506 368 1506 1628 1506 1567 1507 1628 1507 1629 1507 1542 1508 1543 1508 1634 1508 1292 1509 368 1509 1573 1509 1573 1510 1628 1510 1567 1510 1567 1511 1629 1511 1563 1511 1563 1512 1630 1512 1556 1512 1556 1513 1631 1513 1553 1513 1547 1514 1633 1514 1543 1514 459 1515 1298 1515 1107 1515 1109 1516 1107 1516 1108 1516 1117 1517 645 1517 445 1517 1117 1518 1636 1518 645 1518 1117 1519 1614 1519 1636 1519 1117 1520 1073 1520 1614 1520 1596 1521 1613 1521 1073 1521 1614 1522 1637 1522 1636 1522 445 1523 645 1523 440 1523 440 1524 645 1524 264 1524 264 1525 645 1525 642 1525 286 1526 629 1526 625 1526 267 1527 625 1527 620 1527 268 1528 620 1528 616 1528 272 1529 270 1529 612 1529 264 1530 642 1530 265 1530 265 1531 638 1531 275 1531 281 1532 629 1532 286 1532 267 1533 620 1533 268 1533 268 1534 616 1534 270 1534 1309 1535 1310 1535 1638 1535 1638 1536 1637 1536 1591 1536 1309 1537 1638 1537 1591 1537 368 1538 365 1538 1639 1538 1628 1539 1639 1539 1629 1539 365 1540 1641 1540 1639 1540 1641 1541 365 1541 1642 1541 1641 1542 1643 1542 1639 1542 1639 1543 1643 1543 1644 1543 1646 1544 1647 1544 1629 1544 1629 1545 1647 1545 1648 1545 1630 1546 1648 1546 1649 1546 1652 1547 1651 1547 1653 1547 1654 1548 1652 1548 1653 1548 1654 1549 1655 1549 1652 1549 1644 1550 1643 1550 1656 1550 1639 1551 1644 1551 1629 1551 1652 1552 1655 1552 1631 1552 1631 1553 1657 1553 1658 1553 1631 1554 1660 1554 1632 1554 1632 1555 1660 1555 1661 1555 1663 1556 1632 1556 1662 1556 1663 1557 1664 1557 1633 1557 1633 1558 1666 1558 1634 1558 1640 1559 1666 1559 1667 1559 1670 1560 1671 1560 1635 1560 1631 1561 1630 1561 1652 1561 1628 1562 368 1562 1639 1562 1672 1563 1559 1563 1673 1563 1655 1564 1674 1564 1657 1564 790 1565 1655 1565 1675 1565 1674 1566 1655 1566 790 1566 1653 1567 1676 1567 1654 1567 1678 1568 778 1568 1651 1568 1651 1569 778 1569 1679 1569 1651 1570 1650 1570 1678 1570 1680 1571 1650 1571 1681 1571 1681 1572 1650 1572 1682 1572 1647 1573 1646 1573 1685 1573 1646 1574 771 1574 1687 1574 1691 1575 767 1575 1656 1575 1691 1576 1641 1576 1692 1576 1692 1577 1641 1577 1642 1577 1692 1578 1642 1578 1574 1578 365 1579 362 1579 1642 1579 1642 1580 362 1580 1693 1580 364 1581 1694 1581 362 1581 364 1582 1697 1582 1696 1582 364 1583 1702 1583 1701 1583 364 1584 1703 1584 1702 1584 1705 1585 1706 1585 1707 1585 1707 1586 1706 1586 1668 1586 1669 1587 1668 1587 1706 1587 1703 1588 1704 1588 1708 1588 1703 1589 1708 1589 1709 1589 1709 1590 1667 1590 1666 1590 1701 1591 1702 1591 1710 1591 1711 1592 1710 1592 1665 1592 1713 1593 1714 1593 1712 1593 1714 1594 1662 1594 1661 1594 1699 53 1700 53 1712 53 1673 1595 1718 1595 1658 1595 1717 1596 1718 1596 1673 1596 1720 1597 1721 1597 362 1597 1679 1598 1723 1598 1651 1598 1675 1599 1724 1599 1719 1599 1724 1600 1675 1600 1655 1600 1724 1601 1655 1601 1654 1601 1722 1602 1723 1602 1679 1602 1723 1603 1653 1603 1651 1603 1727 1604 362 1604 1726 1604 1727 1605 1728 1605 362 1605 1686 1606 1729 1606 1648 1606 1726 1607 1725 1607 1682 1607 1730 1608 1682 1608 1650 1608 1686 1609 1648 1609 1647 1609 1728 1610 1731 1610 362 1610 362 1611 1731 1611 1732 1611 1733 1612 362 1612 1732 1612 1733 1613 1734 1613 362 1613 1732 1614 1731 1614 1736 1614 1737 1615 1736 1615 1688 1615 1732 1616 1736 1616 1737 1616 1734 1617 1693 1617 362 1617 285 1618 1739 1618 304 1618 304 1619 1739 1619 1738 1619 1739 1620 285 1620 1740 1620 285 1621 332 1621 1740 1621 287 1622 303 1622 1741 1622 1743 1623 664 1623 302 1623 302 1624 664 1624 331 1624 1743 1625 288 1625 1744 1625 1744 1626 288 1626 290 1626 290 1627 1745 1627 1744 1627 291 1628 1748 1628 343 1628 1748 1629 292 1629 1749 1629 294 1630 1751 1630 349 1630 294 1631 295 1631 1751 1631 1751 1632 295 1632 1753 1632 360 1633 1753 1633 295 1633 360 1634 670 1634 1753 1634 1754 1635 1755 1635 1756 1635 1758 1636 1759 1636 1760 1636 299 1637 1758 1637 1760 1637 274 1638 1754 1638 1756 1638 1764 1639 543 1639 539 1639 1764 1640 539 1640 1765 1640 1766 1641 542 1641 1767 1641 1767 1642 1671 1642 1670 1642 1670 1643 1766 1643 1767 1643 1766 1644 1670 1644 1669 1644 534 1645 543 1645 535 1645 1050 1646 535 1646 1764 1646 1050 1647 531 1647 535 1647 1764 1648 1706 1648 1289 1648 1289 1649 1706 1649 364 1649 361 1650 1289 1650 364 1650 563 1651 562 1651 590 1651 590 1652 562 1652 559 1652 1769 1653 565 1653 572 1653 1770 1654 524 1654 528 1654 1759 1655 1771 1655 1761 1655 1759 1656 1772 1656 1771 1656 1772 1657 1757 1657 1755 1657 1773 1658 1774 1658 1755 1658 1773 1659 1775 1659 1774 1659 1774 1660 1775 1660 1776 1660 1778 53 1777 53 589 53 559 1661 1769 1661 1779 1661 1779 53 572 53 1780 53 1780 1662 524 1662 1770 1662 307 1663 1781 1663 308 1663 308 1664 1781 1664 462 1664 1032 1665 1026 1665 1781 1665 1026 1666 1024 1666 1781 1666 1018 1667 1016 1667 1781 1667 1010 1668 1008 1668 1781 1668 1000 1669 994 1669 1781 1669 992 1670 986 1670 462 1670 1781 1671 994 1671 992 1671 986 1672 984 1672 462 1672 978 1673 976 1673 462 1673 968 1674 962 1674 462 1674 960 1675 234 1675 462 1675 962 1676 960 1676 462 1676 236 1677 233 1677 462 1677 234 1678 236 1678 462 1678 237 1679 947 1679 462 1679 948 1680 461 1680 462 1680 1040 1681 1038 1681 1034 1681 1065 1682 442 1682 512 1682 1576 1683 1541 1683 1528 1683 1306 1684 1576 1684 1528 1684 1605 1685 1782 1685 1783 1685 1782 1686 1605 1686 1626 1686 1605 1687 1783 1687 1604 1687 1604 1688 1783 1688 1784 1688 1606 1689 1785 1689 1786 1689 1786 1690 1607 1690 1606 1690 1786 1691 1787 1691 1607 1691 1788 1692 1609 1692 1608 1692 1609 1693 1789 1693 1790 1693 1791 1694 1792 1694 1611 1694 1611 1695 1792 1695 1793 1695 1612 1696 1793 1696 1794 1696 1612 1697 1611 1697 1793 1697 1609 1698 1790 1698 1610 1698 1076 1699 1795 1699 1612 1699 1615 1700 1076 1700 1796 1700 1799 1701 1618 1701 1617 1701 1799 1702 1800 1702 1618 1702 1618 1703 1800 1703 1619 1703 1619 1704 1801 1704 1620 1704 1620 1705 1802 1705 1803 1705 1807 1706 1808 1706 1809 1706 1804 1707 1813 1707 1812 1707 1814 1708 1805 1708 1808 1708 1815 1709 1816 1709 1817 1709 1822 1710 1818 1710 1817 1710 1820 1711 1818 1711 1822 1711 1823 1712 1822 1712 1816 1712 1824 1713 1816 1713 1815 1713 1819 1714 1818 1714 1826 1714 1815 1715 1817 1715 1825 1715 1830 1716 1831 1716 1832 1716 1832 1717 1831 1717 1833 1717 1833 1718 1831 1718 1834 1718 1835 1719 1830 1719 1838 1719 1835 1720 1834 1720 1830 1720 1838 1721 1830 1721 1828 1721 1831 1722 1830 1722 1834 1722 1784 1723 1840 1723 1841 1723 1841 1724 1785 1724 1784 1724 1785 1725 1842 1725 1832 1725 1786 1726 1832 1726 1833 1726 1836 1727 1835 1727 1838 1727 1807 1728 1802 1728 1825 1728 1812 1729 1819 1729 1789 1729 1788 1730 1811 1730 1812 1730 1811 1731 1788 1731 1787 1731 1825 1732 1801 1732 1824 1732 1824 1733 1801 1733 1846 1733 1793 1734 1797 1734 1794 1734 1800 1735 1799 1735 1846 1735 1823 1736 1820 1736 1822 1736 1791 1737 1799 1737 1792 1737 1790 1738 1789 1738 1826 1738 1826 1739 1789 1739 1819 1739 1807 1740 1825 1740 1813 1740 1812 1741 1813 1741 1819 1741 1806 1742 1814 1742 1807 1742 1823 1743 1824 1743 1846 1743 1817 1744 1819 1744 1825 1744 1842 1745 1827 1745 1832 1745 1830 1746 1832 1746 1827 1746 1839 1747 1625 1747 1624 1747 1839 1748 1782 1748 1625 1748 1782 1749 1626 1749 1625 1749 1841 1750 1624 1750 1622 1750 1841 1751 1622 1751 1842 1751 1845 1752 1602 1752 1844 1752 1847 1753 1542 1753 1848 1753 1847 1754 1849 1754 1542 1754 1850 1755 1851 1755 1852 1755 1854 6 1853 6 1855 6 1855 1756 1853 1756 1856 1756 1853 6 1859 6 1856 6 1862 1757 1861 1757 1863 1757 1862 1758 1863 1758 1864 1758 1867 6 1868 6 1869 6 1858 1759 1870 1759 1871 1759 1875 1760 1874 1760 1876 1760 1575 1761 1878 1761 614 1761 1575 1762 1879 1762 1877 1762 1880 6 1849 6 1847 6 1880 1763 1847 1763 1868 1763 1881 1764 1882 1764 1883 1764 1881 6 1884 6 1882 6 1886 1765 1888 1765 1887 1765 1888 1766 1889 1766 614 1766 1885 1767 1884 1767 1850 1767 1885 1768 1850 1768 1852 1768 1873 6 1864 6 1872 6 1877 6 1875 6 1876 6 1883 6 1872 6 1881 6 1848 1769 1891 1769 1847 1769 612 1770 613 1770 1762 1770 1762 1771 1886 1771 1763 1771 1893 1772 587 1772 1858 1772 1858 1773 587 1773 1855 1773 1871 1774 1893 1774 1858 1774 1894 1775 1763 1775 1852 1775 1895 1776 1852 1776 1851 1776 1763 1777 1885 1777 1852 1777 1889 1778 613 1778 614 1778 1893 1779 1892 1779 552 1779 552 1780 1892 1780 546 1780 546 1781 1892 1781 1871 1781 544 1782 546 1782 1871 1782 1891 1783 1848 1783 1671 1783 1635 1784 1671 1784 1542 1784 588 1785 589 1785 1777 1785 1895 1786 1777 1786 1775 1786 1896 1787 1775 1787 1773 1787 1894 1788 1773 1788 1755 1788 588 1789 1777 1789 1895 1789 1897 1790 536 1790 1898 1790 540 1791 1900 1791 1901 1791 537 1792 1903 1792 1898 1792 536 1793 537 1793 1898 1793 549 1794 1903 1794 537 1794 1904 1795 1897 1795 1905 1795 1899 1796 1904 1796 1906 1796 1900 1797 1906 1797 1907 1797 1901 1798 1907 1798 1908 1798 1899 1799 1906 1799 1900 1799 1903 1800 1905 1800 1898 1800 1770 1801 1913 1801 1914 1801 1778 1802 1916 1802 1917 1802 1776 1803 1917 1803 1918 1803 1774 1804 1918 1804 1911 1804 1772 1805 1774 1805 1911 1805 1778 1806 1917 1806 1776 1806 1912 1807 1919 1807 1913 1807 1914 1808 1921 1808 1922 1808 1917 1809 1924 1809 1925 1809 1911 1810 1918 1810 1920 1810 1926 1811 1882 1811 1887 1811 1882 1812 1927 1812 1883 1812 1883 1813 1927 1813 1928 1813 1874 1814 1928 1814 1929 1814 1876 1815 1929 1815 1930 1815 1874 1816 1929 1816 1876 1816 1876 1817 1930 1817 1878 1817 1888 1818 1932 1818 1887 1818 1927 1819 1926 1819 1932 1819 1931 1820 1930 1820 1932 1820 1933 1821 1864 1821 1873 1821 1864 1822 1934 1822 1866 1822 1880 1823 1936 1823 1937 1823 1880 1824 1937 1824 1938 1824 1879 1825 1938 1825 1939 1825 1879 1826 1939 1826 1877 1826 1938 1827 1937 1827 1939 1827 1941 1828 1856 1828 1860 1828 1870 1829 1943 1829 1944 1829 1860 1830 1947 1830 1941 1830 1870 1831 1945 1831 1867 1831 1867 1832 1945 1832 1865 1832 1948 1833 1942 1833 1941 1833 1948 1834 1949 1834 1942 1834 1943 1835 1949 1835 1950 1835 1945 1836 1951 1836 1952 1836 1945 1837 1952 1837 1953 1837 1941 1838 1947 1838 1948 1838 1946 1839 1954 1839 1947 1839 1851 1840 1956 1840 1957 1840 1851 1841 1957 1841 1853 1841 1861 1842 1959 1842 1863 1842 1881 1843 1961 1843 1884 1843 1884 1844 1962 1844 1850 1844 1963 1845 1956 1845 1955 1845 1963 1846 1964 1846 1956 1846 1956 1847 1964 1847 1957 1847 1957 1848 1964 1848 1965 1848 1961 1849 1968 1849 1969 1849 1955 1850 1962 1850 1963 1850 1957 1851 1965 1851 1958 1851 1958 1852 1966 1852 1959 1852 1960 1853 1968 1853 1961 1853 1961 1854 1969 1854 1962 1854 1937 1855 1935 1855 1971 1855 1935 1856 1934 1856 1971 1856 1964 1857 1972 1857 1925 1857 1964 1858 1963 1858 1972 1858 1973 1859 1963 1859 1969 1859 1974 1860 1969 1860 1968 1860 1925 1861 1976 1861 1964 1861 1924 1862 1923 1862 1966 1862 1923 1863 1922 1863 1975 1863 1967 1864 1922 1864 1921 1864 1973 1865 1919 1865 1920 1865 1967 1866 1921 1866 1968 1866 1974 1867 1919 1867 1969 1867 1905 1868 1910 1868 1977 1868 1949 1869 1977 1869 1910 1869 1979 1870 1954 1870 1953 1870 1980 1871 1952 1871 1951 1871 1950 1872 1981 1872 1909 1872 1952 1873 1906 1873 1953 1873 1982 1874 1736 1874 1731 1874 1731 1875 1728 1875 1982 1875 651 1876 279 1876 1984 1876 309 1877 258 1877 1984 1877 1984 1878 258 1878 1985 1878 316 1879 312 1879 1987 1879 1987 1880 312 1880 1988 1880 1989 1881 1695 1881 1990 1881 1990 1882 1695 1882 1717 1882 1991 1883 1715 1883 800 1883 802 1884 1710 1884 1702 1884 1994 1885 1703 1885 1995 1885 1998 1886 348 1886 346 1886 1997 1887 348 1887 1998 1887 346 1888 345 1888 1998 1888 1998 1889 345 1889 1999 1889 2000 1890 360 1890 357 1890 2000 1891 357 1891 352 1891 627 1892 301 1892 2002 1892 2002 1893 340 1893 2003 1893 2005 1894 358 1894 359 1894 2004 1895 358 1895 2005 1895 297 1896 2007 1896 359 1896 359 1897 2007 1897 2006 1897 2007 1898 297 1898 618 1898 1747 1899 342 1899 2008 1899 303 1900 330 1900 1742 1900 1742 1901 330 1901 665 1901 325 1902 319 1902 2009 1902 2010 1903 319 1903 320 1903 2010 1904 320 1904 636 1904 1654 1905 1677 1905 1724 1905 1658 1906 2011 1906 1659 1906 1658 1907 1718 1907 2011 1907 2011 1908 1718 1908 2013 1908 1663 1909 2014 1909 2015 1909 1662 1910 1713 1910 2014 1910 1640 1911 2017 1911 1544 1911 386 1912 2019 1912 381 1912 381 1913 2019 1913 400 1913 390 1914 391 1914 2021 1914 2021 1915 391 1915 397 1915 1334 1916 1336 1916 1349 1916 239 1917 241 1917 247 1917 247 1918 241 1918 2022 1918 277 1919 2023 1919 276 1919 277 1920 313 1920 2023 1920 2023 1921 313 1921 655 1921 2025 1922 317 1922 2027 1922 280 1923 2029 1923 324 1923 324 1924 2029 1924 659 1924 2030 1925 1721 1925 1722 1925 1722 1926 1679 1926 2030 1926 766 1927 1729 1927 2031 1927 2032 1928 1726 1928 1730 1928 1569 1929 2033 1929 1730 1929 2032 1930 1730 1930 2033 1930 1649 1931 1683 1931 1730 1931 1730 1932 1683 1932 1569 1932 2034 1933 1732 1933 1737 1933 248 1934 262 1934 257 1934 255 1935 256 1935 753 1935 753 1936 752 1936 254 1936 257 1937 1574 1937 256 1937 758 1938 759 1938 753 1938 767 1939 759 1939 2035 1939 1689 1940 771 1940 770 1940 761 1941 759 1941 2036 1941 761 1942 2036 1942 2034 1942 2036 1943 759 1943 768 1943 2036 1944 1732 1944 2034 1944 2036 1945 1735 1945 1733 1945 768 1946 1735 1946 2036 1946 1982 1947 1983 1947 762 1947 765 1948 762 1948 1983 1948 771 1949 1568 1949 1687 1949 1685 1950 1687 1950 1568 1950 1568 1951 1570 1951 1685 1951 1983 1952 1728 1952 765 1952 2033 1953 1569 1953 773 1953 773 1954 2031 1954 2032 1954 2037 1955 777 1955 773 1955 778 1956 777 1956 2030 1956 1678 1957 1680 1957 1564 1957 1678 1958 1564 1958 1562 1958 1562 1959 778 1959 1678 1959 1725 1960 1721 1960 2037 1960 2037 1961 1721 1961 2030 1961 650 1962 2022 1962 2038 1962 2022 1963 643 1963 247 1963 650 1964 643 1964 2022 1964 245 1965 643 1965 647 1965 647 1966 422 1966 245 1966 734 1967 652 1967 1984 1967 1984 1968 736 1968 734 1968 650 1969 736 1969 1985 1969 650 1970 1985 1970 2039 1970 1984 1971 652 1971 651 1971 2039 1972 644 1972 650 1972 1985 1973 258 1973 2039 1973 2042 1974 653 1974 734 1974 2043 1975 731 1975 655 1975 655 1976 638 1976 2023 1976 638 1977 641 1977 2023 1977 2023 1978 641 1978 2024 1978 653 1979 2024 1979 641 1979 276 1980 2024 1980 315 1980 2042 1981 310 1981 315 1981 1986 1982 1987 1982 658 1982 1987 1983 1988 1983 731 1983 1987 1984 731 1984 658 1984 658 1985 657 1985 1986 1985 657 1986 656 1986 654 1986 654 1987 655 1987 732 1987 2029 1988 635 1988 656 1988 2044 1989 635 1989 2029 1989 726 1990 2028 1990 659 1990 726 1991 2025 1991 2027 1991 637 1992 2026 1992 2025 1992 637 1993 2025 1993 721 1993 2045 1994 789 1994 784 1994 784 1995 777 1995 2046 1995 784 1996 2046 1996 2045 1996 2046 1997 777 1997 779 1997 779 1998 1561 1998 1676 1998 1561 1999 1558 1999 1677 1999 2045 2000 1719 2000 1724 2000 2045 2001 1724 2001 789 2001 1989 2002 1990 2002 791 2002 1989 2003 791 2003 784 2003 1557 2004 1674 2004 790 2004 1557 2005 1555 2005 1672 2005 1674 2006 1557 2006 1672 2006 2047 2007 799 2007 793 2007 793 2008 2049 2008 2047 2008 1560 2009 2013 2009 2049 2009 1555 2010 1554 2010 2011 2010 2048 2011 2012 2011 799 2011 1716 2012 2012 2012 2048 2012 2047 2013 1697 2013 1716 2013 2047 2014 1716 2014 2048 2014 793 2015 800 2015 1992 2015 1992 2016 1993 2016 703 2016 1992 2017 703 2017 793 2017 799 2018 2050 2018 1991 2018 799 2019 1554 2019 2050 2019 2051 2020 2052 2020 2053 2020 1552 2021 2052 2021 2051 2021 2053 2022 1993 2022 1714 2022 2054 2023 704 2023 2055 2023 2054 2024 706 2024 704 2024 2014 2025 2052 2025 2015 2025 1549 2026 1551 2026 2015 2026 1711 2027 2015 2027 1551 2027 1551 2028 801 2028 1711 2028 2056 2029 2057 2029 1550 2029 1548 2030 1545 2030 2058 2030 2056 2031 1548 2031 2058 2031 2058 2032 1545 2032 1546 2032 706 2033 802 2033 1994 2033 805 2034 804 2034 1995 2034 805 2035 1703 2035 1709 2035 1546 2036 805 2036 1709 2036 2009 2037 721 2037 718 2037 637 2038 721 2038 2010 2038 662 2039 661 2039 1740 2039 1739 2040 634 2040 1738 2040 1739 2041 661 2041 634 2041 636 2042 1738 2042 634 2042 662 2043 332 2043 325 2043 662 2044 718 2044 2059 2044 718 2045 2060 2045 2059 2045 665 2046 631 2046 1742 2046 1742 2047 631 2047 660 2047 663 2048 1741 2048 660 2048 2059 2049 326 2049 333 2049 1745 2050 1996 2050 713 2050 664 2051 713 2051 1996 2051 630 2052 631 2052 2061 2052 1743 2053 1744 2053 2061 2053 666 2054 630 2054 2061 2054 664 2055 1743 2055 2061 2055 1996 2056 329 2056 664 2056 2062 2057 667 2057 711 2057 668 2058 626 2058 1747 2058 668 2059 1747 2059 2008 2059 626 2060 630 2060 1746 2060 1747 2061 626 2061 1746 2061 2065 2062 628 2062 695 2062 691 2063 622 2063 1997 2063 1750 2064 622 2064 624 2064 624 2065 628 2065 1750 2065 2065 2066 1750 2066 628 2066 1999 2067 695 2067 1998 2067 1998 2068 695 2068 691 2068 691 2069 1997 2069 1998 2069 1999 2070 351 2070 2065 2070 671 2071 2000 2071 689 2071 671 2072 670 2072 2000 2072 1753 2073 670 2073 2066 2073 621 2074 623 2074 1751 2074 2001 2075 1752 2075 623 2075 1752 2076 2001 2076 349 2076 676 2077 804 2077 2068 2077 806 2078 2018 2078 2068 2078 806 2079 2017 2079 2018 2079 1668 2080 1544 2080 1707 2080 2067 2081 1705 2081 809 2081 2007 2082 671 2082 2006 2082 2005 2083 2006 2083 671 2083 2004 2084 686 2084 2070 2084 686 2085 672 2085 2070 2085 2069 2086 356 2086 354 2086 2069 2087 354 2087 2070 2087 628 2088 627 2088 2002 2088 1749 2089 627 2089 624 2089 2002 2090 2003 2090 709 2090 2002 2091 709 2091 695 2091 398 2092 685 2092 396 2092 398 2093 399 2093 685 2093 399 2094 400 2094 673 2094 400 2095 2019 2095 681 2095 400 2096 681 2096 673 2096 2019 2097 2020 2097 681 2097 680 2098 681 2098 2020 2098 2021 2099 397 2099 808 2099 2021 2100 808 2100 608 2100 808 2101 396 2101 685 2101 814 2102 813 2102 812 2102 814 2103 1331 2103 688 2103 1331 2104 1321 2104 683 2104 1321 2105 684 2105 683 2105 684 2106 1322 2106 815 2106 1322 2107 1324 2107 815 2107 815 2108 1324 2108 810 2108 1326 2109 812 2109 807 2109 694 2110 1348 2110 690 2110 1348 2111 687 2111 690 2111 1336 2112 813 2112 1349 2112 1349 2113 813 2113 687 2113 813 2114 1337 2114 811 2114 813 2115 1336 2115 1337 2115 1337 2116 1343 2116 811 2116 1343 2117 1344 2117 707 2117 1344 2118 1345 2118 708 2118 1357 2119 1358 2119 700 2119 1358 2120 698 2120 700 2120 1358 2121 1359 2121 696 2121 1359 2122 1361 2122 692 2122 1359 2123 692 2123 696 2123 1361 2124 1363 2124 693 2124 1361 2125 693 2125 692 2125 693 2126 1365 2126 816 2126 816 2127 1365 2127 705 2127 1367 2128 1368 2128 702 2128 1367 2129 702 2129 705 2129 1357 2130 702 2130 1368 2130 1378 2131 797 2131 1388 2131 1378 2132 1379 2132 797 2132 1380 2133 698 2133 697 2133 699 2134 698 2134 1383 2134 1385 2135 1386 2135 792 2135 1385 2136 792 2136 701 2136 1386 2137 1388 2137 796 2137 1386 2138 796 2138 792 2138 1398 2139 716 2139 1408 2139 1399 2140 717 2140 712 2140 1400 2141 1401 2141 717 2141 795 2142 1401 2142 1403 2142 795 2143 798 2143 1401 2143 1403 2144 1405 2144 795 2144 795 2145 1405 2145 794 2145 1405 2146 1406 2146 786 2146 1406 2147 1408 2147 788 2147 1418 2148 782 2148 1428 2148 719 2149 782 2149 1418 2149 1418 2150 1419 2150 719 2150 1420 2151 1421 2151 715 2151 787 2152 1425 2152 785 2152 1425 2153 780 2153 785 2153 775 2154 1448 2154 725 2154 1438 2155 722 2155 725 2155 1439 2156 720 2156 722 2156 781 2157 1441 2157 1443 2157 1443 2158 1445 2158 781 2158 781 2159 1445 2159 776 2159 1446 2160 775 2160 774 2160 1458 2161 730 2161 1468 2161 1468 2162 730 2162 823 2162 1458 2163 1459 2163 727 2163 1459 2164 1460 2164 723 2164 724 2165 1463 2165 817 2165 724 2166 1461 2166 1463 2166 1463 2167 1465 2167 772 2167 764 2168 1468 2168 823 2168 1466 2169 1468 2169 764 2169 819 2170 1488 2170 821 2170 1478 2171 1479 2171 733 2171 1479 2172 728 2172 733 2172 1480 2173 729 2173 728 2173 729 2174 1483 2174 822 2174 1483 2175 1485 2175 763 2175 1485 2176 1486 2176 760 2176 1485 2177 760 2177 763 2177 1498 2178 756 2178 1508 2178 739 2179 824 2179 756 2179 1500 2180 1501 2180 820 2180 1500 2181 820 2181 740 2181 820 2182 1501 2182 1503 2182 818 2183 1505 2183 769 2183 1506 2184 1508 2184 756 2184 1506 2185 756 2185 755 2185 1516 2186 747 2186 748 2186 747 2187 1517 2187 742 2187 1517 2188 1519 2188 737 2188 1517 2189 737 2189 742 2189 1519 2190 738 2190 737 2190 824 2191 1523 2191 754 2191 1525 2192 1526 2192 751 2192 351 2193 1750 2193 2065 2193 2008 2194 342 2194 2064 2194 665 2195 330 2195 2060 2195 2013 2196 1718 2196 2049 2196 1991 2197 2050 2197 1660 2197 1660 2198 1715 2198 1991 2198 1661 2199 2051 2199 1714 2199 2016 2200 1713 2200 2055 2200 1666 2201 2057 2201 2058 2201 2068 2202 1708 2202 1704 2202 1575 2203 614 2203 679 2203 298 2204 356 2204 618 2204 2022 2205 244 2205 2038 2205 244 2206 243 2206 2038 2206 2038 2207 243 2207 741 2207 260 2208 2041 2208 314 2208 260 2209 2040 2209 2041 2209 311 2210 310 2210 2043 2210 339 2211 336 2211 2064 2211 282 2212 321 2212 2044 2212 2044 2213 321 2213 2026 2213 282 2214 2044 2214 280 2214 283 2215 657 2215 305 2215 662 2216 1740 2216 332 2216 2046 2217 1723 2217 1720 2217 779 2218 1723 2218 2046 2218 1648 2219 1729 2219 1684 2219 1696 2220 1697 2220 2049 2220 2049 2221 1697 2221 2047 2221 1644 2222 1735 2222 1690 2222 758 2223 1642 2223 1693 2223 1704 2224 1705 2224 2068 2224 2068 2225 1705 2225 2067 2225 456 2226 1294 2226 433 2226 1276 2227 2072 2227 2071 2227 1276 2228 1277 2228 2072 2228 523 2229 1284 2229 1285 2229 522 2230 1285 2230 1286 2230 521 2231 1286 2231 1268 2231 518 2232 1275 2232 1276 2232 517 2233 518 2233 1276 2233 518 2234 519 2234 1275 2234 521 2235 522 2235 1286 2235 523 2236 2075 2236 1284 2236 2075 2237 2074 2237 1284 2237 2074 2238 2073 2238 1278 2238 2073 2239 2072 2239 1277 2239 504 2240 1206 2240 506 2240 1159 2241 1206 2241 1205 2241 1157 2242 1205 2242 1210 2242 1149 2243 490 2243 1213 2243 1145 2244 1213 2244 1214 2244 1135 2245 1230 2245 1227 2245 1129 2246 1227 2246 1192 2246 1127 2247 1192 2247 1193 2247 1127 2248 1193 2248 1267 2248 1123 2249 1267 2249 471 2249 1197 2250 1171 2250 1173 2250 1197 2251 1200 2251 1171 2251 1171 2252 1200 2252 1167 2252 1169 2253 1171 2253 1167 2253 1155 2254 1210 2254 1153 2254 1151 2255 1153 2255 1149 2255 1153 2256 490 2256 1149 2256 1149 2257 1213 2257 1147 2257 1145 2258 1214 2258 1143 2258 1141 2259 1137 2259 1139 2259 1133 2260 1227 2260 1129 2260 1129 2261 1192 2261 1127 2261 1127 2262 1267 2262 1125 2262 1125 2263 1267 2263 1123 2263 1121 2264 471 2264 1119 2264 1175 2265 1119 2265 1173 2265 1119 2266 1197 2266 1173 2266 1200 2267 500 2267 1165 2267 1227 2268 1133 2268 1135 2268 1228 2269 1089 2269 1088 2269 1229 2270 1093 2270 1091 2270 1229 53 1231 53 1093 53 1093 2271 1231 2271 2074 2271 2075 53 523 53 1093 53 1088 2272 2072 2272 1228 2272 1088 2273 2071 2273 2072 2273 1088 2274 517 2274 2071 2274 2074 2275 1233 2275 2073 2275 2073 2276 1233 2276 2072 2276 2080 2277 2081 2277 2082 2277 2084 2278 2081 2278 2086 2278 2091 53 2089 53 2079 53 2092 53 2078 53 2093 53 2092 2279 2088 2279 2078 2279 2078 2280 2079 2280 2093 2280 2093 53 2079 53 2090 53 2094 2281 2096 2281 2097 2281 2095 2282 2099 2282 2100 2282 2098 2283 2101 2283 2099 2283 2101 2284 2095 2284 2094 2284 2103 2285 2104 2285 2105 2285 2103 2286 2105 2286 2106 2286 2106 2287 2105 2287 2107 2287 2107 2288 2105 2288 2108 2288 2109 2289 2108 2289 2104 2289 2113 2290 2114 2290 2115 2290 2116 2291 2103 2291 2106 2291 2117 2292 2103 2292 2116 2292 2118 2293 2119 2293 2120 2293 2124 2294 2123 2294 2125 2294 2126 2295 2125 2295 2127 2295 2127 2296 2129 2296 2128 2296 2115 2297 2119 2297 2118 2297 2118 2298 2120 2298 2130 2298 2131 2299 2118 2299 2130 2299 2134 2300 2135 2300 2136 2300 2134 2301 2137 2301 2130 2301 2139 2302 2140 2302 2141 2302 2145 2303 2121 2303 2146 2303 2145 2304 2147 2304 2122 2304 2121 2305 2123 2305 2124 2305 2148 2306 2149 2306 2121 2306 2126 2307 2150 2307 2124 2307 2149 2308 2146 2308 2121 2308 2147 2309 2143 2309 2122 2309 2140 2310 2153 2310 2154 2310 2141 2311 2140 2311 2154 2311 2140 2312 2139 2312 2135 2312 2137 2313 2156 2313 2130 2313 2133 2314 2113 2314 2118 2314 2115 2315 2157 2315 2158 2315 2159 2316 2157 2316 2114 2316 2159 2317 2160 2317 2157 2317 2157 2318 2160 2318 2161 2318 2163 2319 2162 2319 2164 2319 2165 2320 2156 2320 2164 2320 2161 2321 2160 2321 2167 2321 2167 2322 2168 2322 2131 2322 2163 53 2169 53 2157 53 2157 2323 2169 2323 2170 2323 2171 53 2157 53 2170 53 2171 2324 2172 2324 2157 2324 2173 2325 2171 2325 2174 2325 2175 2326 2174 2326 2155 2326 2170 2327 2169 2327 2176 2327 2173 2328 2174 2328 2175 2328 2172 53 2178 53 2157 53 2157 2329 2178 2329 2179 2329 2181 53 2180 53 2182 53 2184 2330 2183 2330 2154 2330 2186 2331 2185 2331 2139 2331 2139 2332 2141 2332 2186 2332 2182 2333 2183 2333 2184 2333 2157 53 2181 53 2187 53 2187 53 2181 53 2188 53 2189 2334 2188 2334 2190 2334 2191 2335 2190 2335 2144 2335 2187 2336 2188 2336 2189 2336 2192 2337 2187 2337 2189 2337 2194 2338 2192 2338 2195 2338 2195 2339 2196 2339 2194 2339 2187 2340 2197 2340 2198 2340 2199 53 2187 53 2198 53 2199 2341 2200 2341 2187 2341 2200 2342 2201 2342 2202 2342 2202 2343 2201 2343 2149 2343 2203 2344 2205 2344 2204 2344 2204 2345 2205 2345 2146 2345 2202 2346 2149 2346 2148 2346 2200 2347 2206 2347 2187 2347 2208 2348 2187 2348 2207 2348 2151 2349 2209 2349 2210 2349 2207 2350 2206 2350 2211 2350 2212 53 2211 53 2213 53 2213 2351 2211 2351 2214 2351 2214 2352 2124 2352 2150 2352 2213 2353 2214 2353 2150 2353 2209 2354 2151 2354 2152 2354 2216 2355 2219 2355 2217 2355 2221 2356 2219 2356 2222 2356 2226 2357 2224 2357 2227 2357 2229 2358 2230 2358 2228 2358 2230 2359 2231 2359 2228 2359 2230 2360 2227 2360 2231 2360 2227 2361 2224 2361 2223 2361 2227 2362 2230 2362 2232 2362 2230 2363 2229 2363 2233 2363 2235 2364 2234 2364 2229 2364 2223 2365 2228 2365 2227 2365 2227 2366 2228 2366 2231 2366 2241 2367 2243 2367 2242 2367 2241 2368 2245 2368 2243 2368 2244 2369 2247 2369 2246 2369 2246 2370 2248 2370 2245 2370 2245 2371 2248 2371 2249 2371 2246 2372 2247 2372 2248 2372 2247 2373 2237 2373 2250 2373 2250 2374 2237 2374 2251 2374 2237 2375 2236 2375 2251 2375 2253 2376 2254 2376 2255 2376 2256 2377 2257 2377 2255 2377 2258 2378 2254 2378 2253 2378 2258 2379 2259 2379 2260 2379 2258 2380 2260 2380 2254 2380 2259 2381 2261 2381 2262 2381 2253 2382 2263 2382 2258 2382 2261 2383 2258 2383 2263 2383 2264 2384 2253 2384 2255 2384 2263 2385 2253 2385 2264 2385 2271 2386 2265 2386 2272 2386 2265 2387 2267 2387 2272 2387 2268 2388 2273 2388 2269 2388 2273 2389 2267 2389 2266 2389 2275 2390 2265 2390 2276 2390 2276 2391 2265 2391 2271 2391 2277 2392 2276 2392 2271 2392 2267 2393 2273 2393 2272 2393 2272 2394 2273 2394 2268 2394 2279 2395 2281 2395 2282 2395 2279 2396 2283 2396 2280 2396 2281 2397 2289 2397 2287 2397 2289 2398 2281 2398 2290 2398 2290 2399 2281 2399 2291 2399 2283 2400 2282 2400 2284 2400 2296 2401 2297 2401 2298 2401 2299 2402 2269 2402 2300 2402 2274 2403 2273 2403 2266 2403 2302 2404 2303 2404 2220 2404 2307 2405 2286 2405 2308 2405 2308 2406 2286 2406 2285 2406 2309 2407 2308 2407 2285 2407 2284 2408 2309 2408 2285 2408 2309 2409 2284 2409 2287 2409 2288 2410 2309 2410 2287 2410 2306 2411 2305 2411 2312 2411 2313 2412 2298 2412 2293 2412 2115 2413 2158 2413 2314 2413 2115 2414 2295 2414 2294 2414 2317 2415 2318 2415 2315 2415 2319 2416 2320 2416 2316 2416 2319 2417 2316 2417 2321 2417 2329 2418 2330 2418 2331 2418 2332 2419 2333 2419 2334 2419 2338 2420 2339 2420 2340 2420 2341 2421 2342 2421 2343 2421 2343 2422 2344 2422 2341 2422 2345 2423 2346 2423 2347 2423 2353 2424 2354 2424 2355 2424 2353 2425 2355 2425 2356 2425 2358 2426 2359 2426 2360 2426 2359 2427 2361 2427 2360 2427 2361 2428 2363 2428 2364 2428 2368 2429 2366 2429 2369 2429 2368 2430 2370 2430 2366 2430 2370 2431 2356 2431 2366 2431 2367 53 2355 53 2371 53 2354 2432 2358 2432 2374 2432 2374 2433 2358 2433 2375 2433 2376 2434 2360 2434 2377 2434 2376 2435 2375 2435 2360 2435 2365 584 2377 584 2360 584 2382 2436 2381 2436 2383 2436 2385 2437 2388 2437 2386 2437 2392 2438 2391 2438 2393 2438 2399 53 2397 53 2400 53 2403 53 2402 53 2404 53 2405 53 2400 53 2401 53 2406 53 2402 53 2407 53 2387 2439 2411 2439 2409 2439 2410 2440 2412 2440 2387 2440 2387 2441 2412 2441 2408 2441 2417 2442 2418 2442 2415 2442 2420 2443 2421 2443 2417 2443 2423 53 2421 53 2420 53 2425 53 2420 53 2426 53 2409 2444 2425 2444 2426 2444 2423 53 2420 53 2425 53 2427 2445 2428 2445 2430 2445 2417 2446 2431 2446 2420 2446 2433 2447 2434 2447 2432 2447 2410 2448 2429 2448 2436 2448 2431 2449 2436 2449 2426 2449 2437 2450 2436 2450 2431 2450 2437 2451 2433 2451 2436 2451 2412 2452 2410 2452 2436 2452 2408 2453 2412 2453 2432 2453 2404 2454 2406 2454 2435 2454 2417 2455 2415 2455 2437 2455 2431 2456 2417 2456 2437 2456 2433 2457 2437 2457 2415 2457 2433 2458 2419 2458 2435 2458 2433 2459 2415 2459 2419 2459 2438 2460 2419 2460 2416 2460 2438 2461 2435 2461 2419 2461 2403 2462 2438 2462 2439 2462 2439 2463 2438 2463 2416 2463 2440 2464 2416 2464 2441 2464 2447 2465 2444 2465 2443 2465 2448 2466 2447 2466 2449 2466 2427 2467 2430 2467 2450 2467 2449 2468 2450 2468 2430 2468 2450 2469 2449 2469 2447 2469 2447 2470 2443 2470 2450 2470 2444 2471 2448 2471 2451 2471 2451 2472 2445 2472 2444 2472 2428 2473 2409 2473 2452 2473 2451 2474 2428 2474 2452 2474 2411 2475 2452 2475 2409 2475 2450 2476 2454 2476 2427 2476 2380 2477 2454 2477 2455 2477 2257 2478 2461 2478 2462 2478 2462 2479 2463 2479 2464 2479 2463 2480 2462 2480 2465 2480 2465 2481 2461 2481 2466 2481 2467 2482 2469 2482 2468 2482 2469 2483 2470 2483 2471 2483 2473 2484 2471 2484 2472 2484 2477 2485 2478 2485 2474 2485 2482 2486 2483 2486 2484 2486 2486 2487 2485 2487 2487 2487 2488 2488 2490 2488 2491 2488 2488 2489 2492 2489 2490 2489 2490 2490 2492 2490 2493 2490 2493 2491 2492 2491 2497 2491 2100 2492 2499 2492 2500 2492 2493 2493 2501 2493 2494 2493 2491 2494 2502 2494 2503 2494 2491 2495 2503 2495 2504 2495 2489 2496 2488 2496 2505 2496 2476 2497 2518 2497 2519 2497 2469 2498 2520 2498 2521 2498 2263 2499 2264 2499 2468 2499 2468 2500 2522 2500 2263 2500 2461 2501 2262 2501 2523 2501 2525 2502 2234 2502 2235 2502 2525 2503 2235 2503 2459 2503 2233 2504 2524 2504 2232 2504 2256 2505 2259 2505 2257 2505 2257 2506 2259 2506 2461 2506 2522 2507 2526 2507 2261 2507 2522 2508 2261 2508 2263 2508 2264 2509 2255 2509 2257 2509 2461 2510 2259 2510 2262 2510 2460 2511 2527 2511 2528 2511 2466 2512 2531 2512 2530 2512 2466 2513 2461 2513 2523 2513 2523 2514 2532 2514 2531 2514 2523 2515 2526 2515 2532 2515 2532 2516 2526 2516 2533 2516 2532 2517 2533 2517 2534 2517 2526 2518 2522 2518 2536 2518 2542 2519 2541 2519 2545 2519 2546 2520 2545 2520 2547 2520 2548 2521 2549 2521 2550 2521 2549 2522 2551 2522 2550 2522 2553 2523 2555 2523 2556 2523 2547 2524 2545 2524 2558 2524 2559 2525 2558 2525 2560 2525 2561 2526 2560 2526 2562 2526 2561 2527 2562 2527 2563 2527 2561 2528 2563 2528 2564 2528 2574 2529 2571 2529 2573 2529 2576 2530 2575 2530 2508 2530 2579 2531 2576 2531 2578 2531 2581 2532 2580 2532 2582 2532 2583 2533 2582 2533 2584 2533 2583 2534 2584 2534 2585 2534 2583 2535 2585 2535 2586 2535 2589 2536 2100 2536 2500 2536 2590 2537 2591 2537 2594 2537 2595 2538 2590 2538 2594 2538 2597 2539 2596 2539 2598 2539 2599 2540 2600 2540 2601 2540 2599 2541 2598 2541 2600 2541 2600 2542 2605 2542 2291 2542 2608 2543 2607 2543 2609 2543 2610 2544 2611 2544 2609 2544 2613 2545 2614 2545 2610 2545 2607 2546 2615 2546 2616 2546 2620 2547 2621 2547 2622 2547 2620 2548 2622 2548 2623 2548 2622 2549 2621 2549 2626 2549 2626 2550 2621 2550 2627 2550 2626 2551 2627 2551 2630 2551 2626 2552 2630 2552 2631 2552 2632 2553 2633 2553 2631 2553 2630 2554 2627 2554 2634 2554 2635 2555 2634 2555 2636 2555 2635 2556 2636 2556 2637 2556 2634 2557 2639 2557 2640 2557 2636 2558 2634 2558 2641 2558 2642 2559 2641 2559 2643 2559 2554 2560 2551 2560 2552 2560 2644 2561 2645 2561 2641 2561 2646 2562 2641 2562 2642 2562 2650 2563 2649 2563 2559 2563 2555 2564 2653 2564 2654 2564 2556 2565 2555 2565 2655 2565 2658 2566 2525 2566 2460 2566 2528 2567 2658 2567 2460 2567 2655 2568 2656 2568 2657 2568 2525 2569 2659 2569 2234 2569 2657 2570 2662 2570 2655 2570 2538 2571 2663 2571 2664 2571 2538 2572 2533 2572 2536 2572 2536 2573 2533 2573 2526 2573 2535 2574 2534 2574 2665 2574 2535 2575 2665 2575 2658 2575 2548 2576 2546 2576 2547 2576 2544 2577 2543 2577 2666 2577 2557 2578 2666 2578 2553 2578 2566 2579 2650 2579 2559 2579 2647 2580 2646 2580 2642 2580 2608 2581 2669 2581 2617 2581 2588 2582 2670 2582 2581 2582 2672 2583 2673 2583 2579 2583 2590 2584 2585 2584 2584 2584 2671 2585 2668 2585 2669 2585 2576 2586 2572 2586 2575 2586 2568 2587 2563 2587 2562 2587 2635 2588 2630 2588 2634 2588 2566 2589 2559 2589 2560 2589 2662 2590 2663 2590 2661 2590 2675 2591 2676 2591 2677 2591 2678 2592 2680 2592 2684 2592 2681 2593 2678 2593 2684 2593 2684 2594 2680 2594 2685 2594 2686 2595 2676 2595 2675 2595 2687 2596 2675 2596 2688 2596 2675 2597 2677 2597 2688 2597 2687 2598 2686 2598 2675 2598 2689 2599 2677 2599 2690 2599 2691 2600 2452 2600 2692 2600 2692 2601 2452 2601 2453 2601 2697 2602 2698 2602 2699 2602 2701 2603 2702 2603 2703 2603 2705 2604 2706 2604 2707 2604 2711 2605 2710 2605 2712 2605 2713 2606 2714 2606 2715 2606 2719 2607 2718 2607 2720 2607 2725 2608 2726 2608 2727 2608 2727 2609 2726 2609 2728 2609 2739 2607 2738 2607 2740 2607 2454 2610 2742 2610 2455 2610 2747 2611 2748 2611 2749 2611 2749 2612 2748 2612 2750 2612 2753 2613 2752 2613 2754 2613 2759 2614 2760 2614 2761 2614 2781 2615 2780 2615 2782 2615 2090 2616 2788 2616 2789 2616 2792 2617 2791 2617 2793 2617 2796 53 2368 53 2797 53 2797 53 2368 53 2798 53 2794 53 2799 53 2795 53 2093 2618 2800 2618 2092 2618 2791 2619 2790 2619 2801 2619 2803 2620 2802 2620 2080 2620 2080 2621 2802 2621 2790 2621 2738 53 2080 53 2790 53 2738 53 2804 53 2081 53 2081 2622 2804 2622 2086 2622 2082 2623 2085 2623 2080 2623 2077 53 2087 53 2805 53 2079 2624 2805 2624 2091 2624 2737 2625 2807 2625 2738 2625 2739 53 2809 53 2737 53 2737 53 2809 53 2807 53 2739 2626 2740 2626 2809 2626 2740 2627 2734 2627 2811 2627 2783 2628 2785 2628 2814 2628 2784 53 2814 53 2816 53 2735 53 2817 53 2733 53 2784 2629 2816 2629 2786 2629 2781 53 2786 53 2820 53 2819 2630 2730 2630 2821 2630 2779 2631 2781 2631 2822 2631 2822 2632 2781 2632 2820 2632 2729 2633 2823 2633 2730 2633 2730 2634 2823 2634 2821 2634 2780 2635 2822 2635 2824 2635 2731 53 2825 53 2729 53 2782 2636 2824 2636 2826 2636 2731 2637 2732 2637 2825 2637 2825 2638 2732 2638 2827 2638 2777 53 2782 53 2828 53 2828 2639 2782 2639 2826 2639 2830 2640 2777 2640 2828 2640 2725 2641 2831 2641 2726 2641 2726 2634 2831 2634 2829 2634 2775 53 2830 53 2776 53 2776 53 2830 53 2832 53 2725 2642 2833 2642 2831 2642 2776 2643 2832 2643 2778 2643 2778 2644 2832 2644 2834 2644 2836 2645 2778 2645 2834 2645 2728 2646 2722 2646 2835 2646 2835 2647 2722 2647 2837 2647 2838 2648 2773 2648 2836 2648 2771 2649 2838 2649 2772 2649 2772 2650 2838 2650 2840 2650 2723 53 2841 53 2721 53 2841 2651 2724 2651 2843 2651 2769 53 2774 53 2844 53 2844 2652 2774 2652 2842 2652 2724 2653 2718 2653 2843 2653 2843 2654 2718 2654 2845 2654 2846 2632 2769 2632 2844 2632 2717 2655 2847 2655 2718 2655 2718 2656 2847 2656 2845 2656 2719 2657 2720 2657 2849 2657 2849 2658 2720 2658 2851 2658 2765 2659 2770 2659 2852 2659 2763 2660 2765 2660 2854 2660 2854 2648 2765 2648 2852 2648 2714 2661 2855 2661 2853 2661 2763 53 2854 53 2764 53 2764 53 2854 53 2856 53 2715 53 2857 53 2713 53 2764 2662 2856 2662 2766 2662 2715 2663 2716 2663 2857 2663 2857 2664 2716 2664 2859 2664 2716 2665 2710 2665 2859 2665 2859 2647 2710 2647 2861 2647 2759 2666 2761 2666 2862 2666 2862 2667 2761 2667 2860 2667 2759 53 2862 53 2760 53 2709 53 2865 53 2863 53 2865 2668 2712 2668 2867 2668 2757 53 2762 53 2868 53 2712 2669 2706 2669 2867 2669 2867 2670 2706 2670 2869 2670 2755 2671 2757 2671 2870 2671 2870 2672 2757 2672 2868 2672 2705 2673 2871 2673 2706 2673 2755 53 2870 53 2756 53 2707 53 2873 53 2705 53 2756 2674 2872 2674 2758 2674 2758 2675 2872 2675 2874 2675 2876 2676 2758 2676 2874 2676 2878 2677 2753 2677 2876 2677 2702 2678 2879 2678 2877 2678 2751 53 2878 53 2752 53 2752 2679 2878 2679 2880 2679 2749 53 2754 53 2884 53 2704 2680 2698 2680 2883 2680 2886 2681 2749 2681 2884 2681 2697 2682 2887 2682 2698 2682 2747 2683 2886 2683 2748 2683 2699 53 2889 53 2697 53 2697 53 2889 53 2887 53 2699 2684 2700 2684 2889 2684 2745 53 2750 53 2892 53 2891 2685 2694 2685 2893 2685 2693 2686 2895 2686 2694 2686 2743 53 2894 53 2744 53 2744 53 2894 53 2896 53 2742 881 2898 881 2455 881 2455 2687 2898 2687 2380 2687 2900 2688 2899 2688 2411 2688 2695 2689 2696 2689 2897 2689 2897 2690 2696 2690 2902 2690 2898 2691 2741 2691 2903 2691 2692 2666 2899 2666 2691 2666 2691 2692 2899 2692 2904 2692 2903 2693 2746 2693 2901 2693 2445 53 2905 53 2446 53 2445 2694 2906 2694 2905 2694 2905 53 2907 53 2446 53 2446 2695 2907 2695 2908 2695 2792 2696 2906 2696 2790 2696 2740 2697 2906 2697 2734 2697 2734 2698 2906 2698 2736 2698 2736 2699 2906 2699 2730 2699 2732 2700 2906 2700 2726 2700 2726 2701 2906 2701 2728 2701 2728 2702 2906 2702 2445 2702 2722 2703 2445 2703 2724 2703 2700 2704 2445 2704 2694 2704 2700 2705 2698 2705 2445 2705 2445 2706 2698 2706 2704 2706 2702 2707 2708 2707 2445 2707 2445 2708 2708 2708 2706 2708 2712 2709 2445 2709 2706 2709 2712 2710 2710 2710 2445 2710 2445 2711 2720 2711 2718 2711 2724 2712 2445 2712 2718 2712 2694 2713 2451 2713 2696 2713 2370 2714 2368 2714 2908 2714 2908 2715 2368 2715 2796 2715 2908 2716 2090 2716 2789 2716 2785 2717 2908 2717 2789 2717 2785 2718 2786 2718 2908 2718 2908 2719 2786 2719 2781 2719 2782 2718 2908 2718 2781 2718 2908 2720 2777 2720 2778 2720 2774 2721 2446 2721 2773 2721 2774 2722 2769 2722 2446 2722 2765 2723 2446 2723 2770 2723 2765 2724 2766 2724 2446 2724 2446 2725 2757 2725 2758 2725 2753 2726 2446 2726 2758 2726 2753 2727 2754 2727 2446 2727 2446 2728 2754 2728 2749 2728 2750 2729 2446 2729 2749 2729 2446 2730 2745 2730 2450 2730 2908 2731 2778 2731 2446 2731 2745 2732 2746 2732 2450 2732 2454 2733 2450 2733 2741 2733 2369 2734 2911 2734 2368 2734 2364 2735 2909 2735 2302 2735 2912 2736 2914 2736 2913 2736 2367 2737 2313 2737 2366 2737 2313 2738 2914 2738 2296 2738 2296 2739 2914 2739 2915 2739 2296 2740 2915 2740 2297 2740 2921 2741 2922 2741 2923 2741 2922 2742 2921 2742 2331 2742 2324 2743 2924 2743 2922 2743 2324 2744 2925 2744 2924 2744 2327 2745 2925 2745 2324 2745 2928 2746 2927 2746 2322 2746 2322 2747 2930 2747 2929 2747 2929 2748 2930 2748 2931 2748 2931 2749 2930 2749 2932 2749 2931 2750 2932 2750 2933 2750 2935 2751 2933 2751 2936 2751 2937 2752 2935 2752 2936 2752 2937 2753 2938 2753 2935 2753 2940 2754 2939 2754 2941 2754 2942 2755 2940 2755 2941 2755 2942 2756 2943 2756 2940 2756 2945 2757 2686 2757 2689 2757 2687 2758 2689 2758 2686 2758 2685 2759 2934 2759 2682 2759 2685 2760 2682 2760 2681 2760 2931 2761 2933 2761 2935 2761 2943 2762 2944 2762 2946 2762 2950 2763 2949 2763 2951 2763 2953 2764 2952 2764 2336 2764 2953 2765 2954 2765 2952 2765 2953 2766 2955 2766 2954 2766 2955 2767 2953 2767 2334 2767 2344 2768 2343 2768 2956 2768 2958 2769 2957 2769 2340 2769 2958 2770 2349 2770 2959 2770 2960 2771 2959 2771 2349 2771 2960 2772 2961 2772 2304 2772 2304 2773 2961 2773 2962 2773 2365 2774 2963 2774 2964 2774 2365 2775 2361 2775 2963 2775 2946 2776 2947 2776 2948 2776 2962 2777 2965 2777 2964 2777 2964 2778 2965 2778 2676 2778 2690 2779 2676 2779 2965 2779 2676 2780 2690 2780 2677 2780 2963 2781 2361 2781 2311 2781 2304 2782 2963 2782 2311 2782 2966 2783 2918 2783 2920 2783 2967 2784 2968 2784 2969 2784 2978 2785 2977 2785 2979 2785 2982 2786 2981 2786 2983 2786 2984 2787 2983 2787 2985 2787 2986 2788 2985 2788 2987 2788 2994 2789 2993 2789 2995 2789 2996 2790 2995 2790 2997 2790 3000 2791 2999 2791 3001 2791 3002 2792 3001 2792 3003 2792 3006 2793 3005 2793 3007 2793 2362 2794 3009 2794 3010 2794 2905 2795 3011 2795 2907 2795 2905 2796 2906 2796 3011 2796 2976 2797 2977 2797 2978 2797 2982 2798 2983 2798 2984 2798 2986 2799 2987 2799 2988 2799 2994 2800 2995 2800 2996 2800 3000 2801 3001 2801 3002 2801 3006 2802 3007 2802 3008 2802 2359 2803 3008 2803 2362 2803 2362 2804 3010 2804 2906 2804 2908 2805 3012 2805 3013 2805 2370 2806 3013 2806 3014 2806 3016 2807 3017 2807 3018 2807 3020 2808 3021 2808 3022 2808 2370 2809 2908 2809 3013 2809 3025 2810 2682 2810 2934 2810 3026 2811 2683 2811 3027 2811 3029 2812 2965 2812 2945 2812 3028 2813 2689 2813 2690 2813 3029 2814 3028 2814 2690 2814 3028 2815 3029 2815 2945 2815 2329 2816 3030 2816 3031 2816 3031 2817 3032 2817 3033 2817 3034 2818 3035 2818 3036 2818 3031 2819 3033 2819 3034 2819 3045 2820 3044 2820 3041 2820 3047 2821 3048 2821 3043 2821 3047 2822 3046 2822 3048 2822 3043 2823 3033 2823 3040 2823 3043 2824 3040 2824 3041 2824 3030 2825 2329 2825 2325 2825 3036 2826 3038 2826 3050 2826 2325 2827 2329 2827 3051 2827 3048 2828 3035 2828 3043 2828 3043 2829 3035 2829 3033 2829 3037 2830 3039 2830 3038 2830 2332 2831 3052 2831 3053 2831 3054 2832 3053 2832 3055 2832 2335 2833 2337 2833 3056 2833 3053 2834 2338 2834 2348 2834 2348 2835 2351 2835 3053 2835 3053 2836 2351 2836 3055 2836 3060 2837 3057 2837 3059 2837 2342 2838 3063 2838 3064 2838 3065 2839 3066 2839 3067 2839 3062 2840 3061 2840 2342 2840 3064 2841 3066 2841 3065 2841 2351 2842 3069 2842 3055 2842 3072 2843 3073 2843 3071 2843 3072 2844 3071 2844 3074 2844 3073 2845 3056 2845 3071 2845 3074 2846 3058 2846 2357 2846 3059 2847 3058 2847 3074 2847 3070 2848 3075 2848 3059 2848 3059 2849 3075 2849 3060 2849 2345 2850 3060 2850 2351 2850 3056 2851 3072 2851 3068 2851 3078 2852 3077 2852 3079 2852 3081 2853 3080 2853 3082 2853 3083 2854 3082 2854 3076 2854 3079 2855 3080 2855 3081 2855 2921 2856 2919 2856 3050 2856 2328 2857 2327 2857 2324 2857 2324 2858 3030 2858 2325 2858 3030 2859 3032 2859 3031 2859 2336 2860 2335 2860 3066 2860 2334 2861 2953 2861 2332 2861 2953 2862 2336 2862 3066 2862 2333 2863 3054 2863 3085 2863 2343 2864 2342 2864 2340 2864 2339 2865 2338 2865 3053 2865 2339 2866 3053 2866 3052 2866 3086 2867 2960 2867 2349 2867 3086 2868 2349 2868 3061 2868 2351 2869 2348 2869 2350 2869 2352 2870 2346 2870 2345 2870 3087 2871 2318 2871 2322 2871 2342 2872 3061 2872 2338 2872 3057 2873 3060 2873 2345 2873 3052 2874 2332 2874 2341 2874 2341 2875 2332 2875 3063 2875 3063 2876 2332 2876 3064 2876 3063 2877 2342 2877 2341 2877 2965 2878 3088 2878 2945 2878 2965 2879 2352 2879 3088 2879 2965 2880 2962 2880 2352 2880 3088 2881 2352 2881 3089 2881 2339 2882 2350 2882 2349 2882 3085 2883 2339 2883 3052 2883 3089 2884 3085 2884 3090 2884 2336 2885 3090 2885 3085 2885 3090 2886 2336 2886 2951 2886 3091 2887 2947 2887 2944 2887 2944 2888 2945 2888 3091 2888 3091 2889 2945 2889 3088 2889 2319 2890 3092 2890 3087 2890 2934 2891 3095 2891 2912 2891 2317 2892 2932 2892 2930 2892 3096 2893 2317 2893 2316 2893 2326 2894 2316 2894 2320 2894 2326 2895 2320 2895 2327 2895 3084 2896 2326 2896 3030 2896 2919 2897 3097 2897 3084 2897 2914 2898 2912 2898 3098 2898 3098 2899 2912 2899 3095 2899 3099 2900 3100 2900 3097 2900 3098 2901 3102 2901 3103 2901 2915 2902 3103 2902 3104 2902 3096 2903 3101 2903 3095 2903 3098 2904 3103 2904 2915 2904 2915 2905 3104 2905 2916 2905 2916 2906 3099 2906 3097 2906 3101 2907 3105 2907 3107 2907 3102 2908 3108 2908 3103 2908 3103 2909 3108 2909 3109 2909 3103 2910 3109 2910 3104 2910 3104 2911 3106 2911 3099 2911 3110 2912 3111 2912 3091 2912 2947 2913 3111 2913 3112 2913 3090 2914 3112 2914 3113 2914 3089 2915 3113 2915 3114 2915 2949 2916 3112 2916 3090 2916 3112 2917 3115 2917 3117 2917 3112 2918 3117 2918 3118 2918 3113 2919 3112 2919 3118 2919 3113 2920 3118 2920 3119 2920 3114 2921 3119 2921 3116 2921 3114 2922 3116 2922 3110 2922 3041 2923 3040 2923 3094 2923 3094 2924 3040 2924 2315 2924 3045 2925 3093 2925 3044 2925 3044 2926 3093 2926 3120 2926 3120 2927 3093 2927 3087 2927 3120 2928 3087 2928 3092 2928 3049 2929 3050 2929 3038 2929 3120 2930 3092 2930 2323 2930 3051 2931 3050 2931 3049 2931 3072 2932 3067 2932 3068 2932 2353 2933 3121 2933 2357 2933 3049 2934 3125 2934 3124 2934 3047 2935 3043 2935 3126 2935 3122 2936 3127 2936 3128 2936 3122 2937 3123 2937 3127 2937 3125 2938 3039 2938 3126 2938 3128 2939 3043 2939 3042 2939 3129 2940 3128 2940 3042 2940 3042 2941 3044 2941 3129 2941 3076 2942 3044 2942 3077 2942 3133 2943 2986 2943 3072 2943 3072 2944 3134 2944 3133 2944 3135 2945 3074 2945 3136 2945 3137 2946 3074 2946 3138 2946 2353 2947 3124 2947 3123 2947 3106 2948 3109 2948 3125 2948 3125 2949 3109 2949 3124 2949 3127 2950 3108 2950 3107 2950 3125 2951 3126 2951 3106 2951 3123 2952 3108 2952 3127 2952 3136 2953 3119 2953 3135 2953 3133 2954 3118 2954 3117 2954 3136 2955 3115 2955 3116 2955 3134 2956 3118 2956 3133 2956 3132 2957 3115 2957 3136 2957 2367 2958 2371 2958 2913 2958 2365 2959 2964 2959 2377 2959 2793 2960 3141 2960 2792 2960 2215 2961 2891 2961 2893 2961 2902 2962 2215 2962 2893 2962 2902 2963 2904 2963 2215 2963 2215 2964 2904 2964 3142 2964 2885 2965 2891 2965 2215 2965 2217 2966 2843 2966 2215 2966 2217 2967 2837 2967 2843 2967 2217 2968 2835 2968 2837 2968 2217 2969 2819 2969 2821 2969 2217 2970 2813 2970 2819 2970 2217 2971 2802 2971 2803 2971 2217 2972 3140 2972 2802 2972 2843 2973 2845 2973 2215 2973 2853 2974 2859 2974 2215 2974 2859 2975 2861 2975 2215 2975 2869 2976 2215 2976 2867 2976 2869 2977 2875 2977 2215 2977 2883 2978 2885 2978 2215 2978 2903 2979 3143 2979 2898 2979 2295 2980 2798 2980 2911 2980 2878 2981 2876 2981 2880 2981 2880 2982 2876 2982 2882 2982 2874 2983 2872 2983 2868 2983 2864 2984 2860 2984 2866 2984 2858 2985 2856 2985 2852 2985 2846 2986 2844 2986 2848 2986 2836 2987 2840 2987 2838 2987 2830 2988 2828 2988 2832 2988 2826 2989 2824 2989 2820 2989 2816 2990 2812 2990 2818 2990 2089 2991 2808 2991 2806 2991 2087 2992 2088 2992 2805 2992 2894 2993 2892 2993 2896 2993 2896 2994 2892 2994 2901 2994 3142 2995 2899 2995 2900 2995 2302 2996 2909 2996 2303 2996 2877 2997 2881 2997 2883 2997 2875 2998 2869 2998 2873 2998 2873 2999 2869 2999 2871 2999 2863 3000 2865 3000 2861 3000 2859 3001 2853 3001 2857 3001 2857 3002 2853 3002 2855 3002 2831 3003 2833 3003 2829 3003 2825 3004 2821 3004 2823 3004 2815 3005 2817 3005 2813 3005 2813 3006 2817 3006 2819 3006 2811 3007 2804 3007 2809 3007 2809 3008 2804 3008 2807 3008 2085 3009 2084 3009 2803 3009 2801 3010 3140 3010 3141 3010 2369 3011 2366 3011 2293 3011 2911 3012 2369 3012 2293 3012 2791 53 2801 53 2793 53 3144 3013 2307 3013 3145 3013 2308 3014 3145 3014 2307 3014 2310 3015 2307 3015 3144 3015 3145 3016 2309 3016 3146 3016 2288 3017 3146 3017 2309 3017 2289 3018 3150 3018 3148 3018 2288 3019 3148 3019 3147 3019 3157 3020 2592 3020 3158 3020 3155 3021 3157 3021 3159 3021 2299 3022 2300 3022 2496 3022 2499 3023 2274 3023 2500 3023 2499 3024 2301 3024 2274 3024 2275 3025 2500 3025 2274 3025 2269 3026 3160 3026 2270 3026 2299 3027 3160 3027 2269 3027 3163 3028 3164 3028 3165 3028 3164 3029 3162 3029 3166 3029 3167 3030 3166 3030 3168 3030 3163 3031 3169 3031 3161 3031 3161 3032 3169 3032 3170 3032 3163 3033 3165 3033 3169 3033 3169 3034 3165 3034 3171 3034 3171 3035 3172 3035 3173 3035 3172 3036 3164 3036 3167 3036 3172 3037 3174 3037 3173 3037 3173 3038 3174 3038 3175 3038 3175 3039 3174 3039 3167 3039 3168 3040 3176 3040 3167 3040 3167 3041 3176 3041 3175 3041 3166 3042 3177 3042 3168 3042 3178 3043 3179 3043 3180 3043 3162 3044 3161 3044 3166 3044 3179 3045 3166 3045 3161 3045 3179 3046 3161 3046 3180 3046 3185 3047 3184 3047 3186 3047 3187 3048 3181 3048 3188 3048 3189 3049 3187 3049 3188 3049 3188 3050 3183 3050 3190 3050 3187 3051 3189 3051 3192 3051 3192 3052 3189 3052 3193 3052 3191 3053 3190 3053 3194 3053 3194 3054 3190 3054 3195 3054 3190 3055 3196 3055 3195 3055 3196 3056 3183 3056 3197 3056 3197 3057 3183 3057 3198 3057 3202 3058 3199 3058 3203 3058 3204 3059 3205 3059 3203 3059 3199 3060 3202 3060 3207 3060 3207 3061 3202 3061 3208 3061 3209 3062 3202 3062 3205 3062 3205 3063 3202 3063 3203 3063 3202 3064 3209 3064 3208 3064 3204 3065 3213 3065 3205 3065 3205 3066 3213 3066 3211 3066 3212 3067 3213 3067 3214 3067 3213 3068 3204 3068 3215 3068 3215 3069 3204 3069 3201 3069 3216 3070 3201 3070 3217 3070 3200 3071 3206 3071 3201 3071 3201 3072 3206 3072 3217 3072 3221 3073 3218 3073 3220 3073 3222 3074 3218 3074 3221 3074 3218 3075 3222 3075 3223 3075 3225 3076 3222 3076 3221 3076 3222 3077 3225 3077 3226 3077 3228 3078 3223 3078 3229 3078 3226 3079 3230 3079 3222 3079 3222 3080 3230 3080 3229 3080 3226 3081 3225 3081 3231 3081 3225 3082 3233 3082 3231 3082 3232 3083 3233 3083 3234 3083 3233 3084 3225 3084 3224 3084 3236 3085 3237 3085 3224 3085 3236 3086 3219 3086 3237 3086 3237 3087 3219 3087 3227 3087 3242 3088 3238 3088 3241 3088 3238 3089 3242 3089 3243 3089 3242 3090 3245 3090 3246 3090 3246 3091 3250 3091 3242 3091 3242 3092 3250 3092 3249 3092 3250 3093 3251 3093 3252 3093 3251 3094 3253 3094 3252 3094 3256 3095 3257 3095 3244 3095 3244 3096 3257 3096 3255 3096 3244 3097 3240 3097 3256 3097 3240 3098 3239 3098 3256 3098 3257 3099 3239 3099 3247 3099 3258 3100 3259 3100 3260 3100 3260 3101 3264 3101 3261 3101 3265 3102 3261 3102 3264 3102 3265 3103 3262 3103 3261 3103 3259 3104 3258 3104 3267 3104 3258 3105 3263 3105 3268 3105 3268 3106 3263 3106 3269 3106 3266 3107 3270 3107 3262 3107 3262 3108 3270 3108 3269 3108 3266 3109 3265 3109 3271 3109 3266 3110 3271 3110 3270 3110 3274 3111 3264 3111 3275 3111 3260 3112 3259 3112 3276 3112 3276 3113 3259 3113 3277 3113 3277 3114 3259 3114 3267 3114 3281 3115 3278 3115 3280 3115 3278 3116 3282 3116 3283 3116 3280 3117 3284 3117 3281 3117 3282 3118 3285 3118 3286 3118 3278 3119 3283 3119 3288 3119 3282 3120 3290 3120 3289 3120 3286 3121 3285 3121 3291 3121 3290 3122 3291 3122 3292 3122 3285 3123 3293 3123 3291 3123 3292 3124 3293 3124 3294 3124 3293 3125 3285 3125 3284 3125 3293 3126 3284 3126 3294 3126 3294 3127 3284 3127 3295 3127 3296 3128 3297 3128 3284 3128 3284 3129 3297 3129 3295 3129 3284 3130 3280 3130 3296 3130 3280 3131 3279 3131 3296 3131 3296 3132 3279 3132 3297 3132 3297 3133 3279 3133 3287 3133 3301 3134 3298 3134 3300 3134 3305 3135 3301 3135 3304 3135 3305 3136 3302 3136 3301 3136 3298 3137 3303 3137 3308 3137 3309 3138 3303 3138 3302 3138 3306 3139 3310 3139 3302 3139 3302 3140 3310 3140 3309 3140 3306 3141 3311 3141 3310 3141 3310 3142 3311 3142 3312 3142 3311 3143 3313 3143 3312 3143 3312 3144 3313 3144 3314 3144 3313 3145 3305 3145 3304 3145 3314 3146 3304 3146 3315 3146 3316 3147 3317 3147 3304 3147 3304 3148 3317 3148 3315 3148 3304 3149 3300 3149 3316 3149 3318 3150 3319 3150 3320 3150 3321 3151 3318 3151 3320 3151 3322 3152 3318 3152 3321 3152 3320 3153 3324 3153 3321 3153 3325 3154 3321 3154 3324 3154 3325 3155 3322 3155 3321 3155 3327 3156 3318 3156 3328 3156 3329 3157 3323 3157 3322 3157 3326 3158 3330 3158 3322 3158 3322 3159 3330 3159 3329 3159 3326 3160 3325 3160 3331 3160 3330 3161 3331 3161 3332 3161 3331 3162 3333 3162 3332 3162 3333 3163 3324 3163 3334 3163 3324 3164 3337 3164 3335 3164 3324 3165 3320 3165 3336 3165 3336 3166 3319 3166 3337 3166 3337 3167 3319 3167 3327 3167 3342 3168 3338 3168 3341 3168 3338 3169 3342 3169 3343 3169 3345 3170 3342 3170 3341 3170 3342 3171 3345 3171 3346 3171 3339 3172 3338 3172 3347 3172 3347 3173 3338 3173 3348 3173 3338 3174 3343 3174 3348 3174 3348 3175 3343 3175 3349 3175 3349 3176 3343 3176 3342 3176 3345 3177 3353 3177 3351 3177 3352 3178 3353 3178 3354 3178 3353 3179 3345 3179 3344 3179 3353 3180 3344 3180 3354 3180 3344 3181 3357 3181 3355 3181 3344 3182 3340 3182 3356 3182 3356 3183 3339 3183 3357 3183 3361 3184 3358 3184 3362 3184 3358 3185 3360 3185 3362 3185 3363 3186 3362 3186 3360 3186 3359 3187 3358 3187 3365 3187 3365 3188 3358 3188 2595 3188 2595 3189 3361 3189 3366 3189 3364 3190 3361 3190 3362 3190 3361 3191 3367 3191 3366 3191 3366 3192 3367 3192 3368 3192 3369 3193 3370 3193 3367 3193 3364 3194 3371 3194 3369 3194 3372 3195 3373 3195 3374 3195 3376 3196 3377 3196 3378 3196 3379 3197 3376 3197 3378 3197 3157 3198 3376 3198 2593 3198 3381 3199 3380 3199 3379 3199 3383 3200 3379 3200 3382 3200 3379 3201 3383 3201 3381 3201 2593 3202 3376 3202 3380 3202 3384 3203 2593 3203 3380 3203 3381 3204 3385 3204 3380 3204 3380 3205 3385 3205 3384 3205 3381 3206 3386 3206 3385 3206 3385 3207 3386 3207 3387 3207 3383 3208 3388 3208 3386 3208 3386 3209 3388 3209 3387 3209 3387 3210 3388 3210 3389 3210 3388 3211 3383 3211 3382 3211 3389 3212 3388 3212 2605 3212 3390 3213 3154 3213 3382 3213 3382 3214 3154 3214 2605 3214 3382 3215 3378 3215 3390 3215 3378 3216 3377 3216 3390 3216 2290 3217 3153 3217 2289 3217 2524 3218 2233 3218 3393 3218 3393 3219 2233 3219 3394 3219 3394 3220 2233 3220 2234 3220 3400 3221 3399 3221 3401 3221 3401 3222 3402 3222 3400 3222 3401 3223 2654 3223 3402 3223 3402 3224 2654 3224 2653 3224 3405 3225 3404 3225 3403 3225 3405 3226 2652 3226 2651 3226 3405 3227 3408 3227 3404 3227 3404 3228 3408 3228 3409 3228 3410 3229 3411 3229 3409 3229 3409 3230 3413 3230 3414 3230 3419 3231 3415 3231 3418 3231 2619 3232 3419 3232 3420 3232 3414 3233 3413 3233 2628 3233 3409 3234 3414 3234 3415 3234 3417 3235 3416 3235 2624 3235 3421 3236 3418 3236 2614 3236 3421 3237 2614 3237 2613 3237 3424 3238 3426 3238 3425 3238 3427 3239 2606 3239 2109 3239 3144 3240 2117 3240 2310 3240 3144 3241 3145 3241 3425 3241 2458 3242 3429 3242 2527 3242 2592 3243 2500 3243 2275 3243 2589 3244 2500 3244 2592 3244 2592 3245 2275 3245 2276 3245 2592 3246 2276 3246 2277 3246 2592 3247 2277 3247 3158 3247 3158 3248 3430 3248 3431 3248 2277 3249 3430 3249 3158 3249 3430 3250 2271 3250 2270 3250 3160 3251 3431 3251 3430 3251 3155 3252 3154 3252 3432 3252 3154 3253 2291 3253 2605 3253 3384 3254 3385 3254 2594 3254 3384 3255 2594 3255 2591 3255 3387 3256 3389 3256 2596 3256 2596 3257 3389 3257 2598 3257 2605 3258 2598 3258 3389 3258 2296 3259 2298 3259 2313 3259 2297 3260 2966 3260 2298 3260 3433 3261 3434 3261 3435 3261 3435 3262 3436 3262 3433 3262 3435 3263 3437 3263 3436 3263 3436 3264 3437 3264 3438 3264 3441 3265 3440 3265 3442 3265 3443 3266 3442 3266 3444 3266 3158 3267 3450 3267 3159 3267 3155 3268 3159 3268 3156 3268 3149 3269 3452 3269 3453 3269 3152 3270 3453 3270 3435 3270 3152 3271 3149 3271 3453 3271 3153 3272 3156 3272 3451 3272 3431 3273 3449 3273 3450 3273 3454 3274 3447 3274 3448 3274 3456 3275 3457 3275 3446 3275 3457 3276 3445 3276 3446 3276 3443 3277 3459 3277 3442 3277 3459 3278 3460 3278 3442 3278 3460 3279 3441 3279 3442 3279 3461 3280 3438 3280 3437 3280 3462 3281 2950 3281 3463 3281 2948 3282 3462 3282 2946 3282 2943 3283 3464 3283 3465 3283 2929 3284 3468 3284 3469 3284 2922 3285 3456 3285 3455 3285 2935 3286 3467 3286 2931 3286 2929 3287 3469 3287 2928 3287 2926 3288 3470 3288 2925 3288 3456 3289 2925 3289 3457 3289 3457 3290 2925 3290 3471 3290 3445 3291 3472 3291 3458 3291 3443 3292 3473 3292 3474 3292 3475 3293 3441 3293 3460 3293 3475 3294 3476 3294 3441 3294 3477 3295 3439 3295 3441 3295 3439 3296 3477 3296 3478 3296 3478 3297 3479 3297 3461 3297 3438 3298 3479 3298 3480 3298 3438 3299 3481 3299 3436 3299 3436 3300 3481 3300 3463 3300 2954 3301 3463 3301 2952 3301 2954 3302 2955 3302 3433 3302 3443 3303 3474 3303 3459 3303 3447 3304 2922 3304 3455 3304 3456 3305 2922 3305 2924 3305 3433 3306 2955 3306 3434 3306 3434 3307 2955 3307 3151 3307 3151 3308 3152 3308 3434 3308 3023 3309 3448 3309 3446 3309 3448 3310 3019 3310 3017 3310 3159 3311 3013 3311 3012 3311 3450 3312 3013 3312 3159 3312 3156 3313 3010 3313 3451 3313 3451 6 3010 6 3009 6 3453 3314 3001 3314 2999 3314 3435 3315 2999 3315 2997 3315 3435 3316 2997 3316 2995 3316 3437 3317 2991 3317 2989 3317 3440 3318 2987 3318 2985 3318 3440 3319 2985 3319 2983 3319 3442 3320 3440 3320 2983 3320 3452 3321 3003 3321 3453 3321 3453 3322 2999 3322 3435 3322 3435 3323 2995 3323 3437 3323 3442 3324 2981 3324 2979 3324 3444 6 2975 6 2973 6 3446 3325 2973 3325 2971 3325 3442 3326 2977 3326 3444 3326 3444 3327 2973 3327 3446 3327 2305 3328 2302 3328 2221 3328 2305 3329 2221 3329 3146 3329 3147 3330 2312 3330 3146 3330 2312 3331 3147 3331 3151 3331 2221 3332 2222 3332 3146 3332 3425 3333 2222 3333 3483 3333 3415 3334 3484 3334 3485 3334 3146 3335 2222 3335 3425 3335 3425 3336 3483 3336 3419 3336 3419 3337 3484 3337 3415 3337 3415 3338 3485 3338 3409 3338 3404 3339 3487 3339 3398 3339 3398 3340 3488 3340 3393 3340 2305 3341 3146 3341 2312 3341 2312 3342 2955 3342 2957 3342 2957 3343 2955 3343 2956 3343 2966 3344 3482 3344 2495 3344 2966 3345 3491 3345 3482 3345 2922 3346 2966 3346 2920 3346 2920 3347 2923 3347 2922 3347 2922 3348 3447 3348 3491 3348 2298 3349 2495 3349 2294 3349 2294 3350 2495 3350 2119 3350 2130 3351 2488 3351 2483 3351 2122 3352 2475 3352 2470 3352 2125 3353 2467 3353 2464 3353 2127 3354 2125 3354 2464 3354 2120 3355 2488 3355 2130 3355 2135 3356 2479 3356 2140 3356 2122 3357 2470 3357 2123 3357 2123 3358 2467 3358 2125 3358 3160 3359 2299 3359 2495 3359 3160 3360 3482 3360 3492 3360 3449 3361 3492 3361 3454 3361 3492 3362 3449 3362 3431 3362 2222 3363 2219 3363 3493 3363 2219 3364 3495 3364 3493 3364 3495 3365 3497 3365 3493 3365 3493 3366 3497 3366 3498 3366 3484 3367 3498 3367 3499 3367 3500 3368 3501 3368 3484 3368 3484 3369 3501 3369 3502 3369 3485 3370 3502 3370 3503 3370 3505 3371 3504 3371 3506 3371 3493 3372 3498 3372 3484 3372 3511 3373 3486 3373 3510 3373 3511 3374 3512 3374 3486 3374 3513 3375 3512 3375 3511 3375 3487 3376 3512 3376 3514 3376 3487 3377 3514 3377 3515 3377 3516 3378 3488 3378 3487 3378 3518 3379 3517 3379 3516 3379 3494 3380 3489 3380 3520 3380 3490 3381 3494 3381 3521 3381 3523 3382 3524 3382 3490 3382 3509 3383 3412 3383 3525 3383 3412 3384 2644 3384 3525 3384 3509 3385 3526 3385 3412 3385 3526 3386 3508 3386 2640 3386 2640 3387 3508 3387 3527 3387 3506 3388 3528 3388 3507 3388 3507 3389 3528 3389 3529 3389 3530 3390 2628 3390 3504 3390 3504 3391 2628 3391 3531 3391 3504 3392 3503 3392 3530 3392 3530 3393 3503 3393 3532 3393 3532 3394 3533 3394 2625 3394 3503 3395 3502 3395 3534 3395 3534 3396 3502 3396 3535 3396 3501 3397 3500 3397 3536 3397 3539 3398 3500 3398 3540 3398 3500 3399 3539 3399 3538 3399 3543 3400 3428 3400 3497 3400 3497 3401 3428 3401 3544 3401 3497 3402 3495 3402 3543 3402 3543 3403 3495 3403 3545 3403 3545 3404 3495 3404 3546 3404 2219 3405 2216 3405 3496 3405 2218 3406 3548 3406 2216 3406 2218 3407 3549 3407 3548 3407 2218 3408 3556 3408 3555 3408 2218 3409 3557 3409 3556 3409 2218 3410 3560 3410 3559 3410 3561 3411 3560 3411 3521 3411 3522 3412 3521 3412 3560 3412 3557 3413 3558 3413 3562 3413 3555 3414 3564 3414 3565 3414 3565 3415 3564 3415 3518 3415 3565 3416 3518 3416 3516 3416 3566 3417 3554 3417 3567 3417 3567 3418 3568 3418 3566 3418 3568 3419 3515 3419 3514 3419 3553 53 3554 53 3566 53 3551 53 3552 53 3569 53 3569 3420 3513 3420 3570 3420 3509 3421 3525 3421 3510 3421 3571 3422 3572 3422 3525 3422 2216 3423 3548 3423 3573 3423 3574 3424 2216 3424 3573 3424 3575 53 3574 53 3576 53 3527 3425 3578 3425 3573 3425 3578 3426 3508 3426 3507 3426 3577 3427 3506 3427 3504 3427 3575 3428 3579 3428 2216 3428 3581 3429 3582 3429 2216 3429 3537 3430 3583 3430 3502 3430 3580 3431 3579 3431 3584 3431 2216 3432 3586 3432 3587 3432 3588 3433 2216 3433 3587 3433 3588 3434 3589 3434 2216 3434 3544 3435 3590 3435 3497 3435 3592 3436 3591 3436 3540 3436 3587 3437 3591 3437 3592 3437 3589 3438 3547 3438 2216 3438 3547 3439 3546 3439 3496 3439 3593 3440 2486 3440 2155 3440 2155 3441 2486 3441 2175 3441 2139 3442 3594 3442 2155 3442 3596 3443 2154 3443 3597 3443 3598 3444 2514 3444 2153 3444 2153 3445 2514 3445 2184 3445 2153 3446 2142 3446 3598 3446 3598 3447 2142 3447 3599 3447 3599 3448 2142 3448 2144 3448 2144 3449 3600 3449 3599 3449 2143 3450 2147 3450 3601 3450 2145 3451 3603 3451 2196 3451 3603 3452 2518 3452 2196 3452 2145 3453 2146 3453 3603 3453 3603 3454 2146 3454 3604 3454 2205 3455 3604 3455 2146 3455 2148 3456 3606 3456 2202 3456 3606 3457 3607 3457 2202 3457 3606 3458 2124 3458 3608 3458 3608 3459 2124 3459 2520 3459 3611 3460 3610 3460 3612 3460 3615 3461 3614 3461 3616 3461 2384 3462 2209 3462 3615 3462 2152 3463 3613 3463 3615 3463 2152 3464 2128 3464 3613 3464 3613 3465 2128 3465 3611 3465 2129 3466 3611 3466 2128 3466 2129 3467 3609 3467 3611 3467 3618 3468 2129 3468 3617 3468 3618 3469 3609 3469 2129 3469 3623 3470 3622 3470 2398 3470 3523 3471 3621 3471 3622 3471 3620 3472 3522 3472 3560 3472 2388 3473 2396 3473 3619 3473 2900 3474 3619 3474 3142 3474 2900 3475 2388 3475 3619 3475 2388 3476 2411 3476 2386 3476 2386 3477 2411 3477 2387 3477 3142 3478 3560 3478 2218 3478 2215 3479 3142 3479 2218 3479 3624 3480 2413 3480 2415 3480 2418 3481 3624 3481 2415 3481 3624 3482 2418 3482 2424 3482 3625 53 2382 53 3626 53 3626 53 2383 53 3616 53 3614 3483 3626 3483 3616 3483 3614 3484 3627 3484 3626 3484 3627 53 3612 53 3610 53 3628 53 3630 53 3629 53 3631 3485 3630 3485 3632 3485 2413 3486 3624 3486 3634 3486 3143 3487 2384 3487 2381 3487 2157 3488 3636 3488 2158 3488 2158 3489 3636 3489 2314 3489 2890 3490 2884 3490 3636 3490 2882 3491 2876 3491 3636 3491 2884 3492 2882 3492 3636 3492 2866 3493 2860 3493 3636 3493 2868 3494 2866 3494 3636 3494 2858 3495 2852 3495 3636 3495 2860 3496 2858 3496 3636 3496 2852 3497 2850 3497 3636 3497 2842 3498 2836 3498 2314 3498 3636 3499 2842 3499 2314 3499 2836 3500 2834 3500 2314 3500 2828 3501 2826 3501 2314 3501 2091 3502 2088 3502 2314 3502 2092 3503 2797 3503 2314 3503 2088 3504 2092 3504 2314 3504 2797 3505 2798 3505 2314 3505 2901 3506 3636 3506 2903 3506 2892 3507 2890 3507 3636 3507 3154 3508 3390 3508 3432 3508 3462 3509 3638 3509 3639 3509 3462 3510 3639 3510 3640 3510 3464 3511 3640 3511 3641 3511 3643 3512 3467 3512 3466 3512 3467 3513 3644 3513 3645 3513 3646 3514 3468 3514 3645 3514 3646 3515 3469 3515 3468 3515 3462 3516 3640 3516 3464 3516 3465 3517 3642 3517 3466 3517 3650 3518 2925 3518 3470 3518 3471 3519 2925 3519 3651 3519 3652 3520 3471 3520 3651 3520 3654 3521 3655 3521 3473 3521 3473 3522 3655 3522 3474 3522 3475 3523 3657 3523 3658 3523 3666 3524 3660 3524 3659 3524 3667 3525 3666 3525 3659 3525 3668 3526 3663 3526 3662 3526 3661 3527 3660 3527 3668 3527 3667 3528 3659 3528 3661 3528 3669 3529 3670 3529 3671 3529 3675 3530 3674 3530 3671 3530 3676 3531 3675 3531 3670 3531 3676 3532 3670 3532 3677 3532 3677 3533 3670 3533 3669 3533 3671 3534 3677 3534 3669 3534 3678 3535 3674 3535 3673 3535 3679 3536 3674 3536 3667 3536 3680 3537 3681 3537 3682 3537 3683 3538 3684 3538 3685 3538 3688 3539 3686 3539 3687 3539 3689 3540 3691 3540 3690 3540 3688 3541 3687 3541 3683 3541 3690 3542 3691 3542 3681 3542 3681 3543 3683 3543 3682 3543 3684 3544 3683 3544 3687 3544 3638 3545 3692 3545 3693 3545 3639 3546 3693 3546 3694 3546 3694 3547 3695 3547 3640 3547 3640 3548 3695 3548 3685 3548 3641 3549 3685 3549 3686 3549 3641 3550 3696 3550 3642 3550 3696 3551 3665 3551 3642 3551 3689 3552 3688 3552 3691 3552 3689 3553 3665 3553 3688 3553 3638 3554 3693 3554 3639 3554 3658 3555 3657 3555 3662 3555 3643 3556 3666 3556 3667 3556 3676 3557 3699 3557 3654 3557 3647 3558 3654 3558 3653 3558 3653 3559 3652 3559 3648 3559 3649 3560 3652 3560 3651 3560 3655 3561 3654 3561 3699 3561 3646 3562 3654 3562 3647 3562 3646 3563 3645 3563 3672 3563 3678 3564 3672 3564 3645 3564 3678 3565 3644 3565 3667 3565 3662 3566 3671 3566 3667 3566 3667 3567 3661 3567 3662 3567 3676 3568 3677 3568 3699 3568 3695 3569 3680 3569 3685 3569 3683 3570 3685 3570 3680 3570 3692 3571 3481 3571 3480 3571 3692 3572 3637 3572 3481 3572 3637 3573 3463 3573 3481 3573 3693 3574 3479 3574 3694 3574 3694 3575 3478 3575 3695 3575 3697 3576 3476 3576 3658 3576 3658 3577 3476 3577 3475 3577 3705 3578 3704 3578 3706 3578 3704 3579 3707 3579 3706 3579 3710 6 3708 6 3709 6 3710 3580 3711 3580 3708 3580 3712 3581 3711 3581 3713 3581 3715 3582 3714 3582 3716 3582 3717 3583 3716 3583 3718 3583 3721 3584 3720 3584 3722 3584 3713 3585 3725 3585 3712 3585 3715 3586 3716 3586 3717 3586 3720 6 3718 6 3726 6 3728 3587 3727 3587 3729 3587 3429 6 3730 6 3731 6 3734 3588 3737 3588 3735 3588 3735 3589 3737 3589 3738 3589 3739 6 3741 6 3740 6 3739 3590 3742 3590 3741 3590 3741 6 3742 6 2465 6 3738 3591 3737 3591 3703 3591 3728 6 3720 6 3727 6 3725 3592 3724 3592 3701 3592 3730 3593 3728 3593 3729 3593 3736 6 3726 6 3734 6 3700 3594 3743 3594 3701 3594 3618 3595 3739 3595 3738 3595 3712 3596 3744 3596 3745 3596 3725 3597 3743 3597 3712 3597 3745 3598 2439 3598 3711 3598 3711 3599 2439 3599 3708 3599 3712 3600 3745 3600 3711 3600 2440 3601 3708 3601 2439 3601 3618 3602 3738 3602 3705 3602 3742 3603 2463 3603 2465 3603 2405 3604 3744 3604 2399 3604 2399 3605 3744 3605 3712 3605 2398 3606 2399 3606 3712 3606 2401 3607 2403 3607 2439 3607 3623 3608 3743 3608 3524 3608 3743 3609 3700 3609 3524 3609 3524 3610 3700 3610 2456 3610 3490 3611 3524 3611 2456 3611 2440 3612 2441 3612 3632 3612 3747 3613 3632 3613 3630 3613 3746 3614 3628 3614 3610 3614 2440 3615 3632 3615 3747 3615 3748 3616 3628 3616 3746 3616 3749 3617 2389 3617 3750 3617 2389 3618 3749 3618 2391 3618 2400 3619 3753 3619 3754 3619 2389 3620 2390 3620 3750 3620 2393 3621 3752 3621 2397 3621 2397 3622 3753 3622 2400 3622 2400 3623 3754 3623 2402 3623 3756 3624 3749 3624 3757 3624 3753 3625 3760 3625 3761 3625 3754 3626 3761 3626 3762 3626 3755 3627 3762 3627 3757 3627 3750 3628 3757 3628 3749 3628 3754 3629 3762 3629 3755 3629 3763 3630 3627 3630 3764 3630 3763 3631 3626 3631 3627 3631 3634 3632 3766 3632 3767 3632 3634 3633 3767 3633 3768 3633 3631 3634 3768 3634 3769 3634 3629 3635 3769 3635 3764 3635 3627 3636 3629 3636 3764 3636 3626 3637 3765 3637 3625 3637 3625 3638 3766 3638 3635 3638 3633 3639 3768 3639 3631 3639 3770 3640 3763 3640 3771 3640 3763 3641 3770 3641 3765 3641 3766 3642 3772 3642 3773 3642 3767 3643 3774 3643 3768 3643 3777 3644 3735 3644 3778 3644 3735 3645 3777 3645 3736 3645 3729 3646 3781 3646 3782 3646 3741 3647 3783 3647 3784 3647 3740 3648 3784 3648 3778 3648 3736 3649 3779 3649 3726 3649 3727 3650 3781 3650 3729 3650 3731 3651 3782 3651 3741 3651 3781 3652 3780 3652 3783 3652 3784 3653 3783 3653 3777 3653 3778 3654 3784 3654 3777 3654 3781 3655 3783 3655 3782 3655 3722 3656 3786 3656 3787 3656 3724 3657 3787 3657 3788 3657 3733 3658 3788 3658 3789 3658 3732 3659 3789 3659 3790 3659 3720 3660 3728 3660 3785 3660 3724 3661 3788 3661 3733 3661 3732 3662 3790 3662 3730 3662 3787 3663 3792 3663 3788 3663 3788 3664 3792 3664 3789 3664 3789 3665 3792 3665 3790 3665 3793 3666 3709 3666 3715 3666 3793 3667 3794 3667 3709 3667 3709 3668 3794 3668 3710 3668 3710 3669 3794 3669 3795 3669 3713 3670 3796 3670 3797 3670 3721 3671 3798 3671 3799 3671 3717 3672 3800 3672 3793 3672 3710 3673 3795 3673 3711 3673 3713 3674 3797 3674 3723 3674 3719 3675 3800 3675 3717 3675 3801 3676 3802 3676 3794 3676 3794 3677 3802 3677 3795 3677 3795 3678 3802 3678 3803 3678 3797 3679 3803 3679 3804 3679 3798 3680 3805 3680 3806 3680 3795 3681 3803 3681 3796 3681 3796 3682 3803 3682 3797 3682 3797 3683 3805 3683 3798 3683 3808 3684 3704 3684 3703 3684 3704 3685 3809 3685 3810 3685 3716 3686 3811 3686 3812 3686 3718 3687 3812 3687 3813 3687 3734 3688 3813 3688 3814 3688 3737 3689 3814 3689 3815 3689 3703 3690 3815 3690 3808 3690 3718 3691 3813 3691 3734 3691 3734 3692 3814 3692 3737 3692 3737 3693 3815 3693 3703 3693 3813 3694 3820 3694 3821 3694 3814 3695 3821 3695 3822 3695 3810 3696 3818 3696 3811 3696 3812 3697 3820 3697 3813 3697 3814 3698 3822 3698 3815 3698 3783 3699 3780 3699 3823 3699 3786 3700 3791 3700 3792 3700 3771 3701 3824 3701 3816 3701 3817 3702 3824 3702 3776 3702 3825 3703 3816 3703 3822 3703 3828 3704 3818 3704 3817 3704 3818 3705 3828 3705 3775 3705 3775 3706 3774 3706 3819 3706 3818 3707 3775 3707 3819 3707 3774 3708 3773 3708 3827 3708 3816 3709 3825 3709 3771 3709 3827 3710 3773 3710 3820 3710 3820 3711 3772 3711 3821 3711 3821 3712 3772 3712 3826 3712 3802 3713 3801 3713 3829 3713 3831 3714 3807 3714 3806 3714 3832 3715 3805 3715 3804 3715 3762 3716 3833 3716 3802 3716 3803 3717 3761 3717 3804 3717 3804 3718 3760 3718 3832 3718 3831 3719 3758 3719 3756 3719 3832 3720 3759 3720 3805 3720 3806 3721 3758 3721 3831 3721 3807 3722 3756 3722 3830 3722 3539 3723 3540 3723 3834 3723 3834 3724 3540 3724 3591 3724 3834 3725 3591 3725 3586 3725 2502 3726 2168 3726 3836 3726 3836 3727 2168 3727 2160 3727 2160 3728 2159 3728 3836 3728 3836 3729 2159 3729 3837 3729 3839 3730 3838 3730 2176 3730 3839 3731 2176 3731 2169 3731 2169 3732 2163 3732 3839 3732 3839 3733 2163 3733 3840 3733 3841 3734 2640 3734 3527 3734 3841 3735 3527 3735 3548 3735 3548 3736 3549 3736 3841 3736 3843 3737 3513 3737 3844 3737 3844 3738 3513 3738 3569 3738 3552 3739 3553 3739 3844 3739 3844 3740 3553 3740 3845 3740 3401 3741 3518 3741 2654 3741 2654 3742 3518 3742 3564 3742 3846 3743 2654 3743 3556 3743 3600 3744 2144 3744 2190 3744 3600 3745 2190 3745 2188 3745 2188 3746 2181 3746 3600 3746 2472 3747 2201 3747 3849 3747 2520 3748 2214 3748 3852 3748 3852 3749 2211 3749 2206 3749 2206 3750 2200 3750 3852 3750 2477 3751 2205 3751 3854 3751 3854 3752 2203 3752 2197 3752 2197 3753 2193 3753 3854 3753 3854 3754 2193 3754 3855 3754 3858 3755 3857 3755 2213 3755 2213 3756 3859 3756 3858 3756 3859 3757 2150 3757 2468 3757 3602 3758 2195 3758 3860 3758 2154 3759 2183 3759 3597 3759 3507 3760 3529 3760 3578 3760 3578 3761 3529 3761 2639 3761 3511 3762 3863 3762 3864 3762 3510 3763 3572 3763 3863 3763 3863 3764 3572 3764 2645 3764 3516 3765 3865 3765 3866 3765 3515 3766 3567 3766 3865 3766 3865 3767 3567 3767 3867 3767 3521 3768 3494 3768 3868 3768 3494 3769 3869 3769 3868 3769 3869 3770 3562 3770 3870 3770 2240 3771 2242 3771 3871 3771 2242 3772 2243 3772 3872 3772 3872 3773 2243 3773 3873 3773 3873 3774 2245 3774 2249 3774 3183 3775 3185 3775 3198 3775 2132 3776 3875 3776 2131 3776 2131 3777 3875 3777 3876 3777 3875 3778 2165 3778 3877 3778 3878 3779 2174 3779 2171 3779 3879 3780 2174 3780 3878 3780 2171 3781 2170 3781 3878 3781 3880 3782 2170 3782 2177 3782 3880 3783 2177 3783 3881 3783 2177 3784 3882 3784 2509 3784 3576 3785 3531 3785 3883 3785 3884 3786 3583 3786 3581 3786 2614 3787 3583 3787 3884 3787 3503 3788 3534 3788 3585 3788 2108 3789 2109 3789 2601 3789 2117 3790 3426 3790 2111 3790 3426 3791 3427 3791 2109 3791 3426 3792 2109 3792 2111 3792 3423 3793 3543 3793 3888 3793 2606 3794 2607 3794 2601 3794 3547 3795 3589 3795 2606 3795 2616 3796 3422 3796 3542 3796 3541 3797 3542 3797 3422 3797 3541 3798 3422 3798 3419 3798 3419 3799 2619 3799 3541 3799 2609 3800 3889 3800 3887 3800 3889 3801 2607 3801 2616 3801 3889 3802 3587 3802 3887 3802 3889 3803 3590 3803 3588 3803 3834 3804 3835 3804 2610 3804 2613 3805 2610 3805 3835 3805 3834 3806 2619 3806 3539 3806 3419 3807 3418 3807 3420 3807 3536 3808 3538 3808 3420 3808 3421 3809 3420 3809 3418 3809 3835 3810 3582 3810 2613 3810 3886 3811 2624 3811 2621 3811 2614 3812 3418 3812 3535 3812 3535 3813 3417 3813 3534 3813 2621 3814 2610 3814 3884 3814 2621 3815 3884 3815 3885 3815 2614 3816 3884 3816 2610 3816 2621 3817 2625 3817 3890 3817 3890 3818 3883 3818 2627 3818 3890 3819 2627 3819 2621 3819 2628 3820 2627 3820 3883 3820 3414 3821 2628 3821 3891 3821 3579 3822 3575 3822 3890 3822 3890 3823 3575 3823 3883 3823 3890 3824 3584 3824 3579 3824 2589 3825 2584 3825 3892 3825 3892 3826 2584 3826 2501 3826 2501 3827 2493 3827 3874 3827 2099 3828 2102 3828 2493 3828 2099 3829 2493 3829 2497 3829 2589 3830 2096 3830 2095 3830 2582 3831 2503 3831 3836 3831 3836 3832 3837 3832 2584 3832 3836 3833 2584 3833 2582 3833 2501 3834 2584 3834 3837 3834 3836 3835 2503 3835 2502 3835 2494 3836 3894 3836 2490 3836 2494 3837 3893 3837 3895 3837 3893 3838 2494 3838 2501 3838 3837 3839 2159 3839 3893 3839 3893 3840 2159 3840 2166 3840 3896 3841 2504 3841 2582 3841 2582 3842 2580 3842 3897 3842 3897 3843 2580 3843 2505 3843 2505 3844 2488 3844 3875 3844 2131 3845 3876 3845 2167 3845 2167 3846 3876 3846 2504 3846 3839 3847 2580 3847 2508 3847 2505 3848 3840 3848 3898 3848 2508 3849 2507 3849 3838 3849 2506 3850 2489 3850 3899 3850 2507 3851 2506 3851 3899 3851 2505 3852 3899 3852 2489 3852 3879 3853 2485 3853 3900 3853 2575 3854 2570 3854 3878 3854 3902 3855 2627 3855 2629 3855 3529 3856 3528 3856 3413 3856 3413 3857 3411 3857 3529 3857 3411 3858 3410 3858 2639 3858 2634 3859 2640 3859 3841 3859 3841 3860 3842 3860 2641 3860 3410 3861 3526 3861 2640 3861 3526 3862 3410 3862 3412 3862 2644 3863 3571 3863 3525 3863 2643 3864 2641 3864 3904 3864 2645 3865 3408 3865 3863 3865 3903 3866 3570 3866 2651 3866 3844 3867 3845 3867 2554 3867 2652 3868 3405 3868 3905 3868 3906 3869 3405 3869 3403 3869 3906 3870 3905 3870 3405 3870 3403 3871 3406 3871 3906 3871 3907 3872 2555 3872 2554 3872 3407 3873 3867 3873 2554 3873 3407 3874 3403 3874 3865 3874 3407 3875 3865 3875 3867 3875 3400 3876 3402 3876 3866 3876 3565 3877 3866 3877 3402 3877 3907 3878 3555 3878 2653 3878 2653 3879 3555 3879 3565 3879 3909 3880 3399 3880 3911 3880 3847 3881 3557 3881 3563 3881 3861 3882 3862 3882 2570 3882 3861 3883 2570 3883 2567 3883 3595 3884 2512 3884 2511 3884 2511 3885 2482 3885 2484 3885 2512 3886 2185 3886 2178 3886 2512 3887 2567 3887 3912 3887 2515 3888 2481 3888 3597 3888 3597 3889 2481 3889 2510 3889 2513 3890 3596 3890 2510 3890 2141 3891 3596 3891 2186 3891 2186 3892 3596 3892 2513 3892 3912 3893 2186 3893 2513 3893 2517 3894 3600 3894 2560 3894 3600 3895 2562 3895 2560 3895 3599 3896 2517 3896 2516 3896 2480 3897 2481 3897 3914 3897 3598 3898 3599 3898 3914 3898 3599 3899 2516 3899 3914 3899 3848 3900 2182 3900 2514 3900 3915 3901 2517 3901 2560 3901 2518 3902 3860 3902 3917 3902 2518 3903 2476 3903 3602 3903 2518 3904 3602 3904 3860 3904 2476 3905 2480 3905 3601 3905 3602 3906 2476 3906 3601 3906 3916 3907 3601 3907 2517 3907 2191 3908 3601 3908 3916 3908 3915 3909 2191 3909 3916 3909 3918 3910 2478 3910 2545 3910 3851 3911 2545 3911 3850 3911 3850 3912 2545 3912 2541 3912 2521 3913 2520 3913 3852 3913 3919 3914 2520 3914 2469 3914 3608 3915 2520 3915 3919 3915 2469 3916 2471 3916 3919 3916 3608 3917 3919 3917 3606 3917 2471 3918 2473 3918 3606 3918 3853 3919 3607 3919 2473 3919 3852 3920 3853 3920 2539 3920 2473 3921 2539 3921 3853 3921 3853 3922 2200 3922 2202 3922 2525 3923 3921 3923 3920 3923 3397 3924 3869 3924 3870 3924 3869 3925 3394 3925 3868 3925 2659 3926 3868 3926 3394 3926 3521 3927 3868 3927 3561 3927 2659 3928 3559 3928 3561 3928 3856 3929 2521 3929 2536 3929 2468 3930 2469 3930 3859 3930 2469 3931 2521 3931 3859 3931 2536 3932 2522 3932 3923 3932 3922 3933 2210 3933 2208 3933 2478 3934 2477 3934 3854 3934 3924 3935 2477 3935 2474 3935 2477 3936 3924 3936 3604 3936 2474 3937 2476 3937 3924 3937 2519 3938 3924 3938 2476 3938 3924 3939 2519 3939 3603 3939 3854 3940 2558 3940 2545 3940 3855 3941 2194 3941 2196 3941 2518 3942 3855 3942 2196 3942 2250 3943 2535 3943 2248 3943 2535 3944 2251 3944 2532 3944 2251 3945 2252 3945 2531 3945 2251 3946 2531 3946 2532 3946 2252 3947 3871 3947 2530 3947 2530 3948 3871 3948 2529 3948 2529 3949 3871 3949 3872 3949 3872 3950 3873 3950 2528 3950 3873 3951 2249 3951 2658 3951 3873 3952 2658 3952 2528 3952 2658 3953 2248 3953 2535 3953 2664 3954 2663 3954 2662 3954 3180 3955 3170 3955 2533 3955 3180 3956 2533 3956 2538 3956 3170 3957 3169 3957 2534 3957 2534 3958 3171 3958 2665 3958 2534 3959 3169 3959 3171 3959 2665 3960 3173 3960 2660 3960 3175 3961 2662 3961 2657 3961 3195 3962 2557 3962 3194 3962 3197 3963 3198 3963 2537 3963 2663 3964 3186 3964 2661 3964 2663 3965 3185 3965 3186 3965 3192 3966 2556 3966 2655 3966 3193 3967 3194 3967 2557 3967 3206 3968 3207 3968 2550 3968 3207 3969 3208 3969 2546 3969 3208 3970 3210 3970 2542 3970 3208 3971 2542 3971 2546 3971 2666 3972 3214 3972 2553 3972 3214 3973 3216 3973 2553 3973 3216 3974 3217 3974 2551 3974 3227 3975 2649 3975 3237 3975 2648 3976 3237 3976 2649 3976 3227 3977 3228 3977 2559 3977 3227 3978 2559 3978 2649 3978 3228 3979 2547 3979 2559 3979 2549 3980 2548 3980 3232 3980 2548 3981 3230 3981 3232 3981 3232 3982 3234 3982 2549 3982 2549 3983 3234 3983 2552 3983 3234 3984 3235 3984 2642 3984 3235 3985 3237 3985 2648 3985 3235 3986 2648 3986 2642 3986 3247 3987 3248 3987 2561 3987 3247 3988 2561 3988 2565 3988 3248 3989 2566 3989 2561 3989 3252 3990 3254 3990 2647 3990 2647 3991 3254 3991 2646 3991 3254 3992 3255 3992 2636 3992 3254 3993 2636 3993 2646 3993 3255 3994 3257 3994 2638 3994 3267 3995 3268 3995 2568 3995 3268 3996 3269 3996 2563 3996 3268 3997 2563 3997 2568 3997 3269 3998 2564 3998 2563 3998 2637 3999 2564 3999 3270 3999 3272 4000 3274 4000 2637 4000 2637 4001 3274 4001 2635 4001 3274 4002 3275 4002 2630 4002 3274 4003 2630 4003 2635 4003 3275 4004 3277 4004 2632 4004 3275 4005 2632 4005 2630 4005 2623 4006 3297 4006 2574 4006 3287 4007 3288 4007 2571 4007 3288 4008 3289 4008 2569 4008 3288 4009 2569 4009 2571 4009 3289 4010 3290 4010 2633 4010 2631 4011 2633 4011 3290 4011 2631 4012 3294 4012 2626 4012 3294 4013 3295 4013 2622 4013 3294 4014 2622 4014 2626 4014 3295 4015 3297 4015 2623 4015 3295 4016 2623 4016 2622 4016 3307 4017 2579 4017 3317 4017 3307 4018 2576 4018 2579 4018 3308 4019 2572 4019 2576 4019 3309 4020 2573 4020 2572 4020 2573 4021 3312 4021 2667 4021 3312 4022 3314 4022 2620 4022 3314 4023 3315 4023 2612 4023 3315 4024 2673 4024 2612 4024 3327 4025 3328 4025 2581 4025 3327 4026 2581 4026 2671 4026 3328 4027 2577 4027 2581 4027 2578 4028 3332 4028 2672 4028 2672 4029 3334 4029 2611 4029 3334 4030 2608 4030 2611 4030 3347 4031 2587 4031 2604 4031 3348 4032 3349 4032 2588 4032 3349 4033 3350 4033 2670 4033 3349 4034 2670 4034 2588 4034 2670 4035 3350 4035 2668 4035 3352 4036 3354 4036 2668 4036 2668 4037 3354 4037 2617 4037 3354 4038 3355 4038 2603 4038 3354 4039 2603 4039 2617 4039 3355 4040 3357 4040 2604 4040 3365 4041 2595 4041 2597 4041 2595 4042 3366 4042 2590 4042 3366 4043 2585 4043 2590 4043 3368 4044 3370 4044 2586 4044 3372 4045 3374 4045 2602 4045 3374 4046 3375 4046 2599 4046 3374 4047 2599 4047 2602 4047 3375 4048 2597 4048 2599 4048 2468 4049 2150 4049 2151 4049 2204 4050 3605 4050 3918 4050 3860 4051 2195 4051 3917 4051 3913 4052 2183 4052 2180 4052 2515 4053 2183 4053 3913 4053 3905 4054 3513 4054 3843 4054 3514 4055 3406 4055 3568 4055 3908 4056 3567 4056 3554 4056 3867 4057 3567 4057 3908 4057 3517 4058 3518 4058 3401 4058 3911 4059 3396 4059 3519 4059 3921 4060 3562 4060 3558 4060 3870 4061 3562 4061 3921 4061 2097 4062 2096 4062 3892 4062 3897 4063 2165 4063 2162 4063 3877 4064 2165 4064 3897 4064 2192 4065 2189 4065 3917 4065 3900 4066 2174 4066 3879 4066 2134 4067 3900 4067 3882 4067 2180 4068 2179 4068 3913 4068 3913 4069 2179 4069 3912 4069 2507 4070 2138 4070 3838 4070 2137 4071 2138 4071 2507 4071 2156 4072 2507 4072 3899 4072 3902 4073 3577 4073 3574 4073 3902 4074 3573 4074 3901 4074 3550 4075 3551 4075 3904 4075 3904 4076 3551 4076 3903 4076 3542 4077 3590 4077 2616 4077 3427 4078 3546 4078 2606 4078 2606 4079 3546 4079 3547 4079 3554 4080 3555 4080 3908 4080 3908 4081 3555 4081 3907 4081 3558 4082 3559 4082 3921 4082 3921 4083 3559 4083 3920 4083 3391 4084 2280 4084 2283 4084 2310 4085 3391 4085 2283 4085 3927 4086 3130 4086 3131 4086 3928 4087 3131 4087 3137 4087 2377 4088 3137 4088 3138 4088 2376 4089 3138 4089 3139 4089 2375 4090 3139 4090 3121 4090 2373 4091 3122 4091 3128 4091 2372 4092 3128 4092 3129 4092 2371 4093 2372 4093 3129 4093 3927 4094 3926 4094 3130 4094 2357 4095 3058 4095 2359 4095 2359 4096 3058 4096 3008 4096 3006 4097 3057 4097 3062 4097 2994 4098 3064 4098 3065 4098 2984 4099 2986 4099 3080 4099 2984 4100 3080 4100 3077 4100 2978 4101 3077 4101 3044 4101 2968 4102 2323 4102 3051 4102 3020 4103 3049 4103 3016 4103 3008 4104 3057 4104 3006 4104 3006 4105 3062 4105 3004 4105 3004 4106 3062 4106 3002 4106 3000 4107 3002 4107 2998 4107 2998 4108 3064 4108 2996 4108 2996 4109 3064 4109 2994 4109 2994 4110 3065 4110 2992 4110 2982 4111 3077 4111 2978 4111 2980 4112 2982 4112 2978 4112 2972 4113 2323 4113 2970 4113 2968 4114 3051 4114 3022 4114 3049 4115 2353 4115 3014 4115 3078 4116 2937 4116 2936 4116 2937 53 3078 53 3079 53 3079 53 3081 53 2941 53 2937 53 3079 53 2939 53 3928 4117 3081 4117 3083 4117 3926 4118 3083 4118 3078 4118 2936 4119 3926 4119 3078 4119 2936 4120 3925 4120 3926 4120 2936 4121 2371 4121 3925 4121 3928 4122 3083 4122 3927 4122 3927 4123 3083 4123 3926 4123 3930 4124 3931 4124 3932 4124 3932 4125 3934 4125 3935 4125 3933 4126 3936 4126 3937 4126 3931 4127 3930 4127 3936 4127 3936 4128 3930 4128 3938 4128 3931 4129 3933 4129 3932 4129 3939 4130 3940 4130 3941 4130 3940 4131 3942 4131 3943 4131 3947 4132 3946 4132 3942 4132 3939 4133 3948 4133 3942 4133 3942 4134 3940 4134 3939 4134 3953 4135 3954 4135 3955 4135 3956 4136 3944 4136 3945 4136 3941 4137 3940 4137 3957 4137 3958 4138 3951 4138 3959 4138 3965 4139 3964 4139 3966 4139 3966 4140 3967 4140 3965 4140 3949 4141 3951 4141 3958 4141 3958 4142 3959 4142 3969 4142 3970 4143 3969 4143 3971 4143 3970 4144 3958 4144 3969 4144 3970 4145 3972 4145 3958 4145 3974 4146 3969 4146 3975 4146 3974 4147 3977 4147 3969 4147 3979 4148 3980 4148 3981 4148 3982 4149 3961 4149 3983 4149 3985 4150 3960 4150 3986 4150 3985 4151 3961 4151 3960 4151 3985 4152 3987 4152 3961 4152 3960 4153 3962 4153 3963 4153 3988 4154 3990 4154 3960 4154 3961 4155 3982 4155 3980 4155 3975 4156 3979 4156 3996 4156 3975 4157 3996 4157 3976 4157 3972 4158 3949 4158 3958 4158 3950 4159 3998 4159 3999 4159 3998 4160 3950 4160 3952 4160 3952 4161 4000 4161 3998 4161 4002 4162 3998 4162 4001 4162 4004 4163 4002 4163 4005 4163 4005 4164 3997 4164 4004 4164 4006 4165 3952 4165 3949 4165 3998 4166 4008 4166 4009 4166 4011 4167 4010 4167 4012 4167 4012 4168 4010 4168 4013 4168 4009 53 4008 53 4015 53 4011 4169 4017 4169 3998 4169 3998 4170 4017 4170 4018 4170 4019 53 3998 53 4018 53 4020 53 4019 53 4021 53 4023 4171 4022 4171 3995 4171 3979 4172 3981 4172 4025 4172 4023 4173 3995 4173 3994 4173 3998 4174 4020 4174 4026 4174 4026 4175 4020 4175 4027 4175 4028 53 4027 53 4029 53 4026 4176 4027 4176 4028 4176 4031 53 4026 53 4028 53 4031 53 4032 53 4026 53 4033 4177 4031 4177 4034 4177 4034 4178 4035 4178 4033 4178 4028 4179 4029 4179 4030 4179 4030 4180 3984 4180 3983 4180 4038 4181 4026 4181 4037 4181 4039 4182 4038 4182 4040 4182 4039 4183 4040 4183 4041 4183 4037 4184 4042 4184 4043 4184 4043 4185 4044 4185 3986 4185 4041 4186 3990 4186 3988 4186 4026 4187 4045 4187 4046 4187 4047 4188 4049 4188 4048 4188 4051 4189 4050 4189 4052 4189 4046 53 4050 53 4051 53 4054 4190 4055 4190 4056 4190 4054 4191 4057 4191 4055 4191 4055 4192 4058 4192 4056 4192 4058 4193 4059 4193 4056 4193 4061 4194 4059 4194 4060 4194 4065 4195 4062 4195 4064 4195 4065 4196 4066 4196 4062 4196 4067 4197 4062 4197 4066 4197 4068 4198 4064 4198 4063 4198 4069 4199 4064 4199 4068 4199 4068 4200 4066 4200 4070 4200 4063 4201 4062 4201 4068 4201 4077 4202 4079 4202 4080 4202 4079 4203 4081 4203 4080 4203 4082 4204 4083 4204 4079 4204 4079 4205 4083 4205 4081 4205 4076 4206 4075 4206 4085 4206 4084 4207 4086 4207 4083 4207 4083 4208 4086 4208 4087 4208 4084 4209 4085 4209 4086 4209 4085 4210 4075 4210 4088 4210 4088 4211 4075 4211 4089 4211 4075 4212 4074 4212 4089 4212 4076 4213 4082 4213 4077 4213 4096 4214 4097 4214 4092 4214 4095 4215 4094 4215 4098 4215 4098 4216 4094 4216 4099 4216 4098 4217 4100 4217 4101 4217 4092 4218 4102 4218 4096 4218 4100 4219 4096 4219 4102 4219 4094 4220 4097 4220 4099 4220 4103 4221 4104 4221 4105 4221 4105 4222 4104 4222 4106 4222 4107 4223 4108 4223 4109 4223 4109 4224 4104 4224 4111 4224 4112 4225 4111 4225 4113 4225 4113 4226 4111 4226 4104 4226 4115 4227 4114 4227 4103 4227 4115 4228 4103 4228 4105 4228 4106 4229 4109 4229 4105 4229 4116 4230 4117 4230 4118 4230 4118 4231 4117 4231 4119 4231 4120 4232 4121 4232 4122 4232 4117 4233 4125 4233 4120 4233 4125 4234 4117 4234 4126 4234 4126 4235 4117 4235 4127 4235 4127 4236 4117 4236 4116 4236 4128 4237 4127 4237 4116 4237 4128 4238 4116 4238 4118 4238 4129 4239 4130 4239 4131 4239 4132 4240 4131 4240 4130 4240 4108 4241 4134 4241 4110 4241 4059 4242 4061 4242 4136 4242 4061 4243 4137 4243 4136 4243 4140 4244 4123 4244 4121 4244 4141 4245 4140 4245 4121 4245 4120 4246 4141 4246 4121 4246 4139 4247 4122 4247 4123 4247 4143 4248 4136 4248 4138 4248 4147 4249 4129 4249 4148 4249 4151 4250 4150 4250 4149 4250 3950 4251 4151 4251 4149 4251 4153 4252 4154 4252 4155 4252 4159 4253 4155 4253 4160 4253 4164 4254 4165 4254 4166 4254 4170 4255 4171 4255 4172 4255 4173 4256 4174 4256 4175 4256 4176 4257 4177 4257 4178 4257 4180 4258 4181 4258 4182 4258 4183 4259 4185 4259 4186 4259 4187 4260 4185 4260 4181 4260 4188 4261 4189 4261 4190 4261 4188 4262 4190 4262 4191 4262 4193 4263 4192 4263 4194 4263 4203 4264 4205 4264 4201 4264 4207 4265 4190 4265 4208 4265 4208 4266 4189 4266 4209 4266 4200 53 4212 53 4195 53 4213 4267 4214 4267 4215 4267 4213 4268 4216 4268 4217 4268 4224 53 4222 53 4225 53 4227 4269 4226 4269 4228 4269 4229 4270 4228 4270 4230 4270 4229 4271 4227 4271 4228 4271 4230 4272 4228 4272 4232 4272 4232 53 4228 53 4233 53 4234 4273 4233 4273 4235 4273 4238 4274 4236 4274 4237 4274 4240 53 4233 53 4234 53 4234 53 4235 53 4236 53 4243 53 4237 53 4225 53 4225 53 4222 53 4243 53 4222 4275 4244 4275 4245 4275 4222 4276 4247 4276 4243 4276 4251 4277 4249 4277 4252 4277 4253 4278 4254 4278 4250 4278 4249 4279 4253 4279 4250 4279 4259 4280 4254 4280 4253 4280 4213 4281 4260 4281 4214 4281 4260 4282 4261 4282 4254 4282 4263 4283 4214 4283 4262 4283 4260 4284 4258 4284 4257 4284 4262 4285 4257 4285 4264 4285 4244 4286 4264 4286 4245 4286 4244 4287 4262 4287 4264 4287 4244 53 4265 53 4262 53 4244 4288 4266 4288 4265 4288 4265 4289 4266 4289 4268 4289 4253 4290 4269 4290 4257 4290 4257 4291 4269 4291 4264 4291 4270 4292 4247 4292 4271 4292 4272 4293 4273 4293 4271 4293 4271 4294 4273 4294 4270 4294 4245 4295 4267 4295 4271 4295 4272 4296 4271 4296 4269 4296 4247 4297 4245 4297 4271 4297 4243 4298 4247 4298 4270 4298 4241 4299 4273 4299 4274 4299 4239 4300 4241 4300 4274 4300 4243 4301 4270 4301 4242 4301 4273 4302 4256 4302 4249 4302 4275 4303 4274 4303 4255 4303 4239 4304 4275 4304 4238 4304 4277 4305 4276 4305 4252 4305 4280 4306 4281 4306 4282 4306 4283 4307 4280 4307 4282 4307 4284 4308 4281 4308 4280 4308 4285 4309 4284 4309 4286 4309 4265 4310 4268 4310 4287 4310 4286 4311 4287 4311 4268 4311 4287 4312 4286 4312 4284 4312 4284 4313 4280 4313 4287 4313 4287 4314 4280 4314 4283 4314 4281 4315 4285 4315 4288 4315 4266 4316 4288 4316 4285 4316 4288 4317 4282 4317 4281 4317 4290 4318 4289 4318 4246 4318 4246 4319 4289 4319 4244 4319 4262 4320 4291 4320 4263 4320 4263 4321 4291 4321 4292 4321 4293 4322 4294 4322 4069 4322 4069 4323 4294 4323 4295 4323 4069 4324 4295 4324 4064 4324 4296 4325 4064 4325 4295 4325 4299 4326 4300 4326 4301 4326 4302 4327 4299 4327 4298 4327 4304 4328 4306 4328 4305 4328 4309 4329 4308 4329 4310 4329 4310 4330 4308 4330 4312 4330 4317 4331 4318 4331 4313 4331 4317 4332 4321 4332 4320 4332 4324 4333 4323 4333 4325 4333 4326 4334 4328 4334 4329 4334 4329 4335 4330 4335 4331 4335 4330 4336 4328 4336 4335 4336 4341 4337 4342 4337 4343 4337 4347 4338 4320 4338 4348 4338 4318 4339 4349 4339 4350 4339 4318 4340 4314 4340 4313 4340 4351 4341 4352 4341 4311 4341 4102 4342 4305 4342 4306 4342 4298 4343 4101 4343 4356 4343 4069 4344 4068 4344 4070 4344 4070 4345 4293 4345 4069 4345 4358 4346 4072 4346 4073 4346 4358 4347 4296 4347 4297 4347 4065 4348 4064 4348 4073 4348 4073 4349 4064 4349 4296 4349 4355 4350 4100 4350 4102 4350 4305 4351 4102 4351 4091 4351 4091 4352 4299 4352 4305 4352 4299 4353 4091 4353 4095 4353 4356 4354 4101 4354 4100 4354 4297 4355 4359 4355 4360 4355 4359 4356 4297 4356 4295 4356 4303 4357 4361 4357 4359 4357 4303 4358 4362 4358 4361 4358 4303 4359 4298 4359 4362 4359 4364 4360 4356 4360 4365 4360 4364 4361 4365 4361 4366 4361 4356 4362 4355 4362 4368 4362 4368 4363 4371 4363 4369 4363 4368 4364 4354 4364 4371 4364 4369 4365 4371 4365 4372 4365 4372 4366 4373 4366 4374 4366 4375 4367 4372 4367 4374 4367 4351 4368 4371 4368 4352 4368 4373 4369 4351 4369 4376 4369 4379 4370 4380 4370 4381 4370 4381 4371 4380 4371 4382 4371 4383 4372 4384 4372 4385 4372 4383 4373 4385 4373 4386 4373 4383 4374 4386 4374 4387 4374 4388 4375 4389 4375 4390 4375 4393 4376 4392 4376 4394 4376 4398 4377 4392 4377 4393 4377 4348 4378 4394 4378 4347 4378 4399 4379 4401 4379 4400 4379 4399 4380 4402 4380 4401 4380 4403 4381 4402 4381 4404 4381 4403 4382 4404 4382 4405 4382 4406 4383 4403 4383 4405 4383 4404 4384 4402 4384 4407 4384 4413 4385 4412 4385 4414 4385 4415 4386 4416 4386 4417 4386 4415 4387 4417 4387 4418 4387 4419 4388 4415 4388 4418 4388 4414 4389 4420 4389 4338 4389 4421 4390 4414 4390 4415 4390 4422 4391 4423 4391 4416 4391 4422 4392 4424 4392 4423 4392 4424 4393 4426 4393 4427 4393 4422 4394 4426 4394 4424 4394 4423 4395 4424 4395 4428 4395 4430 4396 4428 4396 4431 4396 4433 4397 4434 4397 4435 4397 4436 4398 4437 4398 4438 4398 4433 4399 4432 4399 4434 4399 4434 4400 4439 4400 4127 4400 4444 4401 4445 4401 4443 4401 4441 4402 4449 4402 4450 4402 4451 4403 4441 4403 4442 4403 4443 4404 4452 4404 4453 4404 4446 4405 4444 4405 4454 4405 4454 4406 4455 4406 4456 4406 4455 4407 4458 4407 4459 4407 4456 4408 4455 4408 4460 4408 4460 4409 4455 4409 4461 4409 4460 4410 4461 4410 4464 4410 4467 4411 4468 4411 4465 4411 4468 4412 4467 4412 4400 4412 4464 4413 4461 4413 4469 4413 4470 4414 4471 4414 4472 4414 4477 4415 4476 4415 4478 4415 4384 4416 4382 4416 4478 4416 4480 4417 4481 4417 4476 4417 4483 4418 4477 4418 4484 4418 4484 4419 4485 4419 4483 4419 4485 4420 4484 4420 4391 4420 4479 4421 4384 4421 4383 4421 4360 4422 4493 4422 4297 4422 4358 4423 4494 4423 4072 4423 4495 4424 4358 4424 4493 4424 4496 4425 4490 4425 4497 4425 4492 4426 4497 4426 4490 4426 4370 4427 4498 4427 4499 4427 4367 4428 4366 4428 4500 4428 4367 4429 4500 4429 4493 4429 4493 4430 4500 4430 4495 4430 4495 4431 4492 4431 4358 4431 4375 4432 4374 4432 4501 4432 4387 4433 4501 4433 4383 4433 4479 4434 4381 4434 4382 4434 4398 4435 4485 4435 4391 4435 4503 4436 4451 4436 4504 4436 4507 4437 4508 4437 4411 4437 4508 4438 4507 4438 4445 4438 4445 4439 4446 4439 4508 4439 4445 4440 4442 4440 4443 4440 4423 4441 4417 4441 4416 4441 4509 4442 4438 4442 4419 4442 4438 4443 4509 4443 4436 4443 4505 4444 4503 4444 4506 4444 4400 4445 4395 4445 4394 4445 4470 4446 4464 4446 4469 4446 4497 4447 4498 4447 4496 4447 4298 4448 4363 4448 4362 4448 4359 4449 4361 4449 4360 4449 4513 4450 4514 4450 4515 4450 4513 4451 4516 4451 4517 4451 4513 4452 4515 4452 4519 4452 4519 4453 4520 4453 4516 4453 4521 4454 4511 4454 4510 4454 4522 4455 4512 4455 4523 4455 4521 4456 4510 4456 4522 4456 4523 4457 4521 4457 4522 4457 4524 4458 4512 4458 4525 4458 4526 4459 4289 4459 4527 4459 4527 4460 4289 4460 4290 4460 4532 4461 4533 4461 4534 4461 4538 4462 4537 4462 4539 4462 4540 4463 4541 4463 4542 4463 4544 4464 4545 4464 4546 4464 4552 4465 4553 4465 4554 4465 4554 4466 4553 4466 4555 4466 4556 4467 4557 4467 4558 4467 4560 4468 4561 4468 4562 4468 4566 4469 4565 4469 4567 4469 4568 4470 4569 4470 4570 4470 4570 4471 4569 4471 4571 4471 4572 4472 4573 4472 4574 4472 4574 4473 4573 4473 4575 4473 4578 4474 4577 4474 4579 4474 4584 4475 4583 4475 4585 4475 4590 4476 4591 4476 4592 4476 4592 4477 4591 4477 4593 4477 4594 4478 4595 4478 4596 4478 4600 4479 4599 4479 4601 4479 4602 4480 4603 4480 4604 4480 4604 4481 4603 4481 4605 4481 4610 4482 4611 4482 4612 4482 4612 4483 4611 4483 4613 4483 4614 4484 4615 4484 4616 4484 4616 4485 4615 4485 4617 4485 4618 4486 4619 4486 4620 4486 4622 4487 4623 4487 4624 4487 4626 4488 4627 4488 4628 4488 4636 4489 4635 4489 4637 4489 4642 4490 4203 4490 4643 4490 4638 4491 4640 4491 4644 4491 4638 4492 4644 4492 4639 4492 4639 4493 4644 4493 4645 4493 4639 4494 4645 4494 4641 4494 4649 4495 4641 4495 4646 4495 4634 4496 4577 4496 4648 4496 4648 4497 4577 4497 4650 4497 4576 4498 4652 4498 4577 4498 4577 4499 4652 4499 4650 4499 4630 840 4651 840 4631 840 4631 53 4651 53 4653 53 4576 53 4654 53 4652 53 4631 4500 4653 4500 4633 4500 4654 4501 4579 4501 4656 4501 4628 53 4633 53 4657 53 4657 4502 4633 4502 4655 4502 4579 4503 4573 4503 4656 4503 4656 4504 4573 4504 4658 4504 4626 4505 4628 4505 4659 4505 4627 53 4659 53 4661 53 4574 4506 4662 4506 4572 4506 4568 4507 4668 4507 4569 4507 4623 53 4667 53 4669 53 4570 53 4670 53 4568 53 4568 4508 4670 4508 4668 4508 4623 4509 4669 4509 4625 4509 4670 4510 4571 4510 4672 4510 4673 4511 4625 4511 4671 4511 4672 4512 4565 4512 4674 4512 4618 4513 4620 4513 4675 4513 4565 4514 4676 4514 4674 4514 4618 4515 4675 4515 4619 4515 4566 4506 4678 4506 4564 4506 4621 4516 4677 4516 4679 4516 4616 4517 4621 4517 4681 4517 4567 4518 4561 4518 4680 4518 4615 53 4683 53 4685 53 4560 4519 4686 4519 4684 4519 4615 4520 4685 4520 4617 4520 4562 4521 4563 4521 4686 4521 4686 4522 4563 4522 4688 4522 4612 53 4617 53 4689 53 4563 4518 4557 4518 4688 4518 4610 4523 4612 4523 4691 4523 4557 4524 4692 4524 4690 4524 4558 4506 4694 4506 4556 4506 4611 4525 4693 4525 4613 4525 4613 4526 4693 4526 4695 4526 4558 4527 4559 4527 4694 4527 4694 4528 4559 4528 4696 4528 4608 53 4613 53 4697 53 4697 4529 4613 4529 4695 4529 4552 4530 4700 4530 4553 4530 4606 4531 4699 4531 4607 4531 4607 53 4699 53 4701 53 4554 4532 4702 4532 4552 4532 4552 53 4702 53 4700 53 4554 4533 4555 4533 4702 4533 4702 4534 4555 4534 4704 4534 4705 4535 4609 4535 4703 4535 4555 4536 4549 4536 4704 4536 4707 4537 4604 4537 4705 4537 4602 4532 4707 4532 4603 4532 4603 53 4707 53 4709 53 4548 53 4710 53 4708 53 4600 53 4605 53 4713 53 4551 4538 4545 4538 4712 4538 4715 4539 4600 4539 4713 4539 4598 53 4715 53 4599 53 4544 53 4718 53 4716 53 4599 4540 4717 4540 4601 4540 4546 4541 4547 4541 4718 4541 4718 4542 4547 4542 4720 4542 4596 4543 4601 4543 4721 4543 4721 4535 4601 4535 4719 4535 4547 4544 4541 4544 4720 4544 4720 4545 4541 4545 4722 4545 4540 4546 4724 4546 4541 4546 4541 4547 4724 4547 4722 4547 4594 53 4723 53 4595 53 4540 53 4726 53 4724 53 4542 4548 4543 4548 4726 4548 4590 4549 4592 4549 4731 4549 4536 4550 4732 4550 4537 4550 4591 53 4731 53 4733 53 4538 879 4734 879 4536 879 4536 53 4734 53 4732 53 4591 4551 4733 4551 4593 4551 4593 4552 4733 4552 4735 4552 4538 4553 4539 4553 4734 4553 4737 4554 4593 4554 4735 4554 4539 4555 4533 4555 4736 4555 4736 4556 4533 4556 4738 4556 4532 4557 4740 4557 4533 4557 4533 4558 4740 4558 4738 4558 4532 53 4742 53 4740 53 4587 4559 4741 4559 4589 4559 4584 53 4589 53 4745 53 4745 4560 4589 4560 4743 4560 4535 4555 4529 4555 4744 4555 4744 4561 4529 4561 4746 4561 4747 4562 4584 4562 4745 4562 4529 4563 4748 4563 4746 4563 4530 4564 4750 4564 4528 4564 4528 53 4750 53 4748 53 4581 4565 4751 4565 4292 4565 4263 4566 4751 4566 4216 4566 4752 4567 4290 4567 4246 4567 4583 4568 4749 4568 4585 4568 4585 4569 4749 4569 4754 4569 4581 4570 4580 4570 4751 4570 4756 4571 4585 4571 4754 4571 4755 4572 4526 4572 4757 4572 4282 53 4758 53 4283 53 4758 53 4760 53 4283 53 4197 4573 4759 4573 4198 4573 4198 4574 4759 4574 4636 4574 4634 4575 4759 4575 4577 4575 4577 4576 4759 4576 4579 4576 4579 4577 4759 4577 4573 4577 4573 4578 4759 4578 4575 4578 4571 4579 4759 4579 4565 4579 4565 4580 4759 4580 4567 4580 4567 4581 4759 4581 4561 4581 4561 4582 4759 4582 4563 4582 4563 4583 4759 4583 4282 4583 4282 4584 4533 4584 4539 4584 4537 4585 4282 4585 4539 4585 4537 4586 4543 4586 4282 4586 4282 4587 4543 4587 4541 4587 4547 4588 4545 4588 4282 4588 4549 4589 4555 4589 4282 4589 4289 4590 4526 4590 4288 4590 4288 4591 4526 4591 4531 4591 4529 4592 4288 4592 4531 4592 4205 4593 4203 4593 4761 4593 4641 4594 4632 4594 4761 4594 4628 4595 4629 4595 4761 4595 4625 4596 4761 4596 4624 4596 4616 4597 4761 4597 4621 4597 4616 4598 4617 4598 4761 4598 4283 4599 4617 4599 4612 4599 4613 4600 4283 4600 4612 4600 4613 4601 4608 4601 4283 4601 4604 4602 4283 4602 4609 4602 4604 4603 4605 4603 4283 4603 4283 4604 4605 4604 4600 4604 4592 4605 4593 4605 4283 4605 4589 4606 4584 4606 4283 4606 4283 4607 4584 4607 4287 4607 4287 4608 4585 4608 4580 4608 4291 4609 4287 4609 4580 4609 4199 4533 4198 4533 4762 4533 4762 4610 4198 4610 4763 4610 4203 4611 4764 4611 4643 4611 4196 4612 4199 4612 4143 4612 4513 4613 4518 4613 4514 4613 4514 4614 4518 4614 4765 4614 4765 4615 4766 4615 4514 4615 4765 4616 4767 4616 4766 4616 4202 4617 4147 4617 4201 4617 4770 4618 4769 4618 4771 4618 4130 4619 4768 4619 4132 4619 4132 4620 4769 4620 4770 4620 4774 4621 4775 4621 4776 4621 4775 4622 4774 4622 4166 4622 4773 4623 4774 4623 4776 4623 4162 4624 4778 4624 4777 4624 4779 4625 4778 4625 4162 4625 4779 4626 4780 4626 4778 4626 4780 4627 4779 4627 4158 4627 4158 4628 4781 4628 4780 4628 4781 4629 4158 4629 4160 4629 4160 4630 4782 4630 4781 4630 4160 4631 4783 4631 4782 4631 4786 4632 4785 4632 4787 4632 4784 4633 4785 4633 4786 4633 4790 4634 4788 4634 4789 4634 4790 4635 4791 4635 4788 4635 4791 4636 4792 4636 4793 4636 4795 4637 4797 4637 4796 4637 4795 4638 4798 4638 4797 4638 4795 4639 4521 4639 4798 4639 4798 4640 4521 4640 4524 4640 4786 4641 4787 4641 4520 4641 4520 4642 4787 4642 4517 4642 4796 4643 4797 4643 4799 4643 4803 4644 4802 4644 4804 4644 4806 4645 4805 4645 4171 4645 4806 4646 4808 4646 4807 4646 4808 4647 4806 4647 4169 4647 4169 4648 4179 4648 4808 4648 4179 4649 4178 4649 4809 4649 4810 4650 4178 4650 4175 4650 4811 4651 4810 4651 4175 4651 4811 4652 4184 4652 4812 4652 4182 4653 4814 4653 4813 4653 4144 4654 4814 4654 4815 4654 4200 4655 4816 4655 4817 4655 4200 4656 4196 4656 4816 4656 4799 4657 4800 4657 4801 4657 4803 4658 4804 4658 4805 4658 4817 4659 4818 4659 4511 4659 4525 4660 4511 4660 4818 4660 4144 4661 4816 4661 4143 4661 4144 4662 4138 4662 4813 4662 4810 4663 4811 4663 4146 4663 4820 4664 4824 4664 4823 4664 4825 4665 4824 4665 4826 4665 4835 4666 4834 4666 4836 4666 4839 4667 4838 4667 4840 4667 4845 4668 4844 4668 4846 4668 4847 4669 4846 4669 4848 4669 4857 4670 4856 4670 4858 4670 4859 4671 4858 4671 4860 4671 4861 4672 4860 4672 4862 4672 4197 4673 4862 4673 4863 4673 4758 4674 4864 4674 4760 4674 4758 4675 4759 4675 4864 4675 4825 4676 4826 4676 4827 4676 4829 4677 4830 4677 4831 4677 4833 4678 4834 4678 4835 4678 4835 4679 4836 4679 4837 4679 4839 4680 4840 4680 4841 4680 4841 4681 4842 4681 4843 4681 4843 4682 4844 4682 4845 4682 4847 4683 4848 4683 4849 4683 4849 4684 4850 4684 4851 4684 4851 4685 4852 4685 4853 4685 4194 4686 4861 4686 4197 4686 4864 4687 4865 4687 4760 4687 4760 4688 4865 4688 4761 4688 4866 4689 4868 4689 4867 4689 4869 4690 4868 4690 4870 4690 4871 4691 4872 4691 4873 4691 4873 4692 4874 4692 4875 4692 4875 4693 4876 4693 4877 4693 4518 4694 4879 4694 4765 4694 4879 4695 4518 4695 4880 4695 4879 4696 4880 4696 4878 4696 4880 4697 4518 4697 4517 4697 4878 4698 4880 4698 4517 4698 4879 4699 4878 4699 4787 4699 4881 4700 4525 4700 4818 4700 4524 4701 4882 4701 4798 4701 4882 4702 4524 4702 4881 4702 4881 4703 4524 4703 4525 4703 4883 4704 4157 4704 4884 4704 4885 4705 4886 4705 4884 4705 4886 4706 4887 4706 4888 4706 4884 4707 4886 4707 4889 4707 4164 4708 4890 4708 4889 4708 4156 4709 4893 4709 4885 4709 4895 4710 4894 4710 4897 4710 4898 4711 4897 4711 4894 4711 4899 4712 4887 4712 4896 4712 4896 4713 4893 4713 4894 4713 4890 4714 4164 4714 4163 4714 4163 4715 4164 4715 4905 4715 4891 4716 4902 4716 4903 4716 4174 4717 4183 4717 4906 4717 4907 4718 4908 4718 4906 4718 4172 4719 4907 4719 4909 4719 4167 4720 4910 4720 4908 4720 4914 4721 4911 4721 4913 4721 4919 4722 4920 4722 4921 4722 4918 4723 4920 4723 4919 4723 4909 4724 4922 4724 4170 4724 4180 4725 4923 4725 4187 4725 4927 4726 4926 4726 4929 4726 4925 4727 4913 4727 4912 4727 4925 4728 4912 4728 4926 4728 4907 4729 4927 4729 4930 4729 4909 4730 4907 4730 4930 4730 4922 4731 4930 4731 4931 4731 4932 4732 4933 4732 4934 4732 4934 4733 4933 4733 4935 4733 4936 4734 4935 4734 4937 4734 4938 4735 4939 4735 4940 4735 4932 4736 4940 4736 4933 4736 4772 4737 4888 4737 4904 4737 4166 4738 4774 4738 4164 4738 4774 4739 4772 4739 4904 4739 4905 4740 4774 4740 4904 4740 4772 4741 4941 4741 4886 4741 4165 4742 4164 4742 4941 4742 4161 4743 4779 4743 4162 4743 4162 4744 4890 4744 4163 4744 4890 4745 4884 4745 4889 4745 4806 4746 4171 4746 4920 4746 4920 4747 4918 4747 4806 4747 4942 4748 4908 4748 4172 4748 4171 4749 4942 4749 4172 4749 4174 4750 4906 4750 4910 4750 4182 4751 4813 4751 4180 4751 4180 4752 4915 4752 4911 4752 4183 4753 4915 4753 4184 4753 4187 4754 4186 4754 4185 4754 4158 4755 4157 4755 4943 4755 4943 4756 4159 4756 4160 4756 4155 4757 4159 4757 4153 4757 4173 4758 4915 4758 4183 4758 4177 4759 4915 4759 4173 4759 4911 4760 4914 4760 4923 4760 4180 4761 4911 4761 4923 4761 4170 4762 4922 4762 4920 4762 4920 4763 4922 4763 4921 4763 4945 4764 4181 4764 4185 4764 4174 4765 4185 4765 4184 4765 4174 4766 4811 4766 4175 4766 4942 4767 4174 4767 4910 4767 4946 4768 4171 4768 4804 4768 4947 4769 4800 4769 4797 4769 4797 4770 4798 4770 4947 4770 4947 4771 4798 4771 4944 4771 4883 4772 4161 4772 4948 4772 4157 4773 4948 4773 4943 4773 4898 4774 4892 4774 4943 4774 4787 4775 4949 4775 4765 4775 4783 4776 4160 4776 4155 4776 4949 4777 4155 4777 4950 4777 4950 4778 4155 4778 4154 4778 4883 4779 4158 4779 4779 4779 4941 4780 4890 4780 4165 4780 4950 4781 4941 4781 4951 4781 4772 4782 4951 4782 4941 4782 4951 4783 4772 4783 4771 4783 4769 4784 4951 4784 4771 4784 4767 4785 4765 4785 4952 4785 4953 4786 4954 4786 4951 4786 4951 4787 4954 4787 4950 4787 4952 4788 4956 4788 4957 4788 4952 4789 4957 4789 4768 4789 4769 4790 4953 4790 4951 4790 4959 4791 4954 4791 4953 4791 4959 4792 4960 4792 4954 4792 4956 4793 4963 4793 4957 4793 4957 4794 4963 4794 4964 4794 4946 4795 4967 4795 4968 4795 4947 4796 4966 4796 4800 4796 4800 4797 4967 4797 4802 4797 4802 4798 4967 4798 4946 4798 4945 4799 4969 4799 4944 4799 4966 4800 4970 4800 4972 4800 4967 4801 4972 4801 4973 4801 4968 4802 4967 4802 4973 4802 4966 4803 4972 4803 4967 4803 4973 4804 4974 4804 4968 4804 4969 4805 4974 4805 4975 4805 4969 4806 4971 4806 4965 4806 4894 4807 4893 4807 4892 4807 4892 4808 4893 4808 4153 4808 4976 4809 4943 4809 4948 4809 4977 4810 4948 4810 4161 4810 4905 4811 4904 4811 4903 4811 4919 4812 4921 4812 4931 4812 4931 4813 4921 4813 4922 4813 4188 4814 4978 4814 4192 4814 4188 4815 4980 4815 4979 4815 4899 4816 4983 4816 4900 4816 4899 4817 4896 4817 4983 4817 4979 4818 4984 4818 4985 4818 4871 4819 4901 4819 4900 4819 4986 4820 4985 4820 4895 4820 4940 4821 4939 4821 4987 4821 4989 4822 4939 4822 4937 4822 4940 4823 4897 4823 4933 4823 4935 4824 4839 4824 4937 4824 4992 4825 4841 4825 4931 4825 4989 4826 4926 4826 4995 4826 4988 4827 4989 4827 4995 4827 4992 4828 4991 4828 4841 4828 4990 4829 4989 4829 4937 4829 4188 4830 4981 4830 4980 4830 4982 4831 4964 4831 4981 4831 4981 4832 4964 4832 4963 4832 4980 4833 4963 4833 4962 4833 4984 4834 4962 4834 4961 4834 4982 4835 4900 4835 4959 4835 4980 4836 4962 4836 4984 4836 4984 4837 4961 4837 4983 4837 4971 4838 4975 4838 4994 4838 4991 4839 4973 4839 4972 4839 4989 4840 4970 4840 4971 4840 4994 4841 4975 4841 4993 4841 4992 4842 4973 4842 4991 4842 4991 4843 4972 4843 4990 4843 4990 4844 4970 4844 4989 4844 4200 4845 4817 4845 4212 4845 4817 4846 4511 4846 4795 4846 4198 4847 4636 4847 4763 4847 4636 4848 4999 4848 4998 4848 4054 4849 4744 4849 4746 4849 4054 4850 4757 4850 5000 4850 4056 4851 4672 4851 4674 4851 4056 4852 4658 4852 4664 4852 4056 4853 4650 4853 4656 4853 4056 4854 4998 4854 4648 4854 4056 4855 4763 4855 4998 4855 4056 4856 4059 4856 4763 4856 4696 4857 4698 4857 4054 4857 4054 4858 4698 4858 4704 4858 4706 4859 4054 4859 4704 4859 4054 4860 4714 4860 4720 4860 4722 4861 4728 4861 4054 4861 4736 4862 4738 4862 4054 4862 4756 4863 5001 4863 4751 4863 4751 4864 5001 4864 4216 4864 4150 4865 4151 4865 4764 4865 4733 4866 4729 4866 4735 4866 4727 4867 4725 4867 4721 4867 4717 4868 4713 4868 4719 4868 4705 4869 4709 4869 4707 4869 4699 4870 4697 4870 4701 4870 4701 4871 4697 4871 4703 4871 4695 4872 4693 4872 4689 4872 4679 4873 4677 4873 4673 4873 4673 4874 4677 4874 4675 4874 4667 4875 4665 4875 4669 4875 4657 4876 4661 4876 4659 4876 4653 4877 4649 4877 4655 4877 4747 4878 4745 4878 4749 4878 4749 4879 4745 4879 4754 4879 4763 4880 4059 4880 4762 4880 4732 4881 4734 4881 4730 4881 4730 4882 4734 4882 4736 4882 4726 4883 4722 4883 4724 4883 4716 4884 4718 4884 4714 4884 4714 4885 4718 4885 4720 4885 4698 4886 4702 4886 4704 4886 4696 4887 4690 4887 4694 4887 4682 4888 4686 4888 4688 4888 4680 4889 4674 4889 4678 4889 4678 4890 4674 4890 4676 4890 4662 4891 4658 4891 4660 4891 4650 4892 4654 4892 4656 4892 4648 4893 4998 4893 4647 4893 4744 4894 4738 4894 4742 4894 4204 4895 4201 4895 4148 4895 4201 4896 4147 4896 4148 4896 4635 53 4647 53 4637 53 4637 4897 4647 4897 4999 4897 5002 4898 4139 4898 4140 4898 4140 4899 5003 4899 5002 4899 4142 4900 4139 4900 5002 4900 5004 4901 5006 4901 5007 4901 4124 4902 5003 4902 4141 4902 4124 4903 5008 4903 5003 4903 5008 4904 4124 4904 5005 4904 5005 4905 4124 4905 5006 4905 4125 4906 5006 4906 4124 4906 5006 4907 4125 4907 5010 4907 5011 4908 5012 4908 5013 4908 5014 4909 5015 4909 4426 4909 4426 4910 5016 4910 5014 4910 5010 4911 5011 4911 5013 4911 5012 4912 5015 4912 5014 4912 4135 4913 4108 4913 5018 4913 5019 4914 5018 4914 4107 4914 5023 4915 5021 4915 5025 4915 5026 4916 5025 4916 5027 4916 5026 4917 5023 4917 5025 4917 5022 4918 5028 4918 5020 4918 5028 4919 5024 4919 5030 4919 5024 4920 5031 4920 5030 4920 5030 4921 5031 4921 5032 4921 5031 4922 5023 4922 5026 4922 5031 4923 5026 4923 5033 4923 5031 4924 5033 4924 5032 4924 5032 4925 5033 4925 5034 4925 5034 4926 5033 4926 5026 4926 5027 4927 5035 4927 5026 4927 5026 4928 5035 4928 5034 4928 5025 4929 5036 4929 5027 4929 5027 4930 5036 4930 5035 4930 5036 4931 5038 4931 5037 4931 5021 4932 5020 4932 5025 4932 5038 4933 5020 4933 5039 4933 5039 4934 5020 4934 5029 4934 5041 4935 5040 4935 5043 4935 5041 4936 5043 4936 5044 4936 5047 4937 5046 4937 5040 4937 5040 4938 5042 4938 5048 4938 5047 4939 5040 4939 5048 4939 5043 4940 5046 4940 5045 4940 5045 4941 5046 4941 5050 4941 5050 4942 5047 4942 5051 4942 5049 4943 5053 4943 5052 4943 5052 4944 5053 4944 5054 4944 5055 4945 5048 4945 5042 4945 5056 4946 5042 4946 5057 4946 5058 4947 5059 4947 5060 4947 5061 4948 5058 4948 5062 4948 5065 4949 5058 4949 5066 4949 5058 4950 5061 4950 5066 4950 5061 4951 5068 4951 5067 4951 5068 4952 5062 4952 5064 4952 5064 4953 5070 4953 5068 4953 5063 4954 5072 4954 5071 4954 5072 4955 5060 4955 5073 4955 5060 4956 5065 4956 5074 4956 5077 4957 5081 4957 5078 4957 5082 4958 5079 4958 5078 4958 5085 4959 5080 4959 5086 4959 5086 4960 5080 4960 5079 4960 5083 4961 5088 4961 5087 4961 5082 4962 5090 4962 5088 4962 5089 4963 5090 4963 5091 4963 5090 4964 5082 4964 5081 4964 5093 4965 5094 4965 5081 4965 5081 4966 5094 4966 5092 4966 5081 4967 5077 4967 5093 4967 5077 4968 5076 4968 5093 4968 5094 4969 5076 4969 5084 4969 5099 4970 5095 4970 5098 4970 5097 4971 5101 4971 5098 4971 5102 4972 5098 4972 5101 4972 5104 4973 5095 4973 5105 4973 5095 4974 5100 4974 5105 4974 5106 4975 5100 4975 5099 4975 5103 4976 5107 4976 5099 4976 5103 4977 5102 4977 5108 4977 5107 4978 5108 4978 5109 4978 5108 4979 5110 4979 5109 4979 5109 4980 5110 4980 5111 4980 5111 4981 5101 4981 5112 4981 5101 4982 5114 4982 5112 4982 5101 4983 5097 4983 5113 4983 5115 4984 5116 4984 5117 4984 5118 4985 5115 4985 5117 4985 5119 4986 5115 4986 5118 4986 5117 4987 5121 4987 5118 4987 5122 4988 5118 4988 5121 4988 5116 4989 5115 4989 5124 4989 5124 4990 5115 4990 5125 4990 5125 4991 5120 4991 5126 4991 5123 4992 5127 4992 5119 4992 5127 4993 5128 4993 5129 4993 5122 4994 5130 4994 5128 4994 5129 4995 5130 4995 5131 4995 5133 4996 5134 4996 5121 4996 5121 4997 5134 4997 5132 4997 5117 4998 5116 4998 5133 4998 5133 4999 5116 4999 5134 4999 5137 5000 5141 5000 5138 5000 5142 5001 5139 5001 5138 5001 5144 5002 5135 5002 5145 5002 5135 5003 5140 5003 5145 5003 5145 5004 5140 5004 5146 5004 5146 5005 5140 5005 5139 5005 5143 5006 5142 5006 5148 5006 5147 5007 5148 5007 5149 5007 5148 5008 5150 5008 5149 5008 5149 5009 5150 5009 5151 5009 5150 5010 5142 5010 5141 5010 5150 5011 5141 5011 5151 5011 5151 5012 5141 5012 5152 5012 5153 5013 5154 5013 5141 5013 5137 5014 5136 5014 5153 5014 5155 5015 5156 5015 5157 5015 5157 5016 5161 5016 5158 5016 5162 5017 5159 5017 5158 5017 5155 5018 5160 5018 5165 5018 5159 5019 5167 5019 5166 5019 5163 5020 5162 5020 5168 5020 5163 5021 5168 5021 5167 5021 5162 5022 5170 5022 5168 5022 5168 5023 5170 5023 5169 5023 5169 5024 5170 5024 5171 5024 5173 5025 5174 5025 5161 5025 5173 5026 5156 5026 5174 5026 5175 5027 5176 5027 5177 5027 5175 5028 5179 5028 5180 5028 5182 5029 5178 5029 5181 5029 5182 5030 5179 5030 5178 5030 5176 5031 5175 5031 5184 5031 5184 5032 5175 5032 5185 5032 5175 5033 5180 5033 5185 5033 5185 5034 5180 5034 5186 5034 5186 5035 5180 5035 5179 5035 5183 5036 5187 5036 5179 5036 5179 5037 5187 5037 5186 5037 5183 5038 5182 5038 5188 5038 5182 5039 5190 5039 5188 5039 5191 5040 5181 5040 5192 5040 5195 5041 5196 5041 5197 5041 5195 5042 5199 5042 5200 5042 5202 5043 5198 5043 5201 5043 5199 5044 5202 5044 5203 5044 5196 5045 5195 5045 5204 5045 5205 5046 5200 5046 5206 5046 5203 5047 5207 5047 5199 5047 5203 5048 5202 5048 5208 5048 5203 5049 5208 5049 5207 5049 5208 5050 5210 5050 5209 5050 5209 5051 5210 5051 5211 5051 5210 5052 5201 5052 5211 5052 5201 5053 5214 5053 5212 5053 5213 5054 5196 5054 5214 5054 5218 5055 5215 5055 5219 5055 5220 5056 5219 5056 5217 5056 5219 5057 5220 5057 5221 5057 5216 5058 5215 5058 5222 5058 5222 5059 5215 5059 4429 5059 4429 5060 5218 5060 5223 5060 5224 5061 5219 5061 5221 5061 5221 5062 5226 5062 5224 5062 5224 5063 5226 5063 5225 5063 5228 5064 5220 5064 5217 5064 5228 5065 5217 5065 5229 5065 5229 5066 5217 5066 5230 5066 5216 5067 5222 5067 5217 5067 5217 5068 5222 5068 5230 5068 5231 5069 5232 5069 5233 5069 5234 5070 5231 5070 5233 5070 5237 5071 5236 5071 5235 5071 5233 5072 5238 5072 5234 5072 5239 5073 5234 5073 5238 5073 5239 5074 5235 5074 5234 5074 5237 5075 4427 5075 5236 5075 5235 5076 5241 5076 5237 5076 5240 5077 5239 5077 5242 5077 5240 5078 5242 5078 5241 5078 5241 5079 5242 5079 5243 5079 5242 5080 5244 5080 5243 5080 5244 5081 5239 5081 5238 5081 5245 5082 5244 5082 4439 5082 4439 5083 5244 5083 5238 5083 5238 5084 5011 5084 4439 5084 5233 5085 5232 5085 5246 5085 4127 5086 5010 5086 4126 5086 5248 5087 4293 5087 5249 5087 5249 5088 4293 5088 4357 5088 5249 5089 4071 5089 5250 5089 5251 5090 5249 5090 5250 5090 5250 5091 4071 5091 4072 5091 5249 5092 5251 5092 5254 5092 5255 5093 5256 5093 5254 5093 5256 5094 5258 5094 5254 5094 5254 5095 5258 5095 5259 5095 5259 5096 5258 5096 5260 5096 5261 5097 5258 5097 5262 5097 5260 5098 5263 5098 5259 5098 5259 5099 5263 5099 5264 5099 5266 5100 5265 5100 4474 5100 5266 5101 5268 5101 5264 5101 5264 5102 5268 5102 5269 5102 5272 5103 5270 5103 5273 5103 4458 5104 5271 5104 4459 5104 5270 5105 5271 5105 4458 5105 5275 5106 5273 5106 4448 5106 5275 5107 4448 5107 4447 5107 5272 5108 5276 5108 5277 5108 5278 5109 5272 5109 5277 5109 5279 5110 4440 5110 3947 5110 5002 5111 5247 5111 4142 5111 3956 5112 4434 5112 5247 5112 4293 5113 5280 5113 4294 5113 4294 5114 5280 5114 4295 5114 4295 5115 5280 5115 4359 5115 4425 5116 4336 5116 4422 5116 4422 5117 4113 5117 4426 5117 4426 5118 4114 5118 4115 5118 4427 5119 5237 5119 4424 5119 4426 5120 5015 5120 4427 5120 5012 5121 5011 5121 5281 5121 5011 5122 4127 5122 4439 5122 5237 5123 5241 5123 4428 5123 5237 5124 4428 5124 4424 5124 4428 5125 5243 5125 4431 5125 4428 5126 5241 5126 5243 5126 4130 5127 4129 5127 4147 5127 5285 5128 5286 5128 5287 5128 5012 5129 5014 5129 5013 5129 5004 5130 5299 5130 5284 5130 5016 5131 5017 5131 5298 5131 5296 5132 5301 5132 5295 5132 5305 5133 5292 5133 5293 5133 5292 5134 5306 5134 5291 5134 5288 5135 5307 5135 5286 5135 5307 5136 5287 5136 5286 5136 5308 5137 4803 5137 5309 5137 4799 5138 5308 5138 5310 5138 4780 5139 5315 5139 5316 5139 4777 5140 4778 5140 5302 5140 4799 5141 5310 5141 4796 5141 4791 5142 5313 5142 4788 5142 4788 5143 5313 5143 4784 5143 4782 5144 5315 5144 4781 5144 5302 5145 4778 5145 5303 5145 5318 5146 5294 5146 5317 5146 5294 5147 5318 5147 5304 5147 5319 5148 5305 5148 5304 5148 5305 5149 5319 5149 5320 5149 5306 5150 5320 5150 5321 5150 5322 5151 5306 5151 5321 5151 5322 5152 5290 5152 5306 5152 5323 5153 5288 5153 5290 5153 5324 5154 5325 5154 5307 5154 5287 5155 5325 5155 5326 5155 5326 5156 5327 5156 5287 5156 4807 5157 5282 5157 5328 5157 5307 5158 5325 5158 5287 5158 5328 5159 5309 5159 4805 5159 4777 5160 5301 5160 4775 5160 5009 5161 5004 5161 5283 5161 4876 5162 5297 5162 5295 5162 5297 5163 4874 5163 4872 5163 5298 5164 4868 5164 4866 5164 5014 5165 4866 5165 4865 5165 5014 5166 4865 5166 4864 5166 4864 5167 4863 5167 5013 5167 5010 5168 4862 5168 4860 5168 5007 5169 4858 5169 4856 5169 5299 5170 4856 5170 4854 5170 5299 5171 4854 5171 4852 5171 5284 5172 4850 5172 4848 5172 5286 5173 4848 5173 4846 5173 5286 5174 4846 5174 4844 5174 5289 5175 4842 5175 4840 5175 5284 5176 4848 5176 5286 5176 5289 5177 4838 5177 5291 5177 5291 5178 4834 5178 4832 5178 5293 5179 4832 5179 4830 5179 5295 5180 4826 5180 4824 5180 5291 5181 4832 5181 5293 5181 4137 5182 4061 5182 5003 5182 4061 5183 4060 5183 5003 5183 5264 5184 5332 5184 5333 5184 5248 5185 5336 5185 5337 5185 5278 5186 5330 5186 5272 5186 5272 5187 5331 5187 5270 5187 5270 5188 5332 5188 5264 5188 5264 5189 5333 5189 5259 5189 4137 5190 5003 5190 4146 5190 4810 5191 4808 5191 4809 5191 4819 5192 4775 5192 5338 5192 4775 5193 4819 5193 4773 5193 4773 5194 4776 5194 4775 5194 5301 5195 5296 5195 4775 5195 4775 5196 5296 5196 5338 5196 4129 5197 4333 5197 4149 5197 4149 5198 4333 5198 3951 5198 3961 5199 4313 5199 4308 5199 3962 5200 4308 5200 4304 5200 3964 5201 4304 5201 4301 5201 3966 5202 3964 5202 4301 5202 3951 5203 4328 5203 3959 5203 3959 5204 4326 5204 3969 5204 3969 5205 4322 5205 3975 5205 3980 5206 4313 5206 3961 5206 3961 5207 4308 5207 3962 5207 3962 5208 4304 5208 3964 5208 5017 5209 4133 5209 5339 5209 5339 5210 4134 5210 4333 5210 5017 5211 5340 5211 5300 5211 5339 5212 5340 5212 5017 5212 5340 5213 5329 5213 5300 5213 4060 5214 4058 5214 3953 5214 3953 5215 3955 5215 5341 5215 5343 5216 5341 5216 5342 5216 5343 5217 5344 5217 5341 5217 5341 5218 5345 5218 5331 5218 5331 5219 5350 5219 5351 5219 5332 5220 5351 5220 5333 5220 5352 5221 5353 5221 5351 5221 5354 5222 5355 5222 5351 5222 5353 5223 5354 5223 5351 5223 5351 5224 5355 5224 5333 5224 5356 5225 5357 5225 5333 5225 5358 5226 5359 5226 5333 5226 5333 5227 5359 5227 5334 5227 5362 5228 5363 5228 5335 5228 5363 5229 5364 5229 5335 5229 5336 5230 5364 5230 5365 5230 5365 5231 5337 5231 5336 5231 5365 5232 5366 5232 5337 5232 5364 5233 5367 5233 5365 5233 5356 5234 5267 5234 5371 5234 5355 5235 5372 5235 5356 5235 5372 5236 5373 5236 4475 5236 5353 5237 5374 5237 5354 5237 5352 5238 5376 5238 5377 5238 5377 5239 5376 5239 4462 5239 5376 5240 5350 5240 5378 5240 5380 5241 5348 5241 5381 5241 5382 5242 5345 5242 5384 5242 5343 5243 5388 5243 5387 5243 5342 5244 3955 5244 5389 5244 5389 5245 3955 5245 5391 5245 3955 5246 5279 5246 5391 5246 3953 5247 4055 5247 3954 5247 4057 5248 5394 5248 4055 5248 4057 5249 5396 5249 5395 5249 4057 5250 5397 5250 5396 5250 4057 5251 5398 5251 5397 5251 5405 5252 5406 5252 5407 5252 5366 5253 5406 5253 5368 5253 5403 5254 5404 5254 5408 5254 5403 5255 5408 5255 5409 5255 5401 5256 5402 5256 5410 5256 5411 5257 5410 5257 5412 5257 5362 5258 5412 5258 5363 5258 5413 5259 5400 5259 5414 5259 5414 5260 5415 5260 5413 5260 5399 5261 5400 5261 5413 5261 5397 5262 5416 5262 5417 5262 5418 5263 5359 5263 5358 5263 5371 5264 5396 5264 5419 5264 5395 5265 5396 5265 5371 5265 5421 5266 4055 5266 5420 5266 5421 5267 5422 5267 4055 5267 5422 5268 5421 5268 5377 5268 5424 53 5420 53 5394 53 5425 5269 5373 5269 5355 5269 5425 5270 5355 5270 5354 5270 5423 5271 5353 5271 5352 5271 5383 5272 5430 5272 5348 5272 5431 5273 5379 5273 5350 5273 5429 5274 5432 5274 4055 5274 5436 5275 5390 5275 5435 5275 3954 5276 5392 5276 3955 5276 5439 5277 4324 5277 3996 5277 3996 5278 4324 5278 4014 5278 3979 5279 5440 5279 3996 5279 5440 5280 3979 5280 5441 5280 3981 5281 3995 5281 5442 5281 5444 5282 4347 5282 3994 5282 3994 5283 3982 5283 5444 5283 3984 5284 5446 5284 4349 5284 3984 5285 5445 5285 3982 5285 3983 5286 3987 5286 5447 5286 5449 5287 4389 5287 4035 5287 3985 5288 3986 5288 5449 5288 5449 5289 3986 5289 5450 5289 4044 5290 5450 5290 3986 5290 5452 5291 4311 5291 4041 5291 4053 5292 4353 5292 3989 5292 4135 5293 4334 5293 4333 5293 4333 5294 4134 5294 4135 5294 5454 5295 5455 5295 5456 5295 5456 5296 5455 5296 5457 5296 5460 5297 5459 5297 5461 5297 5456 5298 5457 5298 5458 5298 5458 5299 5459 5299 5460 5299 5460 5300 5461 5300 4219 5300 4219 5301 4048 5301 5460 5301 3993 5302 3967 5302 5458 5302 5458 5303 3967 5303 5456 5303 3968 5304 5456 5304 3967 5304 3968 5305 5454 5305 5456 5305 5463 5306 3968 5306 5462 5306 5463 5307 5454 5307 3968 5307 5464 5308 4231 5308 4227 5308 5465 5309 4227 5309 4229 5309 5466 5310 4229 5310 4230 5310 5464 5311 4227 5311 5465 5311 5466 5312 4230 5312 5467 5312 5467 5313 5370 5313 5369 5313 5369 5314 5466 5314 5467 5314 5466 5315 5369 5315 5368 5315 5406 5316 5465 5316 5368 5316 4220 5317 4231 5317 4223 5317 4753 5318 4223 5318 5464 5318 4279 5319 4251 5319 4248 5319 5469 5320 4248 5320 4250 5320 4254 5321 5469 5321 4250 5321 5469 5322 4254 5322 4261 5322 5470 53 4217 53 5471 53 5472 53 5457 53 5455 53 5473 53 5472 53 5455 53 5473 53 5474 53 5472 53 5474 53 5475 53 5476 53 5476 5323 5475 5323 5477 5323 5478 5324 4278 5324 4279 5324 4248 5325 5479 5325 5478 5325 5479 53 4261 53 5480 53 4261 5326 4213 5326 5480 5326 5480 5327 4213 5327 5470 5327 4026 5328 4048 5328 5001 5328 5481 5329 4026 5329 5001 5329 4048 5330 4219 5330 5001 5330 4214 5331 4263 5331 4215 5331 5001 5332 4219 5332 4216 5332 4026 5333 5481 5333 3998 5333 3998 5334 5481 5334 3999 5334 4743 5335 4737 5335 5481 5335 4729 5336 4727 5336 5481 5336 4721 5337 4719 5337 5481 5337 4703 5338 4697 5338 5481 5338 5481 5339 4697 5339 4695 5339 4687 5340 4681 5340 4152 5340 4689 5341 4687 5341 4152 5341 4679 5342 4673 5342 4152 5342 4671 5343 4665 5343 4152 5343 4673 5344 4671 5344 4152 5344 4663 5345 4657 5345 4152 5345 4665 5346 4663 5346 4152 5346 4655 5347 4649 5347 4152 5347 4657 5348 4655 5348 4152 5348 4649 5349 4646 5349 4152 5349 4745 5350 4743 5350 5481 5350 4743 5351 4741 5351 4737 5351 5011 5352 5246 5352 5281 5352 5281 5353 5246 5353 5232 5353 5482 5354 5309 5354 5328 5354 5308 5355 5484 5355 5485 5355 5311 5356 5487 5356 5488 5356 5312 5357 5488 5357 5489 5357 5314 5358 5490 5358 5491 5358 5491 5359 5315 5359 5314 5359 5316 5360 5315 5360 5493 5360 5308 5361 5485 5361 5310 5361 4778 5362 5495 5362 5316 5362 5497 5363 5317 5363 5496 5363 5318 5364 5497 5364 5498 5364 4778 5365 5495 5365 5496 5365 5318 5366 5498 5366 5319 5366 5499 5367 5500 5367 5319 5367 5500 5368 5501 5368 5320 5368 5501 5369 5502 5369 5320 5369 5320 5370 5502 5370 5321 5370 5321 5371 5502 5371 5503 5371 5504 5372 5506 5372 5507 5372 5507 5373 5506 5373 5508 5373 5509 5374 5507 5374 5508 5374 5510 5375 5509 5375 5511 5375 5509 5376 5510 5376 5512 5376 5511 5377 5509 5377 5513 5377 5511 5378 5514 5378 5510 5378 5514 5379 5511 5379 5515 5379 5514 5380 5516 5380 5510 5380 5519 5381 5511 5381 5513 5381 5513 5382 5509 5382 5520 5382 5524 5383 5515 5383 5519 5383 5519 5384 5515 5384 5511 5384 5512 5385 5510 5385 5516 5385 5507 5386 5509 5386 5525 5386 5526 5387 5507 5387 5525 5387 5507 5388 5526 5388 5504 5388 5527 5389 5528 5389 5529 5389 5529 5390 5528 5390 5530 5390 5530 5391 5528 5391 5531 5391 5526 5392 5528 5392 5527 5392 5525 5393 5530 5393 5531 5393 5533 5394 5530 5394 5525 5394 5536 5395 5537 5395 5538 5395 5532 5396 5536 5396 5539 5396 5534 5397 5541 5397 5535 5397 5535 5398 5541 5398 5523 5398 5540 5399 5535 5399 5523 5399 5538 5400 5537 5400 5539 5400 5483 5401 5542 5401 5543 5401 5484 5402 5543 5402 5544 5402 5544 5403 5485 5403 5484 5403 5485 5404 5544 5404 5516 5404 5516 5405 5544 5405 5545 5405 5546 5406 5516 5406 5545 5406 5546 5407 5512 5407 5516 5407 5512 5408 5546 5408 5503 5408 5503 5409 5533 5409 5512 5409 5503 5410 5502 5410 5533 5410 5533 5411 5502 5411 5547 5411 5536 5412 5501 5412 5500 5412 5522 5413 5499 5413 5492 5413 5491 5414 5522 5414 5492 5414 5517 5415 5491 5415 5490 5415 5494 5416 5497 5416 5496 5416 5493 5417 5497 5417 5494 5417 5489 5418 5488 5418 5521 5418 5521 5419 5488 5419 5508 5419 5508 5420 5488 5420 5520 5420 5524 5421 5486 5421 5485 5421 5520 5422 5487 5422 5519 5422 5487 5423 5520 5423 5488 5423 5534 5424 5522 5424 5541 5424 5540 5425 5526 5425 5527 5425 5532 5426 5540 5426 5527 5426 5526 5427 5531 5427 5528 5427 5526 5428 5525 5428 5531 5428 5525 5429 5512 5429 5533 5429 5533 5430 5547 5430 5532 5430 5532 5431 5547 5431 5536 5431 5534 5432 5523 5432 5536 5432 5536 5433 5523 5433 5537 5433 5537 5434 5523 5434 5535 5434 5536 5435 5500 5435 5534 5435 5542 5436 5327 5436 5326 5436 5542 5437 5482 5437 5327 5437 5482 5438 5328 5438 5327 5438 5543 5439 5325 5439 5544 5439 5545 5440 5323 5440 5546 5440 5546 5441 5322 5441 5503 5441 4293 5442 5248 5442 5548 5442 5549 5443 5550 5443 4293 5443 4293 5444 5550 5444 5280 5444 5552 5445 5555 5445 5554 5445 5554 5446 5555 5446 5556 5446 5558 6 5556 6 5557 6 5561 6 5560 6 5562 6 5568 6 5570 6 5569 6 5561 5447 5562 5447 5563 5447 5566 5448 5564 5448 5572 5448 5280 6 5577 6 5578 6 5280 5449 5579 5449 5577 5449 5280 6 5550 6 5580 6 5580 5450 5549 5450 5570 5450 5586 6 5582 6 5585 6 5586 5451 5588 5451 5587 5451 5588 6 5589 6 4302 6 5588 6 4302 6 5578 6 5585 5452 5551 5452 5553 5452 5565 6 5563 6 5564 6 5575 6 5573 6 5574 6 5583 5453 5572 5453 5581 5453 5581 5454 5572 5454 5564 5454 5589 5455 5586 5455 4300 5455 4301 5456 4300 5456 5462 5456 5462 5457 5586 5457 5463 5457 5590 5458 5592 5458 5593 5458 5590 5459 5591 5459 5592 5459 5590 5460 5594 5460 5559 5460 5554 5461 5556 5461 4277 5461 5595 5462 5463 5462 5553 5462 5463 5463 5585 5463 5553 5463 5589 5464 4300 5464 4302 5464 5594 5465 5593 5465 4234 5465 4236 5466 4238 5466 4276 5466 5468 5467 4232 5467 5591 5467 5591 5468 5548 5468 5370 5468 5596 5469 5477 5469 5475 5469 5595 5470 5473 5470 5455 5470 5463 5471 5595 5471 5455 5471 5597 5472 5473 5472 5595 5472 4224 5473 5599 5473 4226 5473 4226 5474 5599 5474 5600 5474 4228 5475 5600 5475 5601 5475 4233 5476 5601 5476 5602 5476 4225 5477 5605 5477 5598 5477 5606 5478 5599 5478 5598 5478 5601 5479 5608 5479 5609 5479 5603 5480 5611 5480 5612 5480 5598 5481 5605 5481 5607 5481 5600 5482 5608 5482 5601 5482 5601 5483 5609 5483 5602 5483 5602 5484 5611 5484 5603 5484 5603 5485 5612 5485 5604 5485 5604 5486 5607 5486 5605 5486 5471 5487 5614 5487 5615 5487 5476 5488 5618 5488 5619 5488 5472 5489 5620 5489 5613 5489 5471 5490 5615 5490 5470 5490 5480 5491 5616 5491 5479 5491 5479 5492 5618 5492 5478 5492 5478 5493 5618 5493 5476 5493 5621 5494 5614 5494 5613 5494 5615 5495 5621 5495 5623 5495 5618 5496 5626 5496 5627 5496 5619 5497 5627 5497 5622 5497 5613 5498 5620 5498 5622 5498 5616 5499 5624 5499 5617 5499 5619 5500 5622 5500 5620 5500 5583 5501 5628 5501 5630 5501 5588 5502 5633 5502 5634 5502 5587 5503 5635 5503 5629 5503 5572 5504 5631 5504 5574 5504 5578 5505 5633 5505 5588 5505 5588 5506 5635 5506 5587 5506 5630 5507 5628 5507 5631 5507 5636 5508 5566 5508 5573 5508 5570 5509 5638 5509 5639 5509 5580 5510 5639 5510 5640 5510 5575 5511 5641 5511 5642 5511 5579 5512 5641 5512 5577 5512 5642 5513 5637 5513 5636 5513 5641 5514 5643 5514 5642 5514 5638 5515 5643 5515 5639 5515 5640 5516 5643 5516 5641 5516 5644 5517 5557 5517 5561 5517 5557 5518 5645 5518 5558 5518 5567 5519 5648 5519 5649 5519 5565 5520 5649 5520 5650 5520 5563 5521 5650 5521 5644 5521 5561 5522 5563 5522 5644 5522 5558 5523 5646 5523 5559 5523 5567 5524 5649 5524 5565 5524 5565 5525 5650 5525 5563 5525 5651 5526 5645 5526 5644 5526 5651 5527 5652 5527 5645 5527 5648 5528 5654 5528 5655 5528 5649 5529 5656 5529 5657 5529 5650 5530 5657 5530 5651 5530 5648 5531 5656 5531 5649 5531 5649 5532 5657 5532 5650 5532 5552 5533 5658 5533 5660 5533 5562 5534 5661 5534 5662 5534 5552 5535 5660 5535 5555 5535 5555 5536 5660 5536 5560 5536 5560 5537 5661 5537 5562 5537 5581 5538 5664 5538 5584 5538 5584 5539 5659 5539 5551 5539 5660 5540 5666 5540 5667 5540 5662 5541 5668 5541 5669 5541 5659 5542 5671 5542 5665 5542 5660 5543 5667 5543 5661 5543 5661 5544 5668 5544 5662 5544 5663 5545 5670 5545 5664 5545 5664 5546 5671 5546 5659 5546 5634 5547 5631 5547 5672 5547 5637 5548 5642 5548 5643 5548 5622 5549 5673 5549 5665 5549 5666 5550 5665 5550 5673 5550 5675 5551 5671 5551 5670 5551 5677 5552 5667 5552 5666 5552 5627 5553 5677 5553 5666 5553 5626 5554 5625 5554 5668 5554 5668 5555 5625 5555 5676 5555 5669 5556 5624 5556 5623 5556 5675 5557 5623 5557 5621 5557 5676 5558 5624 5558 5669 5558 5670 5559 5623 5559 5675 5559 5671 5560 5621 5560 5674 5560 5607 5561 5612 5561 5678 5561 5680 5562 5657 5562 5656 5562 5682 5563 5653 5563 5652 5563 5612 5564 5611 5564 5682 5564 5611 5565 5610 5565 5654 5565 5653 5566 5611 5566 5654 5566 5651 5567 5679 5567 5607 5567 5681 5568 5609 5568 5655 5568 5656 5569 5608 5569 5680 5569 5680 5570 5606 5570 5657 5570 5683 5571 5347 5571 5437 5571 5689 5572 4003 5572 5690 5572 5690 5573 4003 5573 4004 5573 5394 5574 5395 5574 5691 5574 5691 5575 5395 5575 5692 5575 5692 5576 5395 5576 5371 5576 4487 5577 5418 5577 5416 5577 5693 5578 4487 5578 5398 5578 5398 5579 5399 5579 5693 5579 5693 5580 5399 5580 5694 5580 4489 5581 5412 5581 5410 5581 5695 5582 4489 5582 5402 5582 5446 5583 3984 5583 4029 5583 5446 5584 4029 5584 4027 5584 5446 5585 4020 5585 5697 5585 3990 5586 4040 5586 4310 5586 4310 5587 4040 5587 5698 5587 5699 5588 4040 5588 4038 5588 5701 5589 4053 5589 4050 5589 5701 5590 4039 5590 5702 5590 4315 5591 4044 5591 5703 5591 5703 5592 4042 5592 4036 5592 4036 5593 4032 5593 5703 5593 5703 5594 4032 5594 5704 5594 5704 5595 4032 5595 4033 5595 5706 5596 4051 5596 4052 5596 5707 5597 5706 5597 4052 5597 5705 5598 4051 5598 5706 5598 3991 5599 5708 5599 4052 5599 4052 5600 5708 5600 5707 5600 3987 5601 4034 5601 5448 5601 3995 5602 4022 5602 5443 5602 5443 5603 4022 5603 4348 5603 4017 5604 4011 5604 5709 5604 4324 5605 4012 5605 4014 5605 5354 5606 5375 5606 5425 5606 5358 5607 5711 5607 5712 5607 5357 5608 5419 5608 5711 5608 5361 5609 5713 5609 5362 5609 5362 5610 5713 5610 5714 5610 5713 5611 5414 5611 5715 5611 5366 5612 5365 5612 5716 5612 5365 5613 5717 5613 5716 5613 4074 5614 5719 5614 4090 5614 4081 5615 4083 5615 5721 5615 5721 5616 4083 5616 4087 5616 5041 5617 5044 5617 5042 5617 5042 5618 5044 5618 5057 5618 3930 5619 3932 5619 3938 5619 3971 5620 4005 5620 5722 5620 5722 5621 4005 5621 5724 5621 5725 5622 4009 5622 5727 5622 4343 5623 5728 5623 4016 5623 5727 5624 4016 5624 5728 5624 4016 5625 5729 5625 4343 5625 5731 5626 5430 5626 5428 5626 4448 5627 5430 5627 5731 5627 5428 5628 5427 5628 5731 5628 5731 5629 5427 5629 5732 5629 5732 5630 5427 5630 5431 5630 5349 5631 5380 5631 5431 5631 5431 5632 5380 5632 4458 5632 4452 5633 5734 5633 5438 5633 5735 5634 5435 5634 4449 5634 3941 5635 3957 5635 3939 5635 3939 5636 3957 5636 3948 5636 4434 5637 3956 5637 3945 5637 3956 5638 5247 5638 3957 5638 3948 5639 3957 5639 5278 5639 3948 5640 5279 5640 3947 5640 5391 5641 5736 5641 5389 5641 5737 5642 5735 5642 4441 5642 5393 5643 5435 5643 5737 5643 4450 5644 5276 5644 5388 5644 5738 5645 4441 5645 4450 5645 5738 5646 5436 5646 5434 5646 5683 5647 5684 5647 4444 5647 5683 5648 4444 5648 4443 5648 5385 5649 5274 5649 5384 5649 5274 5650 5385 5650 4453 5650 5272 5651 5273 5651 5274 5651 5382 5652 5384 5652 5274 5652 5274 5653 5275 5653 5382 5653 5275 5654 4447 5654 5382 5654 5684 5655 5429 5655 4447 5655 5732 5656 5733 5656 4455 5656 4448 5657 5273 5657 5381 5657 5381 5658 5273 5658 5380 5658 5270 5659 4458 5659 5380 5659 4455 5660 4444 5660 5731 5660 4455 5661 5731 5661 5732 5661 4448 5662 5731 5662 4444 5662 5739 5663 4461 5663 4455 5663 4422 5664 4416 5664 5740 5664 4422 5665 5740 5665 4425 5665 4332 5666 5740 5666 5741 5666 5740 5667 4416 5667 5741 5667 4332 5668 4330 5668 3938 5668 4335 5669 3937 5669 3936 5669 5686 5670 4338 5670 5685 5670 5742 5671 4337 5671 4329 5671 4338 5672 4337 5672 5685 5672 4331 5673 5742 5673 4329 5673 4331 5674 4332 5674 5741 5674 5741 5675 3952 5675 4006 5675 5744 5676 4412 5676 4339 5676 5723 5677 5722 5677 4329 5677 5723 5678 4338 5678 4420 5678 4007 5679 5723 5679 4420 5679 5743 5680 4001 5680 4007 5680 5743 5681 4007 5681 4420 5681 5689 5682 5690 5682 4412 5682 4339 5683 4412 5683 5690 5683 4339 5684 5690 5684 5745 5684 4341 5685 4340 5685 5746 5685 5728 5686 4407 5686 5727 5686 5726 5687 4323 5687 5747 5687 5729 5688 4323 5688 4340 5688 4407 5689 4402 5689 5725 5689 4407 5690 5725 5690 5727 5690 4325 5691 5726 5691 5725 5691 5748 5692 4474 5692 4469 5692 4469 5693 4461 5693 5749 5693 4463 5694 5268 5694 5374 5694 5748 5695 5425 5695 4474 5695 4469 5696 4475 5696 5691 5696 5691 5697 5692 5697 4476 5697 5691 5698 4476 5698 4469 5698 4480 5699 4476 5699 5692 5699 4475 5700 5265 5700 5372 5700 5750 5701 4486 5701 4478 5701 4478 5702 4476 5702 5752 5702 5752 5703 4476 5703 4481 5703 5263 5704 5260 5704 5711 5704 5712 5705 5711 5705 5260 5705 5358 5706 5712 5706 5417 5706 5750 5707 5397 5707 5417 5707 4478 5708 4487 5708 5693 5708 5693 5709 5694 5709 4384 5709 5261 5710 5754 5710 5753 5710 5754 5711 5261 5711 5755 5711 5694 5712 5755 5712 5262 5712 5756 5713 4488 5713 4385 5713 5756 5714 4385 5714 4384 5714 5262 5715 5715 5715 4384 5715 5757 5716 4384 5716 5715 5716 5262 5717 5713 5717 5715 5717 5258 5718 5256 5718 5713 5718 5713 5719 5256 5719 5714 5719 5758 5720 5714 5720 5256 5720 5362 5721 5714 5721 5411 5721 5756 5722 5401 5722 4488 5722 5759 5723 5257 5723 5255 5723 5760 5724 5251 5724 5252 5724 5696 5725 5252 5725 5253 5725 5695 5726 5696 5726 4491 5726 5695 5727 4491 5727 4385 5727 5709 5728 5710 5728 4402 5728 5709 5729 4402 5729 4399 5729 4325 5730 4402 5730 5710 5730 4345 5731 4344 5731 5441 5731 4344 5732 5440 5732 5441 5732 5440 5733 4344 5733 5761 5733 4344 5734 4321 5734 5761 5734 4324 5735 5439 5735 5761 5735 4323 5736 4324 5736 5761 5736 4345 5737 4399 5737 5762 5737 4399 5738 4394 5738 5763 5738 4399 5739 5763 5739 5762 5739 4348 5740 4320 5740 5443 5740 5442 5741 5443 5741 4320 5741 4344 5742 4320 5742 4321 5742 4320 5743 4344 5743 5442 5743 4346 5744 5442 5744 4344 5744 4025 5745 5442 5745 4346 5745 4350 5746 5446 5746 4392 5746 5446 5747 5697 5747 4394 5747 5446 5748 4394 5748 4392 5748 5446 5749 4350 5749 4349 5749 5444 5750 5445 5750 4319 5750 5445 5751 4349 5751 4319 5751 4349 5752 4318 5752 4319 5752 4347 5753 5444 5753 4319 5753 5697 5754 4021 5754 4347 5754 4347 5755 4021 5755 4023 5755 5764 5756 4350 5756 4392 5756 4392 5757 4388 5757 5766 5757 4392 5758 5766 5758 5764 5758 4389 5759 4314 5759 4390 5759 4390 5760 4314 5760 5448 5760 4314 5761 4318 5761 5447 5761 5448 5762 4314 5762 5447 5762 4318 5763 4350 5763 5447 5763 5765 5764 5447 5764 4350 5764 3983 5765 5447 5765 4030 5765 4030 5766 5447 5766 5765 5766 5767 5767 4316 5767 4376 5767 4312 5768 4316 5768 5451 5768 5767 5769 5451 5769 4316 5769 5700 5770 4037 5770 4043 5770 5700 5771 4043 5771 5767 5771 5768 5772 4353 5772 4307 5772 5453 5773 4353 5773 5768 5773 4307 5774 4309 5774 5768 5774 5453 5775 5768 5775 5452 5775 4311 5776 5452 5776 5768 5776 4309 5777 4311 5777 5768 5777 5701 5778 5702 5778 4371 5778 4358 5779 5770 5779 5769 5779 5253 5780 5251 5780 5717 5780 5717 5781 5250 5781 5716 5781 5366 5782 5716 5782 5407 5782 5407 5783 5716 5783 4494 5783 5706 5784 4354 5784 5705 5784 5705 5785 4354 5785 4368 5785 4355 5786 4306 5786 5771 5786 5708 5787 4354 5787 5707 5787 5706 5788 5707 5788 4354 5788 5705 5789 4368 5789 5772 5789 4368 5790 4355 5790 5772 5790 5772 5791 4355 5791 5771 5791 4047 5792 4046 5792 5772 5792 4316 5793 4315 5793 5703 5793 5450 5794 4315 5794 4312 5794 5449 5795 4314 5795 4389 5795 5703 5796 5704 5796 4388 5796 4389 5797 4388 5797 5704 5797 5704 5798 4033 5798 4035 5798 4367 5799 4089 5799 4364 5799 4089 5800 4090 5800 4363 5800 4089 5801 4363 5801 4364 5801 4090 5802 5719 5802 4363 5802 4362 5803 5719 5803 4361 5803 4361 5804 5719 5804 5720 5804 4361 5805 5720 5805 4360 5805 5720 5806 5721 5806 4360 5806 5721 5807 4087 5807 4493 5807 5721 5808 4493 5808 4360 5808 4087 5809 4086 5809 4493 5809 4493 5810 4086 5810 4367 5810 5037 5811 4497 5811 5035 5811 5037 5812 5039 5812 4499 5812 4499 5813 5039 5813 4370 5813 5029 5814 5028 5814 4366 5814 5029 5815 4366 5815 4365 5815 4366 5816 5030 5816 4500 5816 5030 5817 5032 5817 4500 5817 4500 5818 5032 5818 4495 5818 5032 5819 5034 5819 4492 5819 5032 5820 4492 5820 4495 5820 5034 5821 4497 5821 4492 5821 5054 5822 4375 5822 4387 5822 4375 5823 4501 5823 4387 5823 5054 5824 5056 5824 4375 5824 4375 5825 5056 5825 4372 5825 5056 5826 5057 5826 4369 5826 5056 5827 4369 5827 4372 5827 5044 5828 4498 5828 5057 5828 4498 5829 5045 5829 4496 5829 5045 5830 5050 5830 4496 5830 5050 5831 5051 5831 4386 5831 5065 5832 5066 5832 4381 5832 5066 5833 4379 5833 4381 5833 5066 5834 4377 5834 4379 5834 5067 5835 5069 5835 4373 5835 5069 5836 4374 5836 4373 5836 4374 5837 5070 5837 5071 5837 5084 5838 4484 5838 5094 5838 5084 5839 5085 5839 4391 5839 5085 5840 4378 5840 4391 5840 5086 5841 5087 5841 4379 5841 4379 5842 5087 5842 5089 5842 4380 5843 5091 5843 4382 5843 5092 5844 4484 5844 4477 5844 5104 5845 5105 5845 4393 5845 5104 5846 4393 5846 4397 5846 5105 5847 5106 5847 4398 5847 5105 5848 4398 5848 4393 5848 5111 5849 5112 5849 4471 5849 4467 5850 4466 5850 5134 5850 5124 5851 4467 5851 5134 5851 5125 5852 4395 5852 4400 5852 5126 5853 4396 5853 4395 5853 4472 5854 5131 5854 4470 5854 5131 5855 4464 5855 4470 5855 5132 5856 4466 5856 4464 5856 4465 5857 5147 5857 5149 5857 5149 5858 5151 5858 4465 5858 4465 5859 5151 5859 4460 5859 5152 5860 5154 5860 4457 5860 5152 5861 4457 5861 4456 5861 5164 5862 4411 5862 5174 5862 5174 5863 4411 5863 4508 5863 5164 5864 5165 5864 4408 5864 5164 5865 4408 5865 4411 5865 5165 5866 4404 5866 4408 5866 4405 5867 5167 5867 5169 5867 4502 5868 5169 5868 4454 5868 5171 5869 5172 5869 4446 5869 5171 5870 4446 5870 4454 5870 5172 5871 5174 5871 4508 5871 5172 5872 4508 5872 4446 5872 5184 5873 5185 5873 4506 5873 4506 5874 5185 5874 4413 5874 5185 5875 5186 5875 4409 5875 5185 5876 4409 5876 4413 5876 5186 5877 4410 5877 4409 5877 4410 5878 5189 5878 4507 5878 4410 5879 5187 5879 5189 5879 5189 5880 5191 5880 4507 5880 5191 5881 5192 5881 4442 5881 5191 5882 4442 5882 4445 5882 5214 5883 4419 5883 4438 5883 5204 5884 5205 5884 4415 5884 5204 5885 4415 5885 4419 5885 5206 5886 4505 5886 4421 5886 4505 5887 5207 5887 4503 5887 5209 5888 5211 5888 4503 5888 5211 5889 4437 5889 4451 5889 4429 5890 5223 5890 4423 5890 5223 5891 5225 5891 4417 5891 5225 5892 4418 5892 4417 5892 4418 5893 5226 5893 5227 5893 5227 5894 5229 5894 4436 5894 5229 5895 5230 5895 4433 5895 5229 5896 4433 5896 4436 5896 4306 5897 3991 5897 3992 5897 4348 5898 4022 5898 5763 5898 4481 5899 5419 5899 5752 5899 5359 5900 5753 5900 5360 5900 5415 5901 5754 5901 5755 5901 5754 5902 5415 5902 5360 5902 5364 5903 5759 5903 5760 5903 5718 5904 5408 5904 5770 5904 5280 5905 4302 5905 4359 5905 3992 5906 4049 5906 4306 5906 4332 5907 3932 5907 3935 5907 4332 5908 3935 5908 5740 5908 3935 5909 3934 5909 5740 5909 3949 5910 5742 5910 4006 5910 5685 5911 4337 5911 3973 5911 3972 5912 3973 5912 4337 5912 3949 5913 4337 5913 5742 5913 5744 5914 4005 5914 4002 5914 5724 5915 4005 5915 5744 5915 4002 5916 4001 5916 5744 5916 3976 5917 4013 5917 5747 5917 5747 5918 4013 5918 5726 5918 3974 5919 5747 5919 5729 5919 5763 5920 4018 5920 5762 5920 3977 5921 3978 5921 4341 5921 5396 5922 5397 5922 5752 5922 5343 5923 5436 5923 5388 5923 4440 5924 5392 5924 3954 5924 5400 5925 5401 5925 5757 5925 5757 5926 5401 5926 5756 5926 5247 5927 4118 5927 4122 5927 4142 5928 5247 5928 4122 5928 5773 5929 4206 5929 4986 5929 4986 5930 5774 5930 5773 5930 5776 5931 4988 5931 4995 5931 4212 5932 4995 5932 4996 5932 4209 5933 4978 5933 4979 5933 4207 5934 4985 5934 4986 5934 4207 5935 4208 5935 4985 5935 4208 5936 4209 5936 4979 5936 4212 5937 5777 5937 4995 5937 4194 5938 4912 5938 4861 5938 4859 5939 4911 5939 4916 5939 4847 5940 4918 5940 4919 5940 4825 5941 4976 5941 4977 5941 4821 5942 4977 5942 4905 5942 4905 5943 4873 5943 4875 5943 4859 5944 4916 5944 4857 5944 4853 5945 4855 5945 4851 5945 4855 5946 4177 5946 4851 5946 4847 5947 4919 5947 4845 5947 4845 5948 4919 5948 4843 5948 4835 5949 4933 5949 4831 5949 4833 5950 4835 5950 4831 5950 4827 5951 4976 5951 4825 5951 4933 5952 4835 5952 4837 5952 4867 5953 4869 5953 4871 5953 4790 53 4934 53 4792 53 5776 5954 4936 5954 4938 5954 5774 5955 4938 5955 4932 5955 5775 5956 4938 5956 5774 5956 5778 5957 5779 5957 5780 5957 5781 5958 5780 5958 5782 5958 5783 5959 5779 5959 5784 5959 5781 5960 5785 5960 5780 5960 5780 5961 5785 5961 5778 5961 5787 5962 5788 5962 5789 5962 5788 5963 5791 5963 5792 5963 5794 5964 5791 5964 5790 5964 5795 5965 5794 5965 5790 5965 5790 5966 5788 5966 5787 5966 5801 5967 5788 5967 5792 5967 5789 5968 5788 5968 5802 5968 5803 5969 5804 5969 5805 5969 5806 5970 5807 5970 5808 5970 5811 5971 5810 5971 5812 5971 5812 5972 5813 5972 5811 5972 5812 5973 5814 5973 5813 5973 5815 5974 5804 5974 5803 5974 5803 5975 5805 5975 5816 5975 5817 5976 5816 5976 5818 5976 5817 5977 5803 5977 5816 5977 5817 5978 5819 5978 5803 5978 5820 5979 5819 5979 5817 5979 5821 5980 5816 5980 5822 5980 5825 5981 5824 5981 5821 5981 5826 5982 5827 5982 5828 5982 5828 5983 5829 5983 5826 5983 5830 5984 5807 5984 5831 5984 5831 5985 5832 5985 5830 5985 5833 5986 5806 5986 5834 5986 5833 5987 5807 5987 5806 5987 5833 5988 5835 5988 5807 5988 5836 5989 5809 5989 5837 5989 5836 5990 5806 5990 5809 5990 5809 5991 5810 5991 5811 5991 5811 5992 5813 5992 5841 5992 5840 5993 5811 5993 5841 5993 5811 5994 5839 5994 5809 5994 5838 5995 5834 5995 5806 5995 5807 5996 5830 5996 5827 5996 5827 5997 5830 5997 5842 5997 5827 5998 5826 5998 5822 5998 5819 5999 5846 5999 5803 5999 5815 6000 5849 6000 5847 6000 5851 6001 5847 6001 5850 6001 5851 6002 5852 6002 5847 6002 5854 53 5855 53 5847 53 5850 6003 5858 6003 5851 6003 5850 6004 5849 6004 5858 6004 5853 6005 5852 6005 5859 6005 5859 6006 5820 6006 5817 6006 5847 53 5860 53 5861 53 5863 53 5862 53 5864 53 5864 6007 5862 6007 5865 6007 5866 6008 5865 6008 5844 6008 5861 6009 5867 6009 5868 6009 5863 53 5869 53 5847 53 5847 6010 5869 6010 5870 6010 5872 53 5871 53 5873 53 5875 6011 5874 6011 5843 6011 5877 6012 5876 6012 5829 6012 5829 6013 5828 6013 5877 6013 5873 6014 5874 6014 5875 6014 5878 6015 5872 6015 5879 6015 5880 6016 5879 6016 5881 6016 5878 6017 5879 6017 5880 6017 5883 53 5878 53 5880 53 5883 53 5884 53 5878 53 5884 53 5883 53 5885 53 5887 6018 5835 6018 5833 6018 5878 6019 5888 6019 5889 6019 5891 6020 5890 6020 5892 6020 5891 6021 5892 6021 5893 6021 5893 6022 5892 6022 5838 6022 5878 6023 5897 6023 5898 6023 5899 6024 5900 6024 5878 6024 5899 6025 5901 6025 5900 6025 5898 6026 5897 6026 5902 6026 5903 53 5902 53 5904 53 5898 53 5902 53 5903 53 5904 6027 5905 6027 5839 6027 5906 6028 5907 6028 5908 6028 5797 6029 5910 6029 5908 6029 5797 6030 5911 6030 5910 6030 5913 6031 5914 6031 5915 6031 5916 6032 5913 6032 5915 6032 5916 6033 5917 6033 5913 6033 5919 6034 5920 6034 5918 6034 5918 6035 5917 6035 5919 6035 5921 6036 5915 6036 5919 6036 5926 6037 5928 6037 5929 6037 5929 6038 5931 6038 5932 6038 5929 6039 5932 6039 5930 6039 5934 6040 5936 6040 5937 6040 5934 6041 5937 6041 5935 6041 5936 6042 5939 6042 5937 6042 5938 6043 5928 6043 5939 6043 5937 6044 5940 6044 5935 6044 5940 6045 5939 6045 5942 6045 5934 6046 5931 6046 5929 6046 5949 6047 5950 6047 5945 6047 5945 6048 5950 6048 5948 6048 5949 6049 5952 6049 5950 6049 5951 6050 5946 6050 5952 6050 5949 6051 5953 6051 5951 6051 5951 6052 5953 6052 5954 6052 5945 6053 5955 6053 5949 6053 5953 6054 5949 6054 5955 6054 5948 6055 5950 6055 5946 6055 5946 6056 5950 6056 5952 6056 5959 6057 5960 6057 5961 6057 5959 6058 5956 6058 5960 6058 5960 6059 5956 6059 5958 6059 5964 6060 5965 6060 5963 6060 5967 6061 5957 6061 5956 6061 5968 6062 5967 6062 5956 6062 5968 6063 5956 6063 5969 6063 5970 6064 5969 6064 5959 6064 5970 6065 5959 6065 5961 6065 5971 6066 5972 6066 5973 6066 5971 6067 5974 6067 5972 6067 5972 6068 5976 6068 5973 6068 5976 6069 5977 6069 5978 6069 5975 6070 5974 6070 5980 6070 5983 6071 5974 6071 5971 6071 5972 6072 5975 6072 5976 6072 5985 6073 5986 6073 5987 6073 5988 6074 5985 6074 5989 6074 5970 6075 5961 6075 5990 6075 5990 6076 5961 6076 5962 6076 5991 6077 5990 6077 5962 6077 5963 6078 5991 6078 5962 6078 5992 6079 5991 6079 5963 6079 5993 6080 5910 6080 5912 6080 5994 6081 5995 6081 5996 6081 5998 6082 5979 6082 5978 6082 5999 6083 5978 6083 5977 6083 5981 6084 5977 6084 5980 6084 5981 6085 5999 6085 5977 6085 5979 6086 5997 6086 6000 6086 6001 6087 5993 6087 5994 6087 5994 6088 6002 6088 6001 6088 6006 6089 5985 6089 6007 6089 5815 6090 5848 6090 6009 6090 5804 6091 5987 6091 5986 6091 6013 6092 6011 6092 6010 6092 6014 6093 6015 6093 6011 6093 6014 6094 6011 6094 6013 6094 6016 6095 6012 6095 6017 6095 6018 6096 6019 6096 6020 6096 6027 6097 6028 6097 6029 6097 6036 6098 6037 6098 6038 6098 6043 6099 6044 6099 6045 6099 6041 6100 6040 6100 6047 6100 6046 6101 6045 6101 6047 6101 6048 6102 6049 6102 6050 6102 6048 6103 6050 6103 6051 6103 6053 6104 6052 6104 6054 6104 6053 6105 6054 6105 6055 6105 6054 6106 6057 6106 6056 6106 6057 6107 6058 6107 6056 6107 6056 6108 6058 6108 6059 6108 6055 6109 6056 6109 6060 6109 6050 6110 6061 6110 6051 6110 6050 6111 6062 6111 6061 6111 6063 6112 6061 6112 6064 6112 6065 6113 6051 6113 6061 6113 6062 53 6050 53 6066 53 6066 6114 6050 6114 6067 6114 6049 6115 6053 6115 6069 6115 6069 6116 6053 6116 6070 6116 6073 6117 6075 6117 6076 6117 6077 6118 6076 6118 6078 6118 6078 6119 6076 6119 6079 6119 6082 6120 6084 6120 6080 6120 6087 53 6086 53 6088 53 6089 6121 6088 6121 6090 6121 6089 6122 6091 6122 6088 6122 6087 6123 6088 6123 6091 6123 6090 6124 6092 6124 6093 6124 6093 53 6092 53 6094 53 6097 53 6096 53 6098 53 6097 53 6099 53 6096 53 6093 53 6094 53 6100 53 6102 53 6101 53 6103 53 6103 6125 6101 6125 6104 6125 6106 6126 6108 6126 6082 6126 6112 6127 6110 6127 6113 6127 6117 6128 6114 6128 6110 6128 6118 6129 6119 6129 6114 6129 6121 6130 6115 6130 6120 6130 6074 6131 6121 6131 6123 6131 6124 6132 6074 6132 6123 6132 6121 53 6119 53 6118 53 6123 6133 6118 6133 6125 6133 6105 6134 6125 6134 6106 6134 6105 53 6126 53 6123 53 6114 6135 6130 6135 6118 6135 6118 6136 6130 6136 6125 6136 6132 6137 6134 6137 6131 6137 6106 6138 6128 6138 6132 6138 6132 6139 6128 6139 6125 6139 6130 6140 6132 6140 6125 6140 6133 6141 6132 6141 6130 6141 6131 6142 6134 6142 6103 6142 6098 6143 6102 6143 6135 6143 6104 6144 6131 6144 6103 6144 6130 6145 6114 6145 6117 6145 6134 6146 6110 6146 6116 6146 6136 6147 6135 6147 6116 6147 6097 6148 6136 6148 6137 6148 6138 6149 6113 6149 6139 6149 6138 6150 6137 6150 6113 6150 6141 6151 6142 6151 6143 6151 6144 6152 6141 6152 6143 6152 6142 6153 6145 6153 6146 6153 6127 6154 6146 6154 6129 6154 6126 6155 6129 6155 6148 6155 6147 6156 6148 6156 6129 6156 6148 6157 6147 6157 6145 6157 6148 6158 6141 6158 6144 6158 6148 6159 6152 6159 6126 6159 6154 6160 6155 6160 5921 6160 5921 6161 6155 6161 5915 6161 6161 6162 6158 6162 6162 6162 6159 6163 6158 6163 6161 6163 6161 6164 6162 6164 6163 6164 6164 6165 6166 6165 6165 6165 6164 6166 6167 6166 6166 6166 6169 6167 6168 6167 6170 6167 6169 6168 6170 6168 6171 6168 6172 6169 6173 6169 6174 6169 6175 6170 6172 6170 6176 6170 6177 6171 6178 6171 6173 6171 6177 6172 6179 6172 6178 6172 6177 6173 6180 6173 6179 6173 6177 6174 6181 6174 6180 6174 6177 6175 6182 6175 6181 6175 6184 6176 6183 6176 6185 6176 6186 6177 6190 6177 6188 6177 6191 6178 6192 6178 6190 6178 6188 6179 6190 6179 6193 6179 6187 6180 6198 6180 6182 6180 6183 6181 6182 6181 6198 6181 6199 6182 6200 6182 6201 6182 6178 6183 6208 6183 6209 6183 6178 6184 6174 6184 6173 6184 6174 6185 6210 6185 6211 6185 6212 6186 6213 6186 6171 6186 6167 6187 6214 6187 6215 6187 5955 6188 6165 6188 6166 6188 5954 6189 6217 6189 6162 6189 5923 6190 6218 6190 5922 6190 5917 6191 5923 6191 5922 6191 5916 6192 5915 6192 5925 6192 5925 6193 5915 6193 6156 6193 6158 6194 5951 6194 6162 6194 6216 6195 6220 6195 5953 6195 6216 6196 5953 6196 5955 6196 6165 6197 5955 6197 5947 6197 5947 6198 6158 6198 6165 6198 6158 6199 6160 6199 6165 6199 6220 6200 5954 6200 5953 6200 6162 6201 5951 6201 5954 6201 6155 6202 6221 6202 6157 6202 6163 6203 6222 6203 6221 6203 6163 6204 6223 6204 6222 6204 6227 6205 6224 6205 6226 6205 6228 6206 6229 6206 6230 6206 6228 6207 6231 6207 6229 6207 6228 6208 6215 6208 6231 6208 6232 6209 6233 6209 6234 6209 6235 6210 6232 6210 6234 6210 6237 6211 6236 6211 6238 6211 6239 6212 6238 6212 6240 6212 6240 6213 6241 6213 6242 6213 6244 6214 6247 6214 6248 6214 6238 6215 6236 6215 6249 6215 6250 6216 6249 6216 6251 6216 6238 6217 6249 6217 6250 6217 6207 6218 6253 6218 6206 6218 6257 6219 6258 6219 6253 6219 6261 6220 6260 6220 6262 6220 6261 6221 6262 6221 6263 6221 6264 6222 6261 6222 6263 6222 6262 6223 6260 6223 6265 6223 6266 6224 6200 6224 6267 6224 6266 6225 6267 6225 6268 6225 6267 6226 6200 6226 6270 6226 6273 6227 6272 6227 6274 6227 6273 6228 6274 6228 6275 6228 6273 6229 6275 6229 6276 6229 6272 6230 6278 6230 6196 6230 6279 6231 6272 6231 6273 6231 6280 6232 6282 6232 6281 6232 6280 6233 6283 6233 6282 6233 6282 6234 6283 6234 6284 6234 6281 6235 6282 6235 6285 6235 6286 6236 6281 6236 6285 6236 6286 6237 6285 6237 6287 6237 6293 6238 6292 6238 6294 6238 6293 6239 6294 6239 6295 6239 6290 6240 6289 6240 6291 6240 6289 6241 6296 6241 5983 6241 6294 6242 6292 6242 6298 6242 6299 6243 6298 6243 6300 6243 6304 6244 6305 6244 6301 6244 6300 6245 6309 6245 6310 6245 6311 6246 6301 6246 6312 6246 6311 6247 6312 6247 6313 6247 6311 6248 6313 6248 6314 6248 6312 6249 6315 6249 6316 6249 6317 6250 6312 6250 6318 6250 6319 6251 6318 6251 6320 6251 6319 6252 6320 6252 6321 6252 6324 6253 6323 6253 6258 6253 6258 6254 6259 6254 6324 6254 6329 6255 6330 6255 6328 6255 6329 6256 6255 6256 6330 6256 6255 6257 6329 6257 6252 6257 6325 6258 6331 6258 6332 6258 6245 6259 6243 6259 6335 6259 6245 6260 6336 6260 6243 6260 6339 6261 6334 6261 6340 6261 6341 6262 6342 6262 6340 6262 6345 6263 6346 6263 6245 6263 6246 6264 6347 6264 6348 6264 6247 6265 6246 6265 6349 6265 6351 6266 6350 6266 6219 6266 6352 6267 6219 6267 6157 6267 6354 6268 6219 6268 6352 6268 6355 6269 6349 6269 6356 6269 6230 6270 6225 6270 6228 6270 6227 6271 6359 6271 6352 6271 6354 6272 6351 6272 6219 6272 6237 6273 6233 6273 6236 6273 6248 6274 6360 6274 6244 6274 6336 6275 6242 6275 6243 6275 6256 6276 6342 6276 6341 6276 6342 6277 6339 6277 6340 6277 6326 6278 6328 6278 6330 6278 6299 6279 6363 6279 6308 6279 6364 6280 6365 6280 6279 6280 6279 6281 6365 6281 6271 6281 6272 6282 6279 6282 6271 6282 6281 6283 6275 6283 6274 6283 6295 6284 6368 6284 6293 6284 6293 6285 6290 6285 6292 6285 6266 6286 6262 6286 6265 6286 6314 6287 6264 6287 6361 6287 6243 6288 6334 6288 6335 6288 6356 6289 6357 6289 6355 6289 6221 6290 6222 6290 6157 6290 6369 6291 6370 6291 6371 6291 6372 6292 6373 6292 6374 6292 6372 6293 6375 6293 6376 6293 6378 6294 6374 6294 6379 6294 6375 6295 6378 6295 6379 6295 6380 6296 6370 6296 6369 6296 6369 6297 6371 6297 6381 6297 6381 6298 6371 6298 6382 6298 6380 6299 6369 6299 6381 6299 6382 6300 6371 6300 6383 6300 6399 6301 6400 6301 6401 6301 6403 6302 6404 6302 6405 6302 6405 6303 6404 6303 6406 6303 6409 6304 6408 6304 6410 6304 6411 6305 6412 6305 6413 6305 6417 6306 6416 6306 6418 6306 6419 6307 6420 6307 6421 6307 6421 6308 6420 6308 6422 6308 6423 6309 6424 6309 6425 6309 6429 6310 6428 6310 6430 6310 6433 6311 6432 6311 6434 6311 6437 6312 6436 6312 6438 6312 6443 6313 6442 6313 6444 6313 6453 6314 6454 6314 6455 6314 6455 6315 6454 6315 6456 6315 6457 6316 6458 6316 6459 6316 6465 6317 6466 6317 6467 6317 6473 6318 6474 6318 6475 6318 6477 6319 6478 6319 6479 6319 6479 6320 6478 6320 6480 6320 6485 6321 6486 6321 6487 6321 6487 6322 6486 6322 6488 6322 6489 6323 6490 6323 6491 6323 6495 6324 6494 6324 6496 6324 6497 6325 6498 6325 6499 6325 6497 6326 6499 6326 6503 6326 6503 6327 6499 6327 6501 6327 6497 53 6503 53 6498 53 6498 53 6503 53 6504 53 6498 6328 6504 6328 6500 6328 6500 6329 6504 6329 6505 6329 6507 6330 6436 6330 6509 6330 6510 6331 6491 6331 6508 6331 6435 6332 6511 6332 6436 6332 6436 6333 6511 6333 6509 6333 6437 6334 6513 6334 6435 6334 6435 53 6513 53 6511 53 6490 6335 6512 6335 6492 6335 6492 6336 6512 6336 6514 6336 6513 6337 6438 6337 6515 6337 6487 53 6492 53 6516 53 6518 6338 6487 6338 6516 6338 6431 6339 6519 6339 6432 6339 6486 53 6518 53 6520 53 6486 6340 6520 6340 6488 6340 6488 6341 6520 6341 6522 6341 6433 6342 6434 6342 6521 6342 6483 53 6488 53 6524 53 6434 6343 6428 6343 6523 6343 6427 6344 6527 6344 6428 6344 6428 6345 6527 6345 6525 6345 6482 855 6526 855 6528 855 6427 53 6529 53 6527 53 6529 6346 6430 6346 6531 6346 6532 6347 6484 6347 6530 6347 6531 6348 6424 6348 6533 6348 6477 6349 6479 6349 6534 6349 6477 6350 6534 6350 6478 6350 6425 53 6537 53 6423 53 6423 6351 6537 6351 6535 6351 6478 6352 6536 6352 6480 6352 6537 6353 6426 6353 6539 6353 6540 6354 6480 6354 6538 6354 6426 6355 6420 6355 6539 6355 6420 6356 6543 6356 6541 6356 6474 6357 6542 6357 6544 6357 6421 802 6545 802 6419 802 6419 6358 6545 6358 6543 6358 6474 6359 6544 6359 6476 6359 6421 6360 6422 6360 6545 6360 6545 6361 6422 6361 6547 6361 6471 6362 6476 6362 6548 6362 6548 6363 6476 6363 6546 6363 6469 6364 6471 6364 6550 6364 6550 6365 6471 6365 6548 6365 6415 6366 6551 6366 6416 6366 6416 6367 6551 6367 6549 6367 6470 6368 6552 6368 6472 6368 6553 6369 6418 6369 6555 6369 6556 6370 6472 6370 6554 6370 6555 6371 6412 6371 6557 6371 6558 6372 6467 6372 6556 6372 6412 6373 6559 6373 6557 6373 6465 53 6558 53 6466 53 6411 53 6561 53 6559 53 6466 6374 6560 6374 6468 6374 6468 6375 6560 6375 6562 6375 6413 6376 6414 6376 6561 6376 6561 6377 6414 6377 6563 6377 6463 6378 6468 6378 6564 6378 6564 6379 6468 6379 6562 6379 6563 6380 6408 6380 6565 6380 6566 6381 6463 6381 6564 6381 6408 6382 6567 6382 6565 6382 6461 53 6566 53 6462 53 6462 53 6566 53 6568 53 6409 53 6569 53 6407 53 6462 6383 6568 6383 6464 6383 6464 6384 6568 6384 6570 6384 6571 6385 6404 6385 6573 6385 6458 6386 6576 6386 6460 6386 6455 53 6460 53 6580 53 6453 6387 6455 6387 6582 6387 6399 6388 6583 6388 6400 6388 6400 6389 6583 6389 6581 6389 6453 53 6582 53 6454 53 6401 53 6585 53 6399 53 6454 6390 6584 6390 6456 6390 6456 6391 6584 6391 6586 6391 6401 6392 6402 6392 6585 6392 6451 53 6456 53 6588 53 6402 6393 6396 6393 6587 6393 6587 6394 6396 6394 6589 6394 6449 6395 6451 6395 6590 6395 6397 53 6593 53 6395 53 6452 6396 6592 6396 6594 6396 6397 6397 6398 6397 6593 6397 6593 6398 6398 6398 6595 6398 6447 53 6452 53 6596 53 6445 6399 6447 6399 6598 6399 6391 6400 6599 6400 6392 6400 6393 53 6601 53 6391 53 6391 53 6601 53 6599 53 6446 6401 6600 6401 6448 6401 6393 6402 6394 6402 6601 6402 6443 53 6448 53 6604 53 6603 6403 6388 6403 6605 6403 6606 6404 6443 6404 6604 6404 6388 6405 6607 6405 6605 6405 6441 53 6606 53 6442 53 6442 53 6606 53 6608 53 6440 6406 6610 6406 6153 6406 6124 6407 6610 6407 6076 6407 6442 6408 6608 6408 6444 6408 6389 6409 6390 6409 6609 6409 6386 6410 6611 6410 6385 6410 6385 6411 6611 6411 6616 6411 6439 6412 6444 6412 6615 6412 6390 6413 6385 6413 6614 6413 6614 6414 6385 6414 6616 6414 6617 53 6619 53 6144 53 6144 6415 6619 6415 6620 6415 6057 6416 6618 6416 6058 6416 6058 6417 6618 6417 6495 6417 6495 6418 6618 6418 6493 6418 6493 6419 6618 6419 6436 6419 6428 6420 6618 6420 6430 6420 6430 6421 6618 6421 6424 6421 6426 6422 6618 6422 6420 6422 6394 6423 6392 6423 6143 6423 6396 6424 6143 6424 6398 6424 6406 6425 6143 6425 6400 6425 6406 6426 6404 6426 6143 6426 6408 6427 6414 6427 6143 6427 6150 6428 6385 6428 6149 6428 6149 6429 6385 6429 6390 6429 6388 6430 6149 6430 6390 6430 6500 6431 6620 6431 6499 6431 6500 6432 6491 6432 6620 6432 6487 6433 6620 6433 6492 6433 6487 6434 6488 6434 6620 6434 6484 6435 6620 6435 6483 6435 6620 6436 6479 6436 6480 6436 6475 6437 6620 6437 6480 6437 6620 6438 6476 6438 6144 6438 6144 6439 6476 6439 6471 6439 6472 6440 6144 6440 6471 6440 6472 6441 6467 6441 6144 6441 6144 6442 6467 6442 6468 6442 6144 6443 6464 6443 6459 6443 6460 6444 6144 6444 6459 6444 6451 6445 6452 6445 6144 6445 6144 6446 6452 6446 6447 6446 6448 6447 6144 6447 6447 6447 6144 6448 6443 6448 6148 6448 6059 6449 6621 6449 6001 6449 6372 6450 6377 6450 6373 6450 6373 6451 6377 6451 6624 6451 6625 6452 6626 6452 6006 6452 6006 6453 6626 6453 5989 6453 6628 6454 6627 6454 6629 6454 6630 6455 6629 6455 6631 6455 6631 6456 6632 6456 6633 6456 6635 6457 6026 6457 6019 6457 6019 6458 6637 6458 6635 6458 6633 6459 6634 6459 6636 6459 6015 6460 6638 6460 6022 6460 6640 6461 6641 6461 6639 6461 6017 6462 6642 6462 6641 6462 6646 6463 6645 6463 6647 6463 6644 6464 6645 6464 6646 6464 6649 6465 6646 6465 6650 6465 6652 6466 6653 6466 6654 6466 6656 6467 6658 6467 6657 6467 6659 6468 6380 6468 6383 6468 6382 6469 6383 6469 6380 6469 6646 6470 6647 6470 6648 6470 6379 6471 6647 6471 6376 6471 6379 6472 6376 6472 6375 6472 6660 6473 6658 6473 6661 6473 6664 6474 6663 6474 6665 6474 6667 6475 6666 6475 6031 6475 6667 6476 6668 6476 6666 6476 6669 6477 6667 6477 6028 6477 6039 6478 6038 6478 6670 6478 6038 6479 6671 6479 6670 6479 6671 6480 6038 6480 6034 6480 6044 6481 6671 6481 6034 6481 5996 6482 6672 6482 6674 6482 6674 6483 6677 6483 6676 6483 6676 6484 6677 6484 6370 6484 6384 6485 6370 6485 6677 6485 6675 6486 5996 6486 6674 6486 6625 6487 6006 6487 6062 6487 6675 6488 6056 6488 6002 6488 6673 6489 6003 6489 6004 6489 6678 6490 6004 6490 6005 6490 6671 6491 6044 6491 6005 6491 6673 6492 6004 6492 6678 6492 6678 6493 6005 6493 6044 6493 5988 6494 6628 6494 6630 6494 6679 6495 6631 6495 6633 6495 5988 6496 6630 6496 6679 6496 6680 6497 6681 6497 6682 6497 6680 6498 6683 6498 6681 6498 6683 6499 6684 6499 6685 6499 6691 6500 6690 6500 6692 6500 6693 6501 6692 6501 6694 6501 6703 6502 6702 6502 6704 6502 6713 6503 6712 6503 6714 6503 6715 6504 6714 6504 6716 6504 6057 6505 6722 6505 6723 6505 6687 6506 6688 6506 6689 6506 6695 6507 6696 6507 6697 6507 6705 6508 6706 6508 6707 6508 6715 6509 6716 6509 6717 6509 6054 6510 6721 6510 6057 6510 6057 6511 6723 6511 6618 6511 6620 6512 6725 6512 6726 6512 6726 6513 6728 6513 6727 6513 6727 6514 6728 6514 6729 6514 6737 6515 6736 6515 6682 6515 6731 6516 6732 6516 6733 6516 6733 6517 6734 6517 6735 6517 6735 6518 6736 6518 6737 6518 6065 6519 6620 6519 6726 6519 6738 6520 6739 6520 6376 6520 6383 6521 6741 6521 6659 6521 6741 6522 6677 6522 6659 6522 6373 6523 6379 6523 6374 6523 6373 6524 6648 6524 6379 6524 6014 6525 6013 6525 6742 6525 6743 6526 6744 6526 6742 6526 6744 6527 6745 6527 6746 6527 6742 6528 6744 6528 6747 6528 6747 6529 6744 6529 6024 6529 6024 6530 6748 6530 6747 6530 6745 6531 6749 6531 6746 6531 6010 6532 6016 6532 6750 6532 6010 6533 6751 6533 6743 6533 6752 6534 6753 6534 6754 6534 6754 6535 6743 6535 6751 6535 6758 6536 6749 6536 6759 6536 6759 6537 6745 6537 6754 6537 6749 6538 6758 6538 6760 6538 6033 6539 6043 6539 6763 6539 6764 6540 6763 6540 6046 6540 6764 6541 6765 6541 6763 6541 6764 6542 6032 6542 6765 6542 6029 6543 6766 6543 6765 6543 6770 6544 6767 6544 6769 6544 6771 6545 6772 6545 6767 6545 6775 6546 6776 6546 6777 6546 6772 6547 6773 6547 6037 6547 6774 6548 6776 6548 6775 6548 6770 6549 6778 6549 6767 6549 6030 6550 6032 6550 6779 6550 6781 6551 6782 6551 6783 6551 6784 6552 6781 6552 6783 6552 6785 6553 6786 6553 6787 6553 6783 6554 6782 6554 6785 6554 6784 6555 6764 6555 6780 6555 6784 6556 6769 6556 6781 6556 6781 6557 6768 6557 6782 6557 6778 6558 6784 6558 6047 6558 6047 6559 6040 6559 6778 6559 6788 6560 6789 6560 6790 6560 6794 6561 6793 6561 6788 6561 6790 6562 6795 6562 6788 6562 6794 6563 6788 6563 6795 6563 6026 6564 6634 6564 6024 6564 6024 6565 6634 6565 6762 6565 6634 6566 6632 6566 6761 6566 6796 6567 6024 6567 6744 6567 6632 6568 6744 6568 6746 6568 6632 6569 6796 6569 6744 6569 6748 6570 6742 6570 6747 6570 6021 6571 6742 6571 6748 6571 6029 6572 6765 6572 6027 6572 6031 6573 6030 6573 6776 6573 6667 6574 6031 6574 6776 6574 6776 6575 6774 6575 6667 6575 6797 6576 6765 6576 6032 6576 6031 6577 6797 6577 6032 6577 6035 6578 6034 6578 6038 6578 6035 6579 6038 6579 6037 6579 6033 6580 6763 6580 6766 6580 6771 6581 6673 6581 6678 6581 6043 6582 6678 6582 6044 6582 6043 6583 6773 6583 6678 6583 6771 6584 6678 6584 6773 6584 6798 6585 6640 6585 6015 6585 6640 6586 6016 6586 6017 6586 6016 6587 6640 6587 6798 6587 6035 6588 6043 6588 6033 6588 6035 6589 6773 6589 6043 6589 6767 6590 6778 6590 6771 6590 6778 6591 6040 6591 6771 6591 6766 6592 6029 6592 6036 6592 6030 6593 6779 6593 6776 6593 6677 6594 6800 6594 6799 6594 6677 6595 6674 6595 6041 6595 6800 6596 6041 6596 6045 6596 6045 6597 6797 6597 6800 6597 6045 6598 6766 6598 6797 6598 6033 6599 6045 6599 6044 6599 6800 6600 6797 6600 6801 6600 6031 6601 6801 6601 6797 6601 6663 6602 6801 6602 6665 6602 6802 6603 6661 6603 6658 6603 6802 6604 6659 6604 6799 6604 6798 6605 6014 6605 6023 6605 6756 6606 6750 6606 6016 6606 6647 6607 6803 6607 6624 6607 6647 6608 6012 6608 6804 6608 6647 6609 6645 6609 6012 6609 6011 6610 6796 6610 6804 6610 6011 6611 6021 6611 6796 6611 6021 6612 6011 6612 6015 6612 6015 6613 6022 6613 6021 6613 6748 6614 6026 6614 6025 6614 6026 6615 6748 6615 6019 6615 6796 6616 6748 6616 6025 6616 6804 6617 6796 6617 6805 6617 6632 6618 6805 6618 6796 6618 6629 6619 6805 6619 6631 6619 6806 6620 6627 6620 6626 6620 6806 6621 6810 6621 6811 6621 6629 6622 6812 6622 6807 6622 6804 6623 6809 6623 6803 6623 6803 6624 6810 6624 6806 6624 6627 6625 6812 6625 6629 6625 6629 6626 6807 6626 6805 6626 6813 6627 6808 6627 6807 6627 6809 6628 6814 6628 6815 6628 6808 6629 6814 6629 6809 6629 6809 6630 6815 6630 6810 6630 6815 6631 6816 6631 6810 6631 6810 6632 6816 6632 6811 6632 6811 6633 6816 6633 6817 6633 6812 6634 6817 6634 6807 6634 6663 6635 6820 6635 6821 6635 6801 6636 6821 6636 6822 6636 6661 6637 6820 6637 6663 6637 6801 6638 6822 6638 6800 6638 6800 6639 6823 6639 6799 6639 6824 6640 6818 6640 6825 6640 6824 6641 6819 6641 6818 6641 6821 6642 6826 6642 6827 6642 6819 6643 6826 6643 6820 6643 6820 6644 6826 6644 6821 6644 6823 6645 6828 6645 6825 6645 6822 6646 6828 6646 6823 6646 6750 6647 6751 6647 6010 6647 6755 6648 6016 6648 6829 6648 6762 6649 6761 6649 6760 6649 6018 6650 6020 6650 6762 6650 6775 6651 6777 6651 6787 6651 6787 6652 6777 6652 6779 6652 6048 6653 6832 6653 6831 6653 6758 6654 6833 6654 6048 6654 6831 6655 6835 6655 6836 6655 6831 6656 6832 6656 6835 6656 6757 6657 6759 6657 6834 6657 6836 6658 6754 6658 6753 6658 6753 6659 6755 6659 6837 6659 6840 6660 6793 6660 6699 6660 6788 6661 6755 6661 6789 6661 6791 6662 6699 6662 6793 6662 6786 6663 6701 6663 6787 6663 6842 6664 6785 6664 6782 6664 6843 6665 6782 6665 6844 6665 6843 6666 6839 6666 6793 6666 6786 6667 6785 6667 6845 6667 6846 6668 6782 6668 6052 6668 6847 6669 6846 6669 6052 6669 6843 6670 6842 6670 6782 6670 6786 6671 6841 6671 6701 6671 6840 6672 6843 6672 6793 6672 6833 6673 6832 6673 6048 6673 6817 6674 6757 6674 6813 6674 6832 6675 6817 6675 6816 6675 6832 6676 6816 6676 6815 6676 6834 6677 6814 6677 6813 6677 6833 6678 6817 6678 6832 6678 6832 6679 6815 6679 6835 6679 6845 6680 6828 6680 6827 6680 6786 6681 6827 6681 6826 6681 6840 6682 6826 6682 6824 6682 6842 6683 6828 6683 6845 6683 6845 6684 6827 6684 6786 6684 6786 6685 6826 6685 6841 6685 6840 6686 6824 6686 6843 6686 6648 6687 6373 6687 6646 6687 6625 6688 6066 6688 6646 6688 6646 6689 6066 6689 6650 6689 6676 6690 6370 6690 6656 6690 6495 6691 6849 6691 6848 6691 5908 6692 6539 6692 6541 6692 5908 6693 6533 6693 6539 6693 5908 6694 6517 6694 6523 6694 5908 6695 6507 6695 6509 6695 6571 6696 6573 6696 5906 6696 6587 6697 6589 6697 5906 6697 6590 6698 6588 6698 6592 6698 6592 6699 6588 6699 6594 6699 6574 6700 6572 6700 6576 6700 6576 6701 6572 6701 6578 6701 6560 6702 6556 6702 6562 6702 6554 6703 6552 6703 6548 6703 6548 6704 6552 6704 6550 6704 6544 6705 6540 6705 6546 6705 6526 6706 6524 6706 6528 6706 6516 6707 6520 6707 6518 6707 6510 6708 6508 6708 6512 6708 6505 6709 6504 6709 6501 6709 6608 6710 6604 6710 6613 6710 6616 6711 6611 6711 6850 6711 6850 6712 6611 6712 6612 6712 6622 6713 5993 6713 6621 6713 6001 6714 6621 6714 5993 6714 6591 6715 6593 6715 6589 6715 6587 6716 6581 6716 6585 6716 6585 6717 6581 6717 6583 6717 6575 6718 6577 6718 6573 6718 6573 6719 6577 6719 6579 6719 6559 6720 6561 6720 6557 6720 6557 6721 6561 6721 6563 6721 6555 6722 6549 6722 6553 6722 6553 6723 6549 6723 6551 6723 6543 6724 6545 6724 6541 6724 6541 6725 6545 6725 6547 6725 6527 6726 6529 6726 6525 6726 6509 6725 6513 6725 6515 6725 6507 6727 6848 6727 6506 6727 6603 6728 6597 6728 6601 6728 6601 6729 6597 6729 6599 6729 6494 53 6506 53 6496 53 6852 6730 5997 6730 6853 6730 5998 6731 6853 6731 5997 6731 5999 6732 6853 6732 5998 6732 5981 6733 5982 6733 6854 6733 6853 6734 5999 6734 6855 6734 6856 6735 5981 6735 6857 6735 6857 6736 5981 6736 6854 6736 6854 6737 5982 6737 6859 6737 6860 6738 6861 6738 6858 6738 5982 6739 5983 6739 6862 6739 6862 6740 6863 6740 6864 6740 5982 6741 6862 6741 6864 6741 6863 6742 6865 6742 6866 6742 6866 6743 5990 6743 6867 6743 5967 6744 6193 6744 6869 6744 6869 6745 6192 6745 6868 6745 5968 6746 6194 6746 5967 6746 5967 6747 6869 6747 5964 6747 5992 6748 5966 6748 6868 6748 6868 6749 5966 6749 5965 6749 6869 6750 6868 6750 5965 6750 6871 6751 6872 6751 6873 6751 6874 6752 6875 6752 6873 6752 6873 6753 6872 6753 6874 6753 6874 6754 6872 6754 6876 6754 6877 6755 6876 6755 6878 6755 6877 6756 6874 6756 6876 6756 6873 6757 6875 6757 6879 6757 6879 6758 6875 6758 6881 6758 6875 6759 6874 6759 6882 6759 6881 6760 6882 6760 6883 6760 6882 6761 6877 6761 6884 6761 6885 6762 6884 6762 6877 6762 6876 6763 6887 6763 6878 6763 6886 6764 6887 6764 6888 6764 6887 6765 6876 6765 6889 6765 6888 6766 6889 6766 6890 6766 6889 6767 6871 6767 6890 6767 6890 6768 6871 6768 6880 6768 6892 6769 6894 6769 6895 6769 6899 6770 6897 6770 6898 6770 6898 6771 6893 6771 6900 6771 6898 6772 6900 6772 6901 6772 6894 6773 6897 6773 6896 6773 6896 6774 6897 6774 6902 6774 6902 6775 6899 6775 6903 6775 6901 6776 6899 6776 6898 6776 6899 6777 6904 6777 6903 6777 6901 6778 6900 6778 6904 6778 6904 6779 6900 6779 6905 6779 6900 6780 6906 6780 6905 6780 6905 6781 6906 6781 6907 6781 6906 6782 6900 6782 6893 6782 6906 6783 6893 6783 6907 6783 6907 6784 6893 6784 6908 6784 6909 6785 6911 6785 6913 6785 6910 6786 6909 6786 6916 6786 6909 6787 6912 6787 6917 6787 6917 6788 6912 6788 6918 6788 6919 6789 6912 6789 6915 6789 6915 6790 6912 6790 6913 6790 6914 6791 6923 6791 6915 6791 6922 6792 6923 6792 6924 6792 6923 6793 6914 6793 6925 6793 6923 6794 6925 6794 6924 6794 6926 6795 6911 6795 6927 6795 6928 6796 6929 6796 6930 6796 6931 6797 6928 6797 6930 6797 6930 6798 6934 6798 6931 6798 6932 6799 6935 6799 6936 6799 6928 6800 6933 6800 6938 6800 6938 6801 6933 6801 6939 6801 6936 6802 6940 6802 6932 6802 6932 6803 6940 6803 6939 6803 6935 6804 6941 6804 6936 6804 6941 6805 6943 6805 6942 6805 6942 6806 6943 6806 6944 6806 6944 6807 6934 6807 6945 6807 6946 6808 6947 6808 6934 6808 6934 6809 6947 6809 6945 6809 6934 6810 6930 6810 6946 6810 6930 6811 6929 6811 6946 6811 6951 6812 6948 6812 6950 6812 6950 6813 6954 6813 6951 6813 6955 6814 6951 6814 6954 6814 6957 6815 6948 6815 6958 6815 6948 6816 6953 6816 6958 6816 6955 6817 6961 6817 6956 6817 6956 6818 6961 6818 6960 6818 6961 6819 6955 6819 6963 6819 6963 6820 6955 6820 6954 6820 6954 6821 6950 6821 6966 6821 6950 6822 6949 6822 6966 6822 6972 6823 6968 6823 6971 6823 6968 6824 6972 6824 6973 6824 6975 6825 6971 6825 6974 6825 6969 6826 6968 6826 6977 6826 6977 6827 6968 6827 6978 6827 6968 6828 6973 6828 6978 6828 6978 6829 6973 6829 6979 6829 6979 6830 6973 6830 6972 6830 6976 6831 6980 6831 6972 6831 6972 6832 6980 6832 6979 6832 6975 6833 6981 6833 6976 6833 6976 6834 6981 6834 6980 6834 6981 6835 6975 6835 6983 6835 6981 6836 6983 6836 6982 6836 6982 6837 6983 6837 6984 6837 6983 6838 6975 6838 6974 6838 6983 6839 6974 6839 6984 6839 6986 6840 6987 6840 6974 6840 6974 6841 6987 6841 6985 6841 6974 6842 6970 6842 6986 6842 6986 6843 6969 6843 6987 6843 6991 6844 6988 6844 6990 6844 6992 6845 6988 6845 6991 6845 6988 6846 6992 6846 6993 6846 6995 6847 6992 6847 6991 6847 6992 6848 6995 6848 6996 6848 6989 6849 6988 6849 6997 6849 6997 6850 6988 6850 6998 6850 6999 6851 6993 6851 6992 6851 6992 6852 7000 6852 6999 6852 7001 6853 7003 6853 7002 6853 7003 6854 6994 6854 7004 6854 7006 6855 7007 6855 6994 6855 6994 6856 7007 6856 7005 6856 6994 6857 6990 6857 7006 6857 7006 6858 6989 6858 7007 6858 7008 6859 7009 6859 7010 6859 7012 6860 7015 6860 7016 6860 7009 6861 7008 6861 7017 6861 7008 6862 7013 6862 7018 6862 7019 6863 7013 6863 7012 6863 7016 6864 7020 6864 7012 6864 7012 6865 7020 6865 7019 6865 7015 6866 7021 6866 7016 6866 7021 6867 7015 6867 7023 6867 7022 6868 7023 6868 7024 6868 7023 6869 7015 6869 7014 6869 7014 6870 7027 6870 7025 6870 7027 6871 7009 6871 7017 6871 7028 6872 7029 6872 7030 6872 7031 6873 7028 6873 7030 6873 7032 6874 7028 6874 7031 6874 7030 6875 7034 6875 7031 6875 7035 6876 7032 6876 7031 6876 7032 6877 7035 6877 7036 6877 7029 6878 7028 6878 7037 6878 7037 6879 7028 6879 7038 6879 7039 6880 7033 6880 7032 6880 7043 6881 7035 6881 7034 6881 7043 6882 7034 6882 7044 6882 7044 6883 7034 6883 7045 6883 7046 6884 7047 6884 7034 6884 7034 6885 7030 6885 7046 6885 7052 6886 7048 6886 7051 6886 7050 6887 7054 6887 7051 6887 7055 6888 7051 6888 7054 6888 7052 6889 7055 6889 7056 6889 7057 6890 7048 6890 7058 6890 7048 6891 7053 6891 7058 6891 7058 6892 7053 6892 7059 6892 7055 6893 7061 6893 7056 6893 7056 6894 7061 6894 7060 6894 7063 6895 7054 6895 7064 6895 7066 6896 7067 6896 7054 6896 7054 6897 7067 6897 7065 6897 7066 6898 7049 6898 7067 6898 7068 6899 7069 6899 7070 6899 7068 6900 7070 6900 7072 6900 6286 6901 7071 6901 7076 6901 7074 6902 7071 6902 7072 6902 7076 6903 7077 6903 7078 6903 7077 6904 7074 6904 7079 6904 7079 6905 7080 6905 7077 6905 7077 6906 7080 6906 7078 6906 7074 6907 7081 6907 7079 6907 7079 6908 7081 6908 7080 6908 7080 6909 7081 6909 7082 6909 7082 6910 7083 6910 7084 6910 7083 6911 7073 6911 7070 6911 7083 6912 7070 6912 7084 6912 7084 6913 7070 6913 7085 6913 7070 6914 7075 6914 7085 6914 7086 6915 7087 6915 7088 6915 6865 6916 7086 6916 6284 6916 7090 6917 7086 6917 7089 6917 7091 6918 7090 6918 7089 6918 7088 6919 7092 6919 7089 6919 6284 6920 7086 6920 7090 6920 7090 6921 7095 6921 7094 6921 7093 6922 7096 6922 7091 6922 7097 6923 7098 6923 7099 6923 7098 6924 7093 6924 7092 6924 7100 6925 6862 6925 7092 6925 7092 6926 7088 6926 7100 6926 7088 6927 7087 6927 7100 6927 5984 6928 7101 6928 6289 6928 7102 6929 6154 6929 7103 6929 7103 6930 6154 6930 6218 6930 7103 6931 5923 6931 7104 6931 7105 6932 7103 6932 7104 6932 7106 6933 5923 6933 5924 6933 7104 6934 5923 6934 7106 6934 7109 6935 7105 6935 7110 6935 7110 6936 7111 6936 7109 6936 7111 6937 7110 6937 7112 6937 7112 6938 6348 6938 7111 6938 7111 6939 6348 6939 6347 6939 7118 6940 7117 6940 7116 6940 7117 6941 7121 6941 7122 6941 7123 6942 7122 6942 7124 6942 7125 6943 7123 6943 7126 6943 7127 6944 6310 6944 7125 6944 7122 6945 6321 6945 6320 6945 7123 6946 7124 6946 6315 6946 7125 6947 7129 6947 7130 6947 7131 6948 7125 6948 7130 6948 7131 6949 7132 6949 7125 6949 7131 6950 7133 6950 7132 6950 7134 6951 7133 6951 7131 6951 7134 6952 6297 6952 5795 6952 7132 6953 5802 6953 6852 6953 6852 6954 5802 6954 6000 6954 6000 6955 5802 6955 5801 6955 6283 6956 5970 6956 5990 6956 6284 6957 7094 6957 6282 6957 6865 6958 6863 6958 7136 6958 6862 6959 5983 6959 6296 6959 7094 6960 6285 6960 6282 6960 6285 6961 7095 6961 7097 6961 6296 6962 6289 6962 7099 6962 5988 6963 6679 6963 7137 6963 7138 6964 7139 6964 7140 6964 7140 6965 7141 6965 7138 6965 7140 6966 7142 6966 7141 6966 7144 6967 7142 6967 7145 6967 7146 6968 7145 6968 7147 6968 6859 6969 7156 6969 7157 6969 6861 6970 7158 6970 7140 6970 6861 6971 6860 6971 7158 6971 6860 6972 6859 6972 7157 6972 6859 6973 5982 6973 7156 6973 7159 6974 7160 6974 7151 6974 7160 6975 7161 6975 7151 6975 7150 6976 7162 6976 7149 6976 7164 6977 7146 6977 7147 6977 6652 6978 7170 6978 7171 6978 6642 6979 7172 6979 7173 6979 6638 6980 7175 6980 6637 6980 6637 6981 7175 6981 7160 6981 6660 6982 7168 6982 6657 6982 6657 6983 7169 6983 6654 6983 6654 6984 7169 6984 6652 6984 6649 6985 7171 6985 6644 6985 6644 6986 7172 6986 6642 6986 6642 6987 7173 6987 6641 6987 7150 6988 7176 6988 7177 6988 7177 6989 7178 6989 7150 6989 7150 6990 7178 6990 7162 6990 7179 6991 7148 6991 7162 6991 7146 6992 7182 6992 7183 6992 7184 6993 7165 6993 7144 6993 7143 6994 7185 6994 7186 6994 7143 6995 7187 6995 7141 6995 6668 6996 7188 6996 6666 6996 6668 6997 7138 6997 7188 6997 7148 6998 7180 6998 7163 6998 7165 6999 7185 6999 7143 6999 7188 7000 7167 7000 6666 7000 7167 7001 6664 7001 6666 7001 7153 7002 7189 7002 7152 7002 7152 7003 6635 7003 7159 7003 6858 7004 7139 7004 7190 7004 6736 7005 7151 7005 6682 7005 6736 7006 7153 7006 7151 7006 6736 7007 6734 7007 7153 7007 7153 7008 6734 7008 6732 7008 7155 7009 6726 7009 6725 7009 7155 7010 6725 7010 6724 7010 7153 7011 6732 7011 7154 7011 7156 7012 6722 7012 6720 7012 7157 7013 6720 7013 6718 7013 7157 7014 6718 7014 6716 7014 7140 7015 6710 7015 6708 7015 7142 7016 6702 7016 6700 7016 7145 6 6698 6 6696 6 7156 7017 6720 7017 7157 7017 7157 7018 6716 7018 7158 7018 7158 7019 6712 7019 7140 7019 7142 7020 6700 7020 7145 7020 7147 7021 6692 7021 6690 7021 7151 7022 6684 7022 6680 7022 7149 7023 6686 7023 7151 7023 5995 7024 5912 7024 6855 7024 6856 7025 6005 7025 6855 7025 6005 7026 6856 7026 6858 7026 7139 7027 6669 7027 7190 7027 5912 7028 5911 7028 6855 7028 7132 7029 5911 7029 7191 7029 7123 7030 7192 7030 7193 7030 7117 7031 7193 7031 7194 7031 7109 7032 7195 7032 7196 7032 7123 7033 7193 7033 7117 7033 7113 7034 7195 7034 7109 7034 6005 7035 6858 7035 6669 7035 6671 7036 6669 7036 6670 7036 7137 7037 5986 7037 5985 7037 6633 7038 6636 7038 6635 7038 7200 7039 7152 7039 7189 7039 7137 7040 6191 7040 5986 7040 5816 7041 6186 7041 6182 7041 5822 7042 6182 7042 6177 7042 5827 7043 6177 7043 6173 7043 5808 7044 6168 7044 6164 7044 5816 7045 6182 7045 5822 7045 5822 7046 6177 7046 5827 7046 5827 7047 6173 7047 5807 7047 7201 7048 5991 7048 7199 7048 5991 7049 7201 7049 6867 7049 7154 7050 7201 7050 7153 7050 7201 7051 7154 7051 6867 7051 7191 7052 7202 7052 7192 7052 7191 7053 5911 7053 7202 7053 7202 7054 7203 7054 7204 7054 7205 7055 7202 7055 7204 7055 7202 7056 7206 7056 7207 7056 7192 7057 7207 7057 7208 7057 7202 7058 7207 7058 7192 7058 7211 7059 7212 7059 7192 7059 7192 7060 7212 7060 7213 7060 7193 7061 7192 7061 7213 7061 7214 7062 7215 7062 7213 7062 7216 7063 7217 7063 7213 7063 7213 7064 7217 7064 7194 7064 7218 7065 7219 7065 7194 7065 7217 7066 7218 7066 7194 7066 7220 7067 7221 7067 7194 7067 7222 7068 7223 7068 7195 7068 7221 7069 7222 7069 7195 7069 7195 7070 7224 7070 7196 7070 7195 7071 7223 7071 7224 7071 7197 7072 7226 7072 7227 7072 7227 7073 7228 7073 7198 7073 7198 7074 7230 7074 7231 7074 7217 7075 7234 7075 7218 7075 7218 7076 7234 7076 7232 7076 6332 7077 7217 7077 7235 7077 6332 7078 7234 7078 7217 7078 7215 7079 7236 7079 7216 7079 7215 7080 6321 7080 7236 7080 7214 7081 7238 7081 7239 7081 7239 7082 7238 7082 6320 7082 7238 7083 7212 7083 7240 7083 6316 7084 7212 7084 7241 7084 7211 7085 7210 7085 7242 7085 7208 7086 7244 7086 7245 7086 7208 7087 7207 7087 7244 7087 7204 7088 7250 7088 7251 7088 7250 7089 7252 7089 7251 7089 7254 7090 7134 7090 7253 7090 7203 7091 7254 7091 7253 7091 5797 7092 5907 7092 5800 7092 5909 7093 7262 7093 7261 7093 5909 7094 7265 7094 7264 7094 5909 7095 7267 7095 7266 7095 5909 7096 7268 7096 7267 7096 7265 7097 7266 7097 7270 7097 7265 7098 7270 7098 7271 7098 7271 7099 7227 7099 7226 7099 7263 7100 7272 7100 7273 7100 7224 7101 7274 7101 7225 7101 7259 7102 7260 7102 7278 7102 7259 7103 7278 7103 7279 7103 7279 7104 7280 7104 7220 7104 7233 7105 7258 7105 7281 7105 7257 7106 7258 7106 7233 7106 7283 7107 7284 7107 5907 7107 7284 7108 7283 7108 7239 7108 7239 7109 7283 7109 7285 7109 7214 7110 7239 7110 7285 7110 7286 53 7282 53 7256 53 7287 7111 7286 7111 7235 7111 7287 7112 7217 7112 7216 7112 5907 7113 7288 7113 7289 7113 7290 7114 5907 7114 7289 7114 7290 7115 7291 7115 5907 7115 7293 7116 7241 7116 7212 7116 7212 7117 7211 7117 7293 7117 7245 7118 7210 7118 7208 7118 7291 7119 7294 7119 5907 7119 7296 7120 5907 7120 7295 7120 7298 7121 7251 7121 7297 7121 7295 7122 7299 7122 7300 7122 7255 7123 7254 7123 5798 7123 7301 7124 6184 7124 5844 7124 5844 7125 6184 7125 5866 7125 5826 7126 7302 7126 5844 7126 5844 7127 7302 7127 7301 7127 6203 7128 5829 7128 6204 7128 5829 7129 7302 7129 5826 7129 7303 7130 5843 7130 7304 7130 5842 7131 6206 7131 5875 7131 5832 7132 7306 7132 5830 7132 5831 7133 5835 7133 7308 7133 7310 7134 5834 7134 7311 7134 5896 7135 7312 7135 7311 7135 5896 7136 7311 7136 5834 7136 5905 7137 7315 7137 5837 7137 7316 7138 7317 7138 7318 7138 7318 7139 7317 7139 7319 7139 7320 7140 7319 7140 7321 7140 7322 7141 7321 7141 7323 7141 6079 7142 7323 7142 6078 7142 7318 7143 7319 7143 7320 7143 5841 7144 7320 7144 7322 7144 5841 7145 5813 7145 7320 7145 7320 7146 5813 7146 7318 7146 5814 7147 6160 7147 7324 7147 7316 7148 7325 7148 7317 7148 7326 7149 6087 7149 6091 7149 7326 7150 6091 7150 7327 7150 7328 7151 6090 7151 7329 7151 7330 7152 7231 7152 7329 7152 7329 7153 7231 7153 7230 7153 7230 7154 7328 7154 7329 7154 7328 7155 7230 7155 7229 7155 7327 7156 7229 7156 7268 7156 7268 7157 7326 7157 7327 7157 6083 7158 6087 7158 7326 7158 6612 7159 6107 7159 6083 7159 6083 7160 6107 7160 6081 7160 6081 7161 6107 7161 6082 7161 5906 7162 6850 7162 5909 7162 7331 7163 6109 7163 6111 7163 6115 7164 7331 7164 6111 7164 7331 7165 6115 7165 6122 7165 7333 7166 6078 7166 7334 7166 7334 7167 6078 7167 7323 7167 7335 7168 7319 7168 7317 7168 7336 53 7335 53 7317 53 7337 7169 7338 7169 7339 7169 7340 53 7339 53 6139 53 7341 7170 6139 7170 6140 7170 6109 7171 7341 7171 6140 7171 6109 7172 7331 7172 7341 7172 7341 53 7331 53 6122 53 7342 7173 7341 7173 6122 7173 7337 7174 7339 7174 7340 7174 7340 53 6139 53 7341 53 6122 7175 6073 7175 7342 7175 7342 7176 6073 7176 7332 7176 5878 7177 5900 7177 6851 7177 7343 7178 5878 7178 6851 7178 5900 7179 6079 7179 6851 7179 6124 7180 6076 7180 6075 7180 6074 7181 6124 7181 6075 7181 6851 7182 6079 7182 6076 7182 5878 7183 7343 7183 5847 7183 5847 7184 7343 7184 5848 7184 5848 7185 7343 7185 6009 7185 6602 7186 6596 7186 7343 7186 6594 7187 6588 7187 7343 7187 6596 7188 6594 7188 7343 7188 6588 7189 6586 7189 7343 7189 6578 7190 6572 7190 7343 7190 6580 7191 6578 7191 7343 7191 6572 7192 6570 7192 7343 7192 6562 7193 6556 7193 7343 7193 7343 7194 6556 7194 6554 7194 6546 7195 6540 7195 6009 7195 6548 7196 6546 7196 6009 7196 6540 7197 6538 7197 6009 7197 6530 7198 6524 7198 6009 7198 6524 7199 6522 7199 6009 7199 6516 7200 6514 7200 6009 7200 6505 7201 6501 7201 6009 7201 6508 7202 6505 7202 6009 7202 6613 7203 7343 7203 6615 7203 6006 7204 6007 7204 6061 7204 6862 7205 7100 7205 7136 7205 7136 7206 7100 7206 7087 7206 7344 7207 7345 7207 7167 7207 7166 7208 7345 7208 7346 7208 7168 6 7347 6 7348 6 7349 7209 7168 7209 7348 7209 7349 7210 7169 7210 7168 7210 7172 7211 7352 7211 7353 7211 7173 7212 7354 7212 7355 7212 7174 7213 7355 7213 7356 7213 7174 7214 7173 7214 7355 7214 7169 7215 7350 7215 7170 7215 7171 7216 7352 7216 7172 7216 7176 7217 7175 7217 7358 7217 7177 7218 7359 7218 7360 7218 7358 7219 7177 7219 7176 7219 7175 7220 7357 7220 7358 7220 7361 7221 7178 7221 7360 7221 7362 7222 7363 7222 7180 7222 7180 7223 7364 7223 7181 7223 7181 7224 7364 7224 7365 7224 7366 7225 7368 7225 7369 7225 7370 7226 7369 7226 7368 7226 7371 7227 7370 7227 7372 7227 7372 7228 7370 7228 7374 7228 7375 7229 7372 7229 7376 7229 7375 7230 7376 7230 7377 7230 7380 7231 7372 7231 7374 7231 7381 7232 7380 7232 7374 7232 7374 7233 7370 7233 7381 7233 7381 7234 7370 7234 7382 7234 7368 7235 7382 7235 7370 7235 7382 7236 7368 7236 7383 7236 7380 7237 7376 7237 7372 7237 7387 7238 7377 7238 7386 7238 7388 7239 7370 7239 7373 7239 7369 7240 7370 7240 7388 7240 7389 7241 7369 7241 7388 7241 7369 7242 7389 7242 7366 7242 7385 7243 7379 7243 7389 7243 7389 7244 7379 7244 7366 7244 7390 7245 7391 7245 7392 7245 7392 7246 7391 7246 7393 7246 7389 7247 7391 7247 7390 7247 7388 7248 7393 7248 7394 7248 7395 7249 7392 7249 7393 7249 7399 7250 7398 7250 7400 7250 7395 7251 7399 7251 7400 7251 7402 7252 7403 7252 7404 7252 7385 7253 7401 7253 7396 7253 7398 7254 7396 7254 7400 7254 7345 7255 7405 7255 7406 7255 7346 7256 7406 7256 7387 7256 7387 7257 7347 7257 7346 7257 7378 7258 7387 7258 7407 7258 7408 7259 7378 7259 7407 7259 7408 7260 7373 7260 7378 7260 7365 7261 7409 7261 7373 7261 7362 7262 7384 7262 7402 7262 7362 7263 7361 7263 7384 7263 7353 7264 7384 7264 7354 7264 7379 7265 7353 7265 7352 7265 7361 7266 7360 7266 7354 7266 7383 7267 7367 7267 7351 7267 7383 7268 7350 7268 7382 7268 7349 7269 7348 7269 7380 7269 7386 7270 7348 7270 7347 7270 7381 7271 7349 7271 7380 7271 7349 7272 7381 7272 7350 7272 7403 7273 7384 7273 7385 7273 7403 7274 7385 7274 7404 7274 7401 7275 7389 7275 7390 7275 7388 7276 7373 7276 7393 7276 7409 7277 7364 7277 7399 7277 7397 7278 7404 7278 7385 7278 7399 7279 7402 7279 7397 7279 7399 7280 7362 7280 7402 7280 7405 7281 7187 7281 7186 7281 7344 7282 7188 7282 7187 7282 7406 7283 7186 7283 7185 7283 7387 7284 7185 7284 7184 7284 7387 7285 7184 7285 7407 7285 7407 7286 7184 7286 7183 7286 7407 7287 7183 7287 7408 7287 7408 7288 7182 7288 7365 7288 7102 7289 7412 7289 7135 7289 7415 7290 7416 7290 7413 7290 7417 6 7416 6 7418 6 7419 6 7417 6 7418 6 7421 7291 7420 7291 7422 7291 7416 6 7423 6 7418 6 7418 6 7423 6 7424 6 7429 7292 7428 7292 7430 7292 7431 6 7432 6 7433 6 7422 7293 7433 7293 7421 7293 7424 6 7425 6 7426 6 7435 7294 7434 7294 7436 7294 7437 6 7436 6 7438 6 7439 7295 7438 7295 7440 7295 7135 7296 7440 7296 6161 7296 7135 6 7439 6 7440 6 7442 7297 7412 7297 7410 7297 7442 6 7410 6 7432 6 7443 7298 7446 7298 7444 7298 7448 7299 7446 7299 7447 7299 7448 7300 7449 7300 7446 7300 7448 7301 7450 7301 7449 7301 7448 7302 7451 7302 7450 7302 7450 6 7451 6 6161 6 7447 7303 7452 7303 7414 7303 7422 7304 7431 7304 7433 7304 7435 6 7428 6 7434 6 7433 6 7432 6 7410 6 7444 6 7434 6 7445 6 7445 6 7434 6 7427 6 7411 7305 7453 7305 7410 7305 6159 7306 7448 7306 7324 7306 7433 7307 7453 7307 7421 7307 7455 7308 6137 7308 7420 7308 7420 7309 6137 7309 7417 7309 7421 7310 7455 7310 7420 7310 7456 7311 7325 7311 7414 7311 7457 7312 7413 7312 6138 7312 7457 7313 7414 7313 7413 7313 7325 7314 7447 7314 7414 7314 6099 7315 6097 7315 6137 7315 7330 7316 7453 7316 7231 7316 7198 7317 7231 7317 7102 7317 7458 7318 7338 7318 7336 7318 6138 7319 7339 7319 7457 7319 7458 7320 7336 7320 7456 7320 7459 7321 7460 7321 6084 7321 6085 7322 7465 7322 7459 7322 6088 7323 7461 7323 6092 7323 6094 7324 7463 7324 6096 7324 6096 7325 7464 7325 6101 7325 7466 7326 7459 7326 7467 7326 7466 7327 7460 7327 7459 7327 7460 7328 7466 7328 7468 7328 7462 7329 7469 7329 7470 7329 7460 7330 7468 7330 7461 7330 7461 7331 7469 7331 7462 7331 7462 53 7470 53 7463 53 7464 7332 7472 7332 7465 7332 7334 7333 7474 7333 7333 7333 7333 7334 7474 7334 7475 7334 7342 7335 7476 7335 7477 7335 7341 7336 7477 7336 7478 7336 7340 7337 7478 7337 7479 7337 7341 7338 7478 7338 7340 7338 7337 7339 7480 7339 7335 7339 7481 7340 7473 7340 7482 7340 7475 7341 7481 7341 7483 7341 7476 7342 7483 7342 7484 7342 7480 7343 7487 7343 7482 7343 7473 7344 7480 7344 7482 7344 7478 7345 7487 7345 7479 7345 7479 7346 7487 7346 7480 7346 7488 7347 7489 7347 7446 7347 7446 7348 7489 7348 7444 7348 7434 7349 7490 7349 7491 7349 7436 7350 7491 7350 7492 7350 7440 7351 7492 7351 7493 7351 7444 7352 7490 7352 7434 7352 7438 7353 7492 7353 7440 7353 7450 7354 7494 7354 7449 7354 7489 7355 7488 7355 7494 7355 7491 7356 7489 7356 7495 7356 7492 7357 7495 7357 7493 7357 7496 7358 7435 7358 7497 7358 7496 7359 7428 7359 7435 7359 7432 7360 7499 7360 7500 7360 7442 7361 7500 7361 7501 7361 7441 7362 7501 7362 7502 7362 7439 7363 7502 7363 7503 7363 7430 7364 7498 7364 7432 7364 7432 7365 7500 7365 7442 7365 7439 7366 7503 7366 7437 7366 7500 7367 7502 7367 7501 7367 7504 7368 7418 7368 7424 7368 7420 7369 7505 7369 7506 7369 7422 7370 7506 7370 7507 7370 7431 7371 7507 7371 7508 7371 7419 7372 7505 7372 7420 7372 7422 7373 7507 7373 7431 7373 7429 7374 7509 7374 7426 7374 7511 7375 7505 7375 7504 7375 7511 7376 7512 7376 7505 7376 7506 7377 7512 7377 7513 7377 7510 7378 7517 7378 7511 7378 7504 7379 7510 7379 7511 7379 7505 7380 7512 7380 7506 7380 7506 7381 7513 7381 7507 7381 7509 7382 7517 7382 7510 7382 7414 7383 7520 7383 7415 7383 7425 7384 7521 7384 7522 7384 7427 7385 7522 7385 7523 7385 7445 7386 7523 7386 7524 7386 7443 7387 7524 7387 7525 7387 7414 7388 7452 7388 7519 7388 7416 7389 7521 7389 7423 7389 7427 7390 7523 7390 7445 7390 7443 7391 7525 7391 7452 7391 7526 7392 7527 7392 7520 7392 7521 7393 7527 7393 7528 7393 7522 7394 7528 7394 7529 7394 7522 7395 7529 7395 7530 7395 7523 7396 7530 7396 7531 7396 7524 7397 7531 7397 7532 7397 7519 7398 7532 7398 7526 7398 7520 7399 7527 7399 7521 7399 7522 7400 7530 7400 7523 7400 7524 7401 7532 7401 7525 7401 7502 7402 7533 7402 7496 7402 7499 7403 7496 7403 7533 7403 7482 7404 7487 7404 7534 7404 7535 7405 7526 7405 7532 7405 7537 7406 7530 7406 7529 7406 7538 7407 7528 7407 7527 7407 7487 7408 7486 7408 7538 7408 7529 7409 7485 7409 7537 7409 7485 7410 7484 7410 7537 7410 7530 7411 7484 7411 7483 7411 7512 7412 7539 7412 7472 7412 7540 7413 7511 7413 7517 7413 7541 7414 7517 7414 7516 7414 7542 7415 7515 7415 7514 7415 7543 7416 7513 7416 7512 7416 7472 7417 7471 7417 7543 7417 7513 7418 7543 7418 7471 7418 7471 7419 7470 7419 7514 7419 7513 7420 7471 7420 7514 7420 7515 7421 7469 7421 7468 7421 7541 7422 7468 7422 7466 7422 7467 7423 7511 7423 7540 7423 7516 7424 7468 7424 7541 7424 6310 7425 7209 7425 7299 7425 7544 7426 6310 7426 7299 7426 7544 7427 7291 7427 7545 7427 7547 7428 5820 7428 5852 7428 7549 7429 5825 7429 5867 7429 7550 7430 5867 7430 5860 7430 5860 7431 5855 7431 7550 7431 7550 7432 5855 7432 7551 7432 7552 7433 6332 7433 7286 7433 7256 7434 7257 7434 7552 7434 7552 7435 7257 7435 7553 7435 6344 7436 7280 7436 7278 7436 7555 7437 6344 7437 7260 7437 7555 7438 7261 7438 7556 7438 7112 7439 7274 7439 6348 7439 6348 7440 7272 7440 7264 7440 7557 7441 6348 7441 7264 7441 7264 7442 7265 7442 7557 7442 7557 7443 7265 7443 7558 7443 7307 7444 5832 7444 5881 7444 5879 7445 5872 7445 7307 7445 7307 7446 5872 7446 7559 7446 7561 7447 5892 7447 5890 7447 7561 7448 5889 7448 7562 7448 7563 7449 5891 7449 7564 7449 7565 7450 5896 7450 5894 7450 7565 7451 5894 7451 5888 7451 5888 7452 5884 7452 7565 7452 7565 7453 5884 7453 7566 7453 7566 7454 5884 7454 5885 7454 7568 7455 5903 7455 5904 7455 7567 7456 5903 7456 7568 7456 5904 7457 7570 7457 7569 7457 7570 7458 5839 7458 6166 7458 5843 7459 5874 7459 7304 7459 5869 7460 5863 7460 7572 7460 7572 7461 5863 7461 7573 7461 7287 7462 7237 7462 6331 7462 7219 7463 7574 7463 7220 7463 7574 7464 7281 7464 6338 7464 7227 7465 7578 7465 7228 7465 7227 7466 7579 7466 7578 7466 5926 7467 7581 7467 5944 7467 7581 7468 5932 7468 7582 7468 5932 7469 5933 7469 7582 7469 7582 7470 5933 7470 7583 7470 5933 7471 5935 7471 7583 7471 7583 7472 5935 7472 5941 7472 5782 7473 5783 7473 5786 7473 5786 7474 5783 7474 7584 7474 5818 7475 7585 7475 5817 7475 7588 7476 5865 7476 5862 7476 5862 7477 5861 7477 7588 7477 7588 7478 5861 7478 7590 7478 7590 7479 5861 7479 5868 7479 6201 7480 7591 7480 5868 7480 5868 7481 7592 7481 6201 7481 7593 7482 7284 7482 7239 7482 7594 7483 7289 7483 7595 7483 7595 7484 7289 7484 7293 7484 7595 7485 7293 7485 7596 7485 7211 7486 7242 7486 7293 7486 7597 7487 7295 7487 7300 7487 7206 7488 7247 7488 7300 7488 7300 7489 7247 7489 6309 7489 7598 7490 7297 7490 7252 7490 7252 7491 7297 7491 7251 7491 5787 7492 5802 7492 5796 7492 6292 7493 5793 7493 5794 7493 7132 7494 7133 7494 5802 7494 5802 7495 7133 7495 5796 7495 7133 7496 7134 7496 5795 7496 7133 7497 5795 7497 5796 7497 7134 7498 7599 7498 7253 7498 7131 7499 7130 7499 7599 7499 7599 7500 7130 7500 7250 7500 7130 7501 7252 7501 7250 7501 6307 7502 6298 7502 7598 7502 6307 7503 7598 7503 7252 7503 6297 7504 7297 7504 7598 7504 7597 7505 6309 7505 6300 7505 6307 7506 7129 7506 7249 7506 7249 7507 7129 7507 7248 7507 7247 7508 7248 7508 7129 7508 7247 7509 7129 7509 7125 7509 7247 7510 6310 7510 6309 7510 6298 7511 6306 7511 7600 7511 7249 7512 7298 7512 6306 7512 6300 7513 6310 7513 7544 7513 7544 7514 7545 7514 6301 7514 7544 7515 6301 7515 6300 7515 6304 7516 6301 7516 7545 7516 7244 7517 7246 7517 7127 7517 6304 7518 7244 7518 7128 7518 7596 7519 6315 7519 6312 7519 7595 7520 7596 7520 6312 7520 6312 7521 6301 7521 7594 7521 6312 7522 7594 7522 7595 7522 6305 7523 7594 7523 6301 7523 6312 7524 6316 7524 7601 7524 7601 7525 6318 7525 6312 7525 6320 7526 6318 7526 7593 7526 7288 7527 7284 7527 7601 7527 7601 7528 7284 7528 7593 7528 7601 7529 7241 7529 7288 7529 6280 7530 6274 7530 7602 7530 6870 7531 6280 7531 7602 7531 7602 7532 6274 7532 7603 7532 7584 7533 6188 7533 5786 7533 5785 7534 6188 7534 6193 7534 5785 7535 5786 7535 6188 7535 6193 7536 6194 7536 5785 7536 6870 7537 5779 7537 5778 7537 6272 7538 6196 7538 7547 7538 7604 7539 6195 7539 6189 7539 6196 7540 6195 7540 7546 7540 7604 7541 7584 7541 7605 7541 7548 7542 5851 7542 7603 7542 7603 7543 5851 7543 5858 7543 6197 7544 7587 7544 7607 7544 6197 7545 6186 7545 7585 7545 6197 7546 7585 7546 7587 7546 7586 7547 7585 7547 6189 7547 6189 7548 6196 7548 7586 7548 7586 7549 6196 7549 6278 7549 5817 7550 7586 7550 5859 7550 7549 7551 7550 7551 6200 7551 7550 7552 6270 7552 6200 7552 6197 7553 7551 7553 7608 7553 7589 7554 6183 7554 7610 7554 6185 7555 6183 7555 7589 7555 7592 7556 6183 7556 6198 7556 7610 7557 6183 7557 7592 7557 6265 7558 6260 7558 7588 7558 6185 7559 7589 7559 7588 7559 6185 7560 7588 7560 6260 7560 7611 7561 7282 7561 7287 7561 7611 7562 7287 7562 6331 7562 6325 7563 6332 7563 7552 7563 7552 7564 7553 7564 6333 7564 7120 7565 7118 7565 7116 7565 7118 7566 7120 7566 7232 7566 7234 7567 7118 7567 7232 7567 7553 7568 7233 7568 6337 7568 7613 7569 6343 7569 6335 7569 7613 7570 7614 7570 6343 7570 6335 7571 6333 7571 7615 7571 6335 7572 7615 7572 7613 7572 6338 7573 7116 7573 7574 7573 7116 7574 7115 7574 7574 7574 7614 7575 7575 7575 6343 7575 7220 7576 7575 7576 7279 7576 7279 7577 7575 7577 7614 7577 7613 7578 7279 7578 7614 7578 6335 7579 6344 7579 7555 7579 7555 7580 7556 7580 6245 7580 7555 7581 6245 7581 6335 7581 6343 7582 7616 7582 7554 7582 7617 7583 7616 7583 7115 7583 6345 7584 7275 7584 7277 7584 7618 7585 6347 7585 6246 7585 7618 7586 6246 7586 6245 7586 7619 7587 6245 7587 6346 7587 6346 7588 6345 7588 7576 7588 7576 7589 7111 7589 7577 7589 7224 7590 7577 7590 7273 7590 6347 7591 7263 7591 7273 7591 7621 7592 7110 7592 7623 7592 6246 7593 6348 7593 7557 7593 7558 7594 7265 7594 7271 7594 6185 7595 7573 7595 6184 7595 7302 7596 6203 7596 7624 7596 6203 7597 6181 7597 7624 7597 6184 7598 7301 7598 7624 7598 6183 7599 6184 7599 7624 7599 6204 7600 5876 7600 5869 7600 7625 7601 6205 7601 6204 7601 7303 7602 7304 7602 6180 7602 6202 7603 6180 7603 6181 7603 6180 7604 6202 7604 7303 7604 6205 7605 7303 7605 6202 7605 6209 7606 7307 7606 6251 7606 7307 7607 7559 7607 6253 7607 7307 7608 6253 7608 6251 7608 6208 7609 7307 7609 6209 7609 7305 7610 7306 7610 6179 7610 6206 7611 7305 7611 6179 7611 7627 7612 7628 7612 6209 7612 6251 7613 6249 7613 7629 7613 6251 7614 7629 7614 7627 7614 6210 7615 6174 7615 7309 7615 7309 7616 6174 7616 7308 7616 5831 7617 7308 7617 5882 7617 7627 7618 5882 7618 7628 7618 7562 7619 7630 7619 6236 7619 6212 7620 6170 7620 7560 7620 7630 7621 7313 7621 6175 7621 7562 7622 5889 7622 5895 7622 6215 7623 7563 7623 6231 7623 7315 7624 6169 7624 7314 7624 6169 7625 6171 7625 7314 7625 7108 7626 7580 7626 7632 7626 7632 7627 6350 7627 7108 7627 7578 7628 7579 7628 7104 7628 7579 7629 7105 7629 7104 7629 6353 7630 7578 7630 7106 7630 7104 7631 7106 7631 7578 7631 7269 7632 7578 7632 6353 7632 7631 7633 7267 7633 6353 7633 7568 7634 6215 7634 7567 7634 7567 7635 6215 7635 6228 7635 6216 7636 6166 7636 7633 7636 7570 7637 6215 7637 7569 7637 7568 7638 7569 7638 6215 7638 6228 7639 6216 7639 7634 7639 7634 7640 6216 7640 7633 7640 7633 7641 5901 7641 5899 7641 7633 7642 5899 7642 7634 7642 7565 7643 6175 7643 7312 7643 6172 7644 6174 7644 6176 7644 6211 7645 6176 7645 6174 7645 6211 7646 6210 7646 7310 7646 7566 7647 5885 7647 5887 7647 5942 7648 6227 7648 5940 7648 6227 7649 5943 7649 6224 7649 5943 7650 5944 7650 6217 7650 7582 7651 7583 7651 6157 7651 6352 7652 5940 7652 6227 7652 6888 7653 6356 7653 6886 7653 6358 7654 6357 7654 6356 7654 6890 7655 6880 7655 6225 7655 6890 7656 6225 7656 6230 7656 6880 7657 6879 7657 6226 7657 6880 7658 6226 7658 6225 7658 6881 7659 6883 7659 6359 7659 6885 7660 6886 7660 6356 7660 6905 7661 6248 7661 6904 7661 6905 7662 6235 7662 6248 7662 6235 7663 6360 7663 6248 7663 6235 7664 6907 7664 6232 7664 6895 7665 6357 7665 6908 7665 6357 7666 6896 7666 6355 7666 6357 7667 6895 7667 6896 7667 6896 7668 6902 7668 6355 7668 6355 7669 6902 7669 6349 7669 6902 7670 6247 7670 6349 7670 6903 7671 6904 7671 6248 7671 6903 7672 6248 7672 6247 7672 6916 7673 6917 7673 6242 7673 6918 7674 6920 7674 6233 7674 6918 7675 6233 7675 6237 7675 6920 7676 6922 7676 6234 7676 6920 7677 6234 7677 6233 7677 6360 7678 6924 7678 6244 7678 6924 7679 6926 7679 6244 7679 6926 7680 6927 7680 6336 7680 6336 7681 6916 7681 6242 7681 6340 7682 6947 7682 6341 7682 6937 7683 6938 7683 6250 7683 6938 7684 6939 7684 6238 7684 6939 7685 6240 7685 6238 7685 6241 7686 6240 7686 6942 7686 6240 7687 6940 7687 6942 7687 6241 7688 6944 7688 6243 7688 6944 7689 6334 7689 6243 7689 6945 7690 6340 7690 6334 7690 6329 7691 6328 7691 6967 7691 6957 7692 6329 7692 6967 7692 6329 7693 6957 7693 6252 7693 6957 7694 6958 7694 6252 7694 6958 7695 6959 7695 6256 7695 6964 7696 6965 7696 6327 7696 6964 7697 6327 7697 6339 7697 6965 7698 6328 7698 6327 7698 6977 7699 6323 7699 6987 7699 6258 7700 6323 7700 6977 7700 6977 7701 6978 7701 6258 7701 6979 7702 6255 7702 6254 7702 6255 7703 6980 7703 6330 7703 6330 7704 6980 7704 6982 7704 6982 7705 6984 7705 6326 7705 6984 7706 6985 7706 6322 7706 6985 7707 6987 7707 6323 7707 6314 7708 7007 7708 6264 7708 6997 7709 6998 7709 6261 7709 6997 7710 6261 7710 6264 7710 6998 7711 6259 7711 6261 7711 6999 7712 7000 7712 6324 7712 6999 7713 6324 7713 6259 7713 6324 7714 7000 7714 7002 7714 7017 7715 6266 7715 6269 7715 7018 7716 7019 7716 6262 7716 7018 7717 6262 7717 6266 7717 7019 7718 7020 7718 6263 7718 6263 7719 7022 7719 6361 7719 6303 7720 7027 7720 6367 7720 7025 7721 7027 7721 6303 7721 6363 7722 7047 7722 6365 7722 7038 7723 6267 7723 6271 7723 7039 7724 7040 7724 6268 7724 6268 7725 7040 7725 7042 7725 6366 7726 7042 7726 6302 7726 7045 7727 7047 7727 6363 7727 7045 7728 6363 7728 6299 7728 7057 7729 6295 7729 7067 7729 7057 7730 6277 7730 6295 7730 6277 7731 6368 7731 6295 7731 6277 7732 7058 7732 6273 7732 7059 7733 7060 7733 6364 7733 6362 7734 6364 7734 7062 7734 6362 7735 7064 7735 6308 7735 7064 7736 7065 7736 6294 7736 7064 7737 6294 7737 6308 7737 7065 7738 7067 7738 6295 7738 7065 7739 6295 7739 6294 7739 7075 7740 6286 7740 6287 7740 6286 7741 7076 7741 6281 7741 7076 7742 6275 7742 6281 7742 7078 7743 7080 7743 6276 7743 6276 7744 7082 7744 6368 7744 6276 7745 7080 7745 7082 7745 6368 7746 7082 7746 6293 7746 7571 7747 5886 7747 7629 7747 6207 7748 5874 7748 7626 7748 7615 7749 7281 7749 7258 7749 7616 7750 7280 7750 7554 7750 7221 7751 7616 7751 7222 7751 7222 7752 7616 7752 7617 7752 7277 7753 7617 7753 6345 7753 7623 7754 7107 7754 7226 7754 7632 7755 7270 7755 7266 7755 7580 7756 7270 7756 7632 7756 7135 7757 6161 7757 6221 7757 6221 7758 6161 7758 6163 7758 6166 7759 5901 7759 7633 7759 5784 7760 5779 7760 7602 7760 5846 7761 7604 7761 5858 7761 5819 7762 5820 7762 6195 7762 5819 7763 6195 7763 5846 7763 7607 7764 5857 7764 5854 7764 7587 7765 5857 7765 7607 7765 5854 7766 5853 7766 7607 7766 5883 7767 5880 7767 7629 7767 7629 7768 5880 7768 7627 7768 7610 7769 5865 7769 7589 7769 5821 7770 7610 7770 7592 7770 7626 7771 5870 7771 7625 7771 7609 7772 7608 7772 5845 7772 5824 7773 5825 7773 6199 7773 5824 7774 6199 7774 5845 7774 7601 7775 6316 7775 7241 7775 7612 7776 7282 7776 7611 7776 7243 7777 7292 7777 6305 7777 7258 7778 7259 7778 7615 7778 6297 7779 7254 7779 7255 7779 7262 7780 7263 7780 7619 7780 7619 7781 7263 7781 7618 7781 7266 7782 7267 7782 7632 7782 7632 7783 7267 7783 7631 7783 5984 7784 5973 7784 7101 7784 7101 7785 5973 7785 5976 7785 7635 7786 6066 7786 6837 7786 6837 7787 7636 7787 7635 7787 7637 7788 6838 7788 6839 7788 6072 7789 6844 7789 6846 7789 6069 7790 6830 7790 6831 7790 6068 7791 6831 7791 6836 7791 6066 7792 6067 7792 6837 7792 6068 7793 6069 7793 6831 7793 7638 7794 7637 7794 6839 7794 6721 7795 6768 7795 6767 7795 6715 7796 6772 7796 6037 7796 6703 7797 6775 7797 6701 7797 6697 7798 6791 7798 6789 7798 6689 7799 6755 7799 6829 7799 6685 7800 6829 7800 6018 7800 6681 7801 6018 7801 6762 7801 6731 7802 6733 7802 6729 7802 6719 7803 6772 7803 6717 7803 6717 7804 6772 7804 6715 7804 6713 7805 6715 7805 6711 7805 6711 7806 6774 7806 6709 7806 6709 7807 6774 7807 6707 7807 6707 7808 6775 7808 6705 7808 6693 7809 6695 7809 6691 7809 6691 7810 6755 7810 6689 7810 6689 7811 6829 7811 6687 7811 6687 7812 6829 7812 6685 7812 6685 7813 6018 7813 6683 7813 6683 7814 6018 7814 6681 7814 6758 7815 6048 7815 6727 7815 6051 7816 6727 7816 6048 7816 6790 53 6650 53 6795 53 6790 53 6655 53 6653 53 6655 7817 6792 7817 7638 7817 7639 7818 6655 7818 7638 7818 7639 53 6072 53 6655 53 7638 7819 6792 7819 6794 7819 7640 7820 7641 7820 7642 7820 7643 7821 7641 7821 7644 7821 7644 7822 7641 7822 7640 7822 7648 243 7645 243 7646 243 7649 7823 7647 7823 7650 7823 7650 7824 7647 7824 7648 7824 7651 7825 7649 7825 7652 7825 7653 7826 7654 7826 7655 7826 7659 7827 7660 7827 7657 7827 7656 7828 7655 7828 7660 7828 7663 243 7662 243 7664 243 7666 7829 7661 7829 7663 7829 7670 7830 7667 7830 7668 7830 7672 7831 7669 7831 7670 7831 7673 427 7671 427 7674 427 7676 7832 7673 7832 7674 7832 7682 243 7677 243 7679 243 7680 243 7683 243 7684 243 7686 243 7675 243 7676 243 7687 7833 7685 7833 7688 7833 7688 7834 7685 7834 7686 7834 7689 243 7687 243 7690 243 7690 243 7687 243 7688 243 7684 7835 7689 7835 7690 7835 7691 7836 7692 7836 7693 7836 7694 7837 7696 7837 7695 7837 7697 7838 7695 7838 7698 7838 7698 7838 7695 7838 7696 7838 7655 7839 7699 7839 7656 7839 7701 7840 7655 7840 7656 7840 7701 7841 7702 7841 7703 7841 7704 7842 7703 7842 7702 7842 7705 7843 7703 7843 7704 7843 7706 7844 7692 7844 7704 7844 7693 7845 7692 7845 7706 7845 7708 7846 7710 7846 7709 7846 7713 7847 7714 7847 7715 7847 7712 7848 7715 7848 7647 7848 7714 7849 7647 7849 7715 7849 7718 7850 7717 7850 7714 7850 7719 7851 7720 7851 7716 7851 7720 7852 7719 7852 7721 7852 7717 7853 7721 7853 7716 7853 7716 7854 7721 7854 7722 7854 7711 7855 7725 7855 7727 7855 7727 7838 7725 7838 7726 7838 7708 7856 7711 7856 7727 7856 7728 7857 7729 7857 7730 7857 7728 7858 7731 7858 7729 7858 7729 7859 7731 7859 7732 7859 7733 7860 7724 7860 7734 7860 7737 6 7666 6 7724 6 7668 6 7738 6 7739 6 7672 6 7668 6 7739 6 7672 7861 7670 7861 7668 7861 7729 7862 7732 7862 7734 7862 7735 7863 7740 7863 7736 7863 7741 6 7740 6 7742 6 7742 6 7743 6 7741 6 7740 6 7745 6 7742 6 7750 7864 7748 7864 7728 7864 7755 7865 7756 7865 7754 7865 7754 7866 7756 7866 7757 7866 7758 7867 7757 7867 7759 7867 7746 7868 7747 7868 7748 7868 7763 7869 7767 7869 7765 7869 7765 7870 7767 7870 7768 7870 7770 6 7768 6 7769 6 7770 7871 7730 7871 7768 7871 7730 7872 7751 7872 7728 7872 7767 7873 7771 7873 7769 7873 7777 7874 7776 7874 7778 7874 7777 6 7778 6 7779 6 7716 7875 7780 7875 7734 7875 7716 7876 7734 7876 7724 7876 7781 6 7706 6 7782 6 7786 7877 7789 7877 7790 7877 7790 7878 7789 7878 7791 7878 7794 7879 7796 7879 7792 7879 7794 7880 7797 7880 7796 7880 7796 7881 7797 7881 7798 7881 7798 6 7797 6 7799 6 7800 7882 7799 7882 7801 7882 7800 6 7798 6 7799 6 7800 7883 7803 7883 7802 7883 7802 7884 7803 7884 7804 7884 7813 7885 7814 7885 7810 7885 7813 7886 7698 7886 7814 7886 7813 7887 7816 7887 7815 7887 7819 7888 7818 7888 7820 7888 7822 7889 7821 7889 7823 7889 7824 6 7823 6 7825 6 7825 6 7827 6 7826 6 7830 6 7828 6 7829 6 7830 7890 7831 7890 7828 7890 7830 7891 7832 7891 7831 7891 7830 6 7834 6 7833 6 7837 6 7836 6 7838 6 7838 6 7840 6 7839 6 7840 7892 7841 7892 7839 7892 7833 7893 7842 7893 7832 7893 7833 7894 7839 7894 7842 7894 7845 7895 7844 7895 7846 7895 7845 7896 7846 7896 7847 7896 7848 7897 7843 7897 7849 7897 7853 6 7851 6 7852 6 7853 7898 7855 7898 7851 7898 7852 6 7782 6 7854 6 7854 6 7782 6 7674 6 7857 7899 7674 7899 7739 7899 7858 7900 7861 7900 7859 7900 7858 7901 7862 7901 7861 7901 7865 7902 7864 7902 7866 7902 7867 7903 7866 7903 7868 7903 7869 7904 7868 7904 7870 7904 7870 7905 7871 7905 7869 7905 7874 7906 7873 7906 7875 7906 7863 6 7864 6 7865 6 7868 7907 7876 7907 7877 7907 7876 7908 7879 7908 7878 7908 7878 7909 7879 7909 7880 7909 7880 7910 7879 7910 7715 7910 7712 7911 7880 7911 7715 7911 7646 7912 7880 7912 7648 7912 7646 7913 7881 7913 7880 7913 7646 7914 7658 7914 7653 7914 7658 7915 7644 7915 7642 7915 7684 7916 7659 7916 7642 7916 7684 7917 7686 7917 7659 7917 7684 6 7690 6 7688 6 7882 7918 7883 7918 7879 7918 7884 7919 7882 7919 7885 7919 7885 7920 7882 7920 7886 7920 7885 7921 7886 7921 7887 7921 7886 7922 7860 7922 7887 7922 7888 7923 7860 7923 7889 7923 7889 7924 7890 7924 7888 7924 7888 7925 7890 7925 7891 7925 7891 7926 7890 7926 7892 7926 7891 7927 7892 7927 7893 7927 7893 7928 7892 7928 7894 7928 7861 7929 7898 7929 7859 7929 7896 7930 7899 7930 7895 7930 7899 7931 7900 7931 7895 7931 7895 6 7900 6 7871 6 7871 7932 7900 7932 7869 7932 7869 7933 7867 7933 7868 7933 7901 7934 7905 7934 7904 7934 7907 7935 7908 7935 7906 7935 7907 7936 7909 7936 7908 7936 7909 7937 7907 7937 7910 7937 7911 7938 7910 7938 7913 7938 7916 7939 7914 7939 7915 7939 7917 7940 7918 7940 7811 7940 7909 7941 7910 7941 7912 7941 7915 7942 7903 7942 7919 7942 7920 7943 7902 7943 7921 7943 7819 7944 7817 7944 7818 7944 7815 7945 7881 7945 7698 7945 7700 6 7881 6 7653 6 7656 7946 7700 7946 7653 7946 7704 7947 7656 7947 7659 7947 7880 7948 7881 7948 7832 7948 7821 7949 7922 7949 7823 7949 7823 7950 7922 7950 7908 7950 7918 7951 7812 7951 7811 7951 7859 7952 7889 7952 7860 7952 7788 7953 7787 7953 7924 7953 7808 7954 7924 7954 7805 7954 7788 6 7924 6 7808 6 7927 7955 7928 7955 7926 7955 7927 7956 7929 7956 7928 7956 7927 7957 7930 7957 7929 7957 7929 7958 7930 7958 7931 7958 7932 7959 7931 7959 7801 7959 7799 7960 7932 7960 7801 7960 7925 7961 7926 7961 7928 7961 7846 7962 7929 7962 7847 7962 7845 7963 7795 7963 7844 7963 7752 7964 7753 7964 7754 7964 7814 7965 7698 7965 7783 7965 7783 6 7698 6 7696 6 7783 7966 7696 7966 7693 7966 7829 7967 7935 7967 7933 7967 7829 6 7827 6 7935 6 7836 6 7835 6 7936 6 7933 6 7936 6 7934 6 7837 6 7834 6 7836 6 7938 6 7838 6 7836 6 7871 7968 7873 7968 7874 7968 7879 7969 7883 7969 7713 7969 7715 7970 7879 7970 7713 7970 7883 6 7779 6 7713 6 7713 6 7779 6 7718 6 7758 7971 7754 7971 7757 7971 7914 7972 7911 7972 7913 7972 7825 7973 7939 7973 7940 7973 7712 7974 7710 7974 7648 7974 7652 7975 7727 7975 7726 7975 7664 6 7726 6 7663 6 7664 7976 7680 7976 7652 7976 7664 7977 7679 7977 7680 7977 7664 6 7682 6 7679 6 7693 7978 7696 7978 7694 7978 7706 7979 7704 7979 7676 7979 7676 7980 7704 7980 7686 7980 7704 7981 7702 7981 7656 7981 7642 7982 7644 7982 7640 7982 7941 7983 7942 7983 7943 7983 7941 7984 7948 7984 7947 7984 7954 7985 7952 7985 7953 7985 7954 7986 7955 7986 7952 7986 7956 7987 7945 7987 7946 7987 7961 7988 7959 7988 7960 7988 7962 7989 7963 7989 7965 7989 7966 53 7962 53 7965 53 7967 7990 1889 7990 1886 7990 7969 53 7971 53 7970 53 7975 7991 7974 7991 7976 7991 7976 7992 7977 7992 7975 7992 7975 53 7977 53 7978 53 7978 7993 7977 7993 7979 7993 7979 7994 7980 7994 7978 7994 7979 53 7981 53 7980 53 7980 53 7981 53 7982 53 7973 7995 7983 7995 7984 7995 7697 53 7985 53 7695 53 7692 7996 7695 7996 7985 7996 7983 53 7974 53 7975 53 7987 53 7986 53 7988 53 7988 7997 7989 7997 7987 7997 7988 7998 7990 7998 7989 7998 7993 53 5550 53 7992 53 7993 7999 7994 7999 5550 7999 7996 8000 7995 8000 7997 8000 7998 8001 7997 8001 7999 8001 8000 8002 8001 8002 7998 8002 8000 53 7989 53 8001 53 8003 8003 8002 8003 8004 8003 7982 8004 8004 8004 8005 8004 7985 53 8005 53 7692 53 7995 8005 8006 8005 7997 8005 8008 8006 8009 8006 7997 8006 8011 8007 8010 8007 8012 8007 8016 53 7673 53 8014 53 8016 8008 8018 8008 7673 8008 7673 53 8018 53 7671 53 7671 53 8018 53 8019 53 7667 53 8019 53 7665 53 7667 8009 7671 8009 8019 8009 7667 53 7669 53 7671 53 8019 53 8020 53 7665 53 7665 8010 8020 8010 8021 8010 8022 8011 8021 8011 8023 8011 8022 53 8023 53 8024 53 8025 8012 8024 8012 8026 8012 8022 8013 8025 8013 8027 8013 8029 8014 8030 8014 8028 8014 8031 8015 8032 8015 8033 8015 7725 8016 7661 8016 7723 8016 7725 8017 7651 8017 7662 8017 7725 8018 7711 8018 7651 8018 7651 8019 7711 8019 7649 8019 8036 8020 8026 8020 8035 8020 8032 8021 8035 8021 8037 8021 8038 8022 8032 8022 8037 8022 7451 8023 8039 8023 8033 8023 7451 8024 8041 8024 8040 8024 7451 8025 7448 8025 8041 8025 8042 8026 7448 8026 8043 8026 8044 53 8042 53 8043 53 8044 53 8046 53 8045 53 8048 8027 8047 8027 8049 8027 8048 8028 8049 8028 8039 8028 8050 8029 8044 8029 8043 8029 8054 8030 8055 8030 7714 8030 7723 53 8054 53 7717 53 7723 8031 8056 8031 8054 8031 8058 53 8060 53 7714 53 8061 8032 8062 8032 8063 8032 8064 8033 8062 8033 8065 8033 8064 8034 8065 8034 8066 8034 8067 8035 8066 8035 8068 8035 8067 8036 8068 8036 8069 8036 8070 53 8069 53 8071 53 8072 53 8070 53 8071 53 8072 53 7957 53 8060 53 8072 53 7944 53 7957 53 8074 8037 8059 8037 8073 8037 8078 53 8077 53 8079 53 8079 8038 8066 8038 8065 8038 8059 53 8074 53 8075 53 8080 8039 8076 8039 3701 8039 8081 8040 8080 8040 3702 8040 3702 8041 2465 8041 8081 8041 8085 53 8086 53 3742 53 8085 8042 8087 8042 8086 8042 7943 8043 8090 8043 8089 8043 8086 8044 8088 8044 8089 8044 8027 8045 8028 8045 8030 8045 8086 53 8069 53 3742 53 3742 8046 8069 8046 8068 8046 8067 53 8069 53 8070 53 8069 8047 8091 8047 8071 8047 8017 8048 8014 8048 8012 8048 7982 8049 7981 8049 8003 8049 8005 53 8014 53 7692 53 7692 53 8014 53 7675 53 2465 8050 8084 8050 8082 8050 8092 53 7645 53 8060 53 8092 8051 7654 8051 7645 8051 7973 53 8093 53 7965 53 7965 8052 8093 8052 8094 8052 8031 53 8047 53 8030 53 8030 8053 8047 8053 8046 8053 8095 8054 8046 8054 8096 8054 1849 8055 7958 8055 7953 8055 7703 8056 7660 8056 7655 8056 7685 8057 7705 8057 7675 8057 7660 8058 7685 8058 7683 8058 7678 8059 7657 8059 7683 8059 7678 8060 7662 8060 7651 8060 7678 53 7681 53 7662 53 7661 8061 7665 8061 8022 8061 7673 8062 7675 8062 8014 8062 7645 8063 7654 8063 7643 8063 7643 8064 7654 8064 7657 8064 7657 8065 7641 8065 7643 8065 8100 8066 8089 8066 8091 8066 8097 8067 8069 8067 8098 8067 8103 8068 8104 8068 7938 8068 7938 8069 8104 8069 7838 8069 7838 8070 8104 8070 8105 8070 7838 8071 8106 8071 8107 8071 7840 8072 8107 8072 8108 8072 7840 8073 8109 8073 8110 8073 7873 8074 8111 8074 8112 8074 8115 8075 8116 8075 8117 8075 8118 8076 8120 8076 8121 8076 8121 8077 8122 8077 8123 8077 8124 8078 8121 8078 8123 8078 8124 8079 8125 8079 8121 8079 8125 8080 8127 8080 8117 8080 8117 8081 8127 8081 8115 8081 7942 7838 8072 7838 7834 7838 8090 8082 7942 8082 7837 8082 7839 8083 8090 8083 7837 8083 8072 427 8071 427 7833 427 8126 8084 8128 8084 7874 8084 8129 8085 8130 8085 3742 8085 8085 8086 8130 8086 8087 8086 8130 8087 8131 8087 8087 8087 8087 8088 8131 8088 8088 8088 8131 8089 8132 8089 8088 8089 8088 8090 8132 8090 7943 8090 8117 8091 8121 8091 8125 8091 8135 8092 7947 8092 7951 8092 8136 8093 7952 8093 7946 8093 8135 8094 7952 8094 8136 8094 8136 8095 7946 8095 8134 8095 7956 427 7957 427 7829 427 7829 427 7957 427 7830 427 7945 8096 7956 8096 7934 8096 7934 8097 7956 8097 7829 8097 7944 8098 7945 8098 7835 8098 7937 8099 8139 8099 7936 8099 8140 8100 8141 8100 7940 8100 7825 8101 8142 8101 8143 8101 7935 8102 8145 8102 8146 8102 7935 8103 8146 8103 8147 8103 7935 8104 8147 8104 8148 8104 7933 8105 8148 8105 8149 8105 7933 8106 8150 8106 8138 8106 7825 8107 8144 8107 7827 8107 7935 8108 8148 8108 7933 8108 8151 8109 8152 8109 8153 8109 8155 8110 8151 8110 8156 8110 8156 8111 8151 8111 8153 8111 8159 8112 8160 8112 8156 8112 8163 427 8140 427 7939 427 8164 8113 8162 8113 8154 8113 8132 8114 8165 8114 7943 8114 7943 8115 8165 8115 7941 8115 8165 8116 8166 8116 7941 8116 7941 8117 8166 8117 7948 8117 7949 8118 8167 8118 7950 8118 7950 8119 8168 8119 1849 8119 8156 6 8153 6 8154 6 8156 8120 8154 8120 8159 8120 7984 8121 7783 8121 7985 8121 7984 8122 7814 8122 7783 8122 7814 8123 7984 8123 7983 8123 7807 8124 7975 8124 7978 8124 7808 8125 7978 8125 7980 8125 7788 8126 7980 8126 7982 8126 7810 8127 7975 8127 7807 8127 7788 8128 7982 8128 7784 8128 7784 8129 7985 8129 7783 8129 8169 8130 8174 8130 8013 8130 8171 8131 7997 8131 8172 8131 8029 8132 8175 8132 8032 8132 8029 8133 8176 8133 8175 8133 8176 8134 8029 8134 8028 8134 8178 8135 8026 8135 8036 8135 8176 8136 8028 8136 8177 8136 8179 8137 8032 8137 8175 8137 8095 8138 7731 8138 7728 8138 7731 8139 8095 8139 7732 8139 7735 8140 8056 8140 8022 8140 7747 8141 8022 8141 8027 8141 7749 8142 8027 8142 8030 8142 7733 8143 8056 8143 7735 8143 8049 8144 7772 8144 8039 8144 7769 8145 8049 8145 8047 8145 7750 8146 8047 8146 8031 8146 7755 8147 8031 8147 8034 8147 7772 8148 7757 8148 8039 8148 7751 8149 8047 8149 7750 8149 7750 8150 8031 8150 7753 8150 8001 8151 7797 8151 7794 8151 7799 8152 8001 8152 7990 8152 7929 8153 7990 8153 7992 8153 7799 8154 7990 8154 7932 8154 7929 8155 7992 8155 7847 8155 7931 8156 7993 8156 7991 8156 7803 8157 7800 8157 7988 8157 7803 8158 7994 8158 7926 8158 7930 8159 7993 8159 7931 8159 7931 8160 7991 8160 7801 8160 7981 8161 7787 8161 8003 8161 7790 8162 7989 8162 8003 8162 7787 8163 7786 8163 8003 8163 7805 8164 7979 8164 7802 8164 7802 8165 7987 8165 7798 8165 7792 8166 7989 8166 7790 8166 7790 8167 8003 8167 7786 8167 7859 8168 8083 8168 8077 8168 7890 8169 8077 8169 8080 8169 7897 8170 8081 8170 7898 8170 7898 8171 8083 8171 7859 8171 7889 8172 8077 8172 7890 8172 7890 8173 8080 8173 7892 8173 8067 8174 7870 8174 8064 8174 7870 8175 8067 8175 7872 8175 7923 8176 8067 8176 8070 8176 7872 8177 8067 8177 7923 8177 7842 8178 8070 8178 7832 8178 7878 8179 8061 8179 7877 8179 7818 8180 7965 8180 7920 8180 7916 8181 7964 8181 7970 8181 7818 8182 7816 8182 7965 8182 7919 8183 7964 8183 7915 8183 7915 8184 7964 8184 7916 8184 7916 8185 7970 8185 7918 8185 7820 8186 7962 8186 7953 8186 7904 8187 7959 8187 7902 8187 7902 8188 7962 8188 7921 8188 7921 8189 7962 8189 7820 8189 7820 8190 7953 8190 7821 8190 7824 8191 7955 8191 7954 8191 7817 8192 7966 8192 8094 8192 7881 8193 8093 8193 8092 8193 7822 8194 7954 8194 7819 8194 7819 8195 7966 8195 7817 8195 7817 8196 8094 8196 7815 8196 7905 8197 7961 8197 7960 8197 7901 8198 7903 8198 7961 8198 7907 8199 7967 8199 7910 8199 7913 8200 7968 8200 7903 8200 7869 8201 8068 8201 8066 8201 7899 8202 7896 8202 8082 8202 7867 8203 8066 8203 7865 8203 7865 8204 8066 8204 7863 8204 7863 8205 8079 8205 7861 8205 7861 8206 8082 8206 7896 8206 8078 8207 7862 8207 7858 8207 7862 8208 8078 8208 7864 8208 7860 8209 8059 8209 8075 8209 7864 8210 8065 8210 7866 8210 7866 8211 8065 8211 7876 8211 7876 8212 8062 8212 7879 8212 7879 8213 8058 8213 7882 8213 7886 8214 8059 8214 7860 8214 8005 8151 7785 8151 7781 8151 8005 8215 8004 8215 7785 8215 7793 8216 8002 8216 8000 8216 7781 8217 7782 8217 8014 8217 7791 8218 8002 8218 7793 8218 7850 8219 8015 8219 7852 8219 7852 8220 8014 8220 7782 8220 8044 8221 8051 8221 7775 8221 7775 8222 8051 8222 7776 8222 7778 8223 8051 8223 8054 8223 7778 8224 8054 8224 7780 8224 7780 8225 8054 8225 7734 8225 7734 8226 8054 8226 7729 8226 7729 8227 8096 8227 7730 8227 8041 8228 7762 8228 7760 8228 7763 8229 8041 8229 8042 8229 7771 8230 8045 8230 8048 8230 7760 8231 8040 8231 8041 8231 7767 8232 8045 8232 7771 8232 7774 8233 8048 8233 7759 8233 7759 8234 8040 8234 7760 8234 8180 8235 7743 8235 8181 8235 8181 8236 7743 8236 8182 8236 8184 8237 7742 8237 7746 8237 8185 8238 7746 8238 7748 8238 8186 8239 7748 8239 7752 8239 8187 8240 8188 8240 7752 8240 8189 8241 7746 8241 8185 8241 8190 8242 7748 8242 8186 8242 8186 8243 7752 8243 8191 8243 8191 8244 7752 8244 8188 8244 8139 427 8102 427 7936 427 7936 427 8102 427 7836 427 7895 8245 8194 8245 7893 8245 7893 8246 8195 8246 7891 8246 7891 8247 8195 8247 7888 8247 8195 8248 8196 8248 7888 8248 7888 8249 8196 8249 7887 8249 8196 8250 8197 8250 7887 8250 7887 8251 8197 8251 7885 8251 7885 8252 8198 8252 7884 8252 7883 8253 8199 8253 7779 8253 8201 8254 8202 8254 7766 8254 7766 8255 8202 8255 7764 8255 8202 8256 8203 8256 7764 8256 7764 8257 8203 8257 7761 8257 8203 8258 8204 8258 7761 8258 7744 8259 8207 8259 7741 8259 8210 8260 7736 8260 8209 8260 7737 8261 8211 8261 7738 8261 7739 8262 8212 8262 8213 8262 7741 8263 8208 8263 7736 8263 7738 243 8212 243 7739 243 7739 8264 8213 8264 7857 8264 7856 8265 8217 8265 7855 8265 7855 8266 8219 8266 8220 8266 7843 8267 8224 8267 8225 8267 7843 8268 8225 8268 8226 8268 7851 8269 8222 8269 7843 8269 7843 8270 8226 8270 7844 8270 7844 8271 8228 8271 7846 8271 7846 243 8228 243 8229 243 8229 8272 8230 8272 7846 8272 7928 8273 8231 8273 7925 8273 8231 8274 8232 8274 7925 8274 8232 8275 8233 8275 7804 8275 8233 8276 8234 8276 7806 8276 8235 8277 8236 8277 7809 8277 7809 8278 8236 8278 7811 8278 7811 8279 8237 8279 7917 8279 8238 8280 8239 8280 7911 8280 7911 8281 8239 8281 7912 8281 7912 8282 8240 8282 7909 8282 8242 8283 8243 8283 7908 8283 7908 8284 8243 8284 7823 8284 7939 8285 7823 8285 8163 8285 8163 8286 7823 8286 8243 8286 8244 8287 8024 8287 8245 8287 8245 8288 8024 8288 8023 8288 8246 8289 8023 8289 8021 8289 8247 8290 8021 8290 8020 8290 8249 8291 8019 8291 8018 8291 8251 8292 8016 8292 8017 8292 8253 8293 8012 8293 8010 8293 8254 8294 8253 8294 8010 8294 8245 8288 8023 8288 8246 8288 8246 8295 8021 8295 8247 8295 8247 8296 8020 8296 8248 8296 8248 8297 8019 8297 8249 8297 8249 8298 8018 8298 8250 8298 8252 8299 8012 8299 8253 8299 8033 8300 8038 8300 8255 8300 8255 8301 8038 8301 8256 8301 7451 8302 8033 8302 8258 8302 8258 8303 8033 8303 8255 8303 7448 8304 7451 8304 8259 8304 8052 8305 8050 8305 8262 8305 8262 8306 8050 8306 8261 8306 8053 8307 8052 8307 8263 8307 8055 8308 8053 8308 8264 8308 8265 8309 8055 8309 8264 8309 8073 8310 8057 8310 8265 8310 8266 8311 8073 8311 8265 8311 8267 8312 8074 8312 8266 8312 8076 8313 8074 8313 8267 8313 3701 8314 8076 8314 8268 8314 3702 8315 3701 8315 8270 8315 8270 8316 3701 8316 8269 8316 2465 8317 3702 8317 8271 8317 8271 8318 3702 8318 8270 8318 8272 8319 2465 8319 8271 8319 8129 8320 3742 8320 8272 8320 8273 8321 1849 8321 8168 8321 1575 8322 1849 8322 8274 8322 1889 8323 1575 8323 8275 8323 8275 8324 1575 8324 8274 8324 8276 8325 1889 8325 8275 8325 7972 8326 7971 8326 8280 8326 8281 8327 7976 8327 8280 8327 8283 8328 7977 8328 8282 8328 7986 8329 7977 8329 8283 8329 8284 8330 7986 8330 8283 8330 5550 8331 5549 8331 8285 8331 8285 8332 5549 8332 8284 8332 7995 8333 5550 8333 8286 8333 8286 8334 5550 8334 8285 8334 8254 8335 8008 8335 8007 8335 8254 8336 8007 8336 8287 8336 8157 8337 8138 8337 8133 8337 8137 8338 8157 8338 8133 8338 8147 8339 8134 8339 8148 8339 8134 8340 8146 8340 8136 8340 8136 8341 8145 8341 8144 8341 8133 8342 8150 8342 8134 8342 8140 8343 8163 8343 8151 8343 8242 8344 8273 8344 8168 8344 8277 8345 8240 8345 8239 8345 8278 8346 8238 8346 8237 8346 8280 8347 8237 8347 8236 8347 8280 8348 8236 8348 8235 8348 8280 8349 8235 8349 8281 8349 8277 8350 8238 8350 8278 8350 8281 8351 8235 8351 8282 8351 8282 8352 8235 8352 8234 8352 8283 8353 8234 8353 8233 8353 8291 6 8217 6 8216 6 8173 8354 8218 8354 8217 8354 8283 8355 8231 8355 8284 8355 8229 8356 8228 8356 8288 8356 8288 8357 8228 8357 8293 8357 8292 8358 8293 8358 8172 8358 8170 8359 8225 8359 8224 8359 8169 8360 8223 8360 8222 8360 8253 8361 8216 8361 8215 8361 8252 6 8215 6 8214 6 8249 6 8212 6 8211 6 8245 6 8208 6 8207 6 8244 8362 8295 8362 8257 8362 8257 8363 8295 8363 8256 8363 8256 8364 8295 8364 8296 8364 8256 8365 8296 8365 8255 8365 8297 8366 8255 8366 8296 8366 8297 6 8187 6 8206 6 8187 8367 8298 8367 8175 8367 8191 8368 8175 8368 8176 8368 8253 8369 8215 8369 8252 8369 8250 8370 8212 8370 8249 8370 8246 6 8208 6 8245 6 8179 8371 8298 8371 8299 8371 8298 8372 8179 8372 8175 8372 8177 8373 8182 8373 8183 8373 8258 8374 8206 8374 8205 8374 8259 8375 8204 8375 8203 8375 8260 8376 8202 8376 8201 8376 8259 8377 8203 8377 8260 8377 8260 8378 8201 8378 8261 8378 8201 8379 8200 8379 8262 8379 8262 8380 8200 8380 8263 8380 8263 8381 8200 8381 8264 8381 8199 8382 8265 8382 8264 8382 8267 8383 8197 8383 8196 8383 8269 8384 8195 8384 8194 8384 8266 8385 8197 8385 8267 8385 8272 8386 8193 8386 8192 8386 8271 8387 8193 8387 8272 8387 8126 8388 8129 8388 8128 8388 8126 8389 8130 8389 8129 8389 8126 8390 8114 8390 8116 8390 8097 8391 8109 8391 8108 8391 8100 8392 8108 8392 8107 8392 8106 8393 8105 8393 8100 8393 8099 8394 8124 8394 8123 8394 8099 8395 8123 8395 8122 8395 8132 8396 8102 8396 8165 8396 8132 8397 8127 8397 8125 8397 8244 6 8245 6 8207 6 8286 8398 8285 8398 8229 8398 8275 8399 8274 8399 8240 8399 8301 8400 8288 8400 8293 8400 8301 8401 8292 8401 8302 8401 8302 8402 8292 8402 8303 8402 8290 8403 8289 8403 8304 8403 8304 8404 8300 8404 8301 8404 8301 8405 8303 8405 8304 8405 8301 8406 8302 8406 8303 8406 8299 8407 8298 8407 8306 8407 8306 8408 8298 8408 8307 8408 8296 8409 8295 8409 8309 8409 8309 8410 8307 8410 8308 8410 8310 8411 8311 8411 8312 8411 8311 8412 8314 8412 8313 8412 8311 8413 8315 8413 8314 8413 8319 6 8320 6 8317 6 8319 6 8321 6 8320 6 8321 6 8322 6 8323 6 8324 6 8325 6 8323 6 8333 8414 8332 8414 8310 8414 8331 8415 8332 8415 8334 8415 8340 8416 8339 8416 8341 8416 8342 8417 8340 8417 8341 8417 8341 8418 8343 8418 8342 8418 8341 8419 8344 8419 8343 8419 8348 8420 8347 8420 8349 8420 8317 6 8351 6 8352 6 8317 6 8320 6 8351 6 8353 8421 8354 8421 8355 8421 8355 8422 8357 8422 8356 8422 8356 8423 8357 8423 8358 8423 8357 8424 8360 8424 8359 8424 8359 8425 8360 8425 8361 8425 8362 8426 8355 8426 8354 8426 8364 8427 8365 8427 8363 8427 8365 8428 8366 8428 8367 8428 8367 8429 8371 8429 8369 8429 8372 8430 8371 8430 8373 8430 8373 8431 8371 8431 8374 8431 8375 8432 8374 8432 8376 8432 8373 8433 8374 8433 8375 8433 8378 8434 8377 8434 8379 8434 8381 8435 8382 8435 8377 8435 8381 8436 8383 8436 8382 8436 8390 8437 8389 8437 8391 8437 8383 8438 8385 8438 8387 8438 8350 6 8394 6 8383 6 8389 6 8388 6 8359 6 8359 8439 8388 8439 8358 8439 8399 6 8400 6 8401 6 8399 8440 8402 8440 8400 8440 8405 6 8404 6 8406 6 8407 6 8406 6 8321 6 8407 8441 8405 8441 8406 8441 8410 6 8409 6 8326 6 8406 6 8411 6 8321 6 8412 8442 8413 8442 8414 8442 8320 8443 8411 8443 8412 8443 8410 8444 8326 8444 8327 8444 8416 8445 8417 8445 8352 8445 8392 8446 8417 8446 8393 8446 8392 8447 8352 8447 8417 8447 8390 8448 8387 8448 8389 8448 8418 8449 2396 8449 8414 8449 8402 8450 8418 8450 8400 8450 8420 8451 6087 8451 8421 8451 8423 6 6087 6 8422 6 6087 8452 8423 8452 6078 8452 8424 8453 7319 8453 6078 8453 8422 8454 8379 8454 8426 8454 8379 8455 8422 8455 8420 8455 8426 8456 8379 8456 8397 8456 8398 6 8379 6 8382 6 8398 8457 8397 8457 8379 8457 8427 6 8428 6 8380 6 8427 6 8429 6 8428 6 8432 6 8405 6 8431 6 8432 8458 8433 8458 8405 8458 8329 6 8328 6 8435 6 8436 8459 1755 8459 529 8459 8324 6 8438 6 8437 6 8328 8460 8436 8460 529 8460 4232 6 8439 6 8442 6 8442 8461 4230 8461 4232 8461 8443 8462 4231 8462 8442 8462 8443 8463 4218 8463 4231 8463 4218 8464 8443 8464 8441 8464 8444 8465 8441 8465 8389 8465 4218 8466 8441 8466 8444 8466 8445 8467 4218 8467 8444 8467 8446 8468 4218 8468 8445 8468 8448 8469 8359 8469 8361 8469 8430 8470 8429 8470 8421 8470 8449 8471 8450 8471 8430 8471 8448 8472 8454 8472 8453 8472 8455 8473 8430 8473 6087 8473 8457 8474 8458 8474 4218 8474 8428 8475 8451 8475 8460 8475 8461 8476 8462 8476 8378 8476 8378 8477 8380 8477 8461 8477 8467 8478 8357 8478 8468 8478 8467 8479 8469 8479 8357 8479 8464 8480 8355 8480 8363 8480 8464 8481 8468 8481 8355 8481 8469 8482 8466 8482 8360 8482 8310 8483 8470 8483 8311 8483 8311 8484 8470 8484 8472 8484 8332 8485 8475 8485 8476 8485 8311 8486 8473 8486 8315 8486 8316 8487 8475 8487 8330 8487 8330 8488 8475 8488 8332 8488 8338 8489 8477 8489 8479 8489 8339 8490 8480 8490 8481 8490 8341 8491 8481 8491 8482 8491 8344 8492 8482 8492 8483 8492 8347 8493 8484 8493 8335 8493 8484 8494 8478 8494 8335 8494 8352 8495 8485 8495 8317 8495 8317 8496 8486 8496 8314 8496 8318 8497 8489 8497 8490 8497 8319 8498 8490 8498 8491 8498 8331 8499 8489 8499 8318 8499 8319 8500 8492 8500 8322 8500 8337 8501 8493 8501 8494 8501 8337 8502 8494 8502 8350 8502 8499 8503 8340 8503 8498 8503 8342 8504 8343 8504 8498 8504 8498 8505 8343 8505 8500 8505 8345 8506 8501 8506 8343 8506 8450 8507 8502 8507 8503 8507 8451 8508 8503 8508 8460 8508 8502 8509 8455 8509 8504 8509 8504 8510 8455 8510 8505 8510 8506 8511 8455 8511 8507 8511 8507 8512 8508 8512 8506 8512 8507 8513 8509 8513 8508 8513 8510 8514 8511 8514 8508 8514 8513 8515 8497 8515 8496 8515 8518 8516 8517 8516 8519 8516 8519 8517 8520 8517 8521 8517 8509 53 8520 53 8510 53 8495 8518 8478 8518 8525 8518 8495 8519 8494 8519 8478 8519 8478 8520 8494 8520 8477 8520 8477 8521 8494 8521 8493 8521 8479 8522 8499 8522 8480 8522 8481 8523 8499 8523 8498 8523 8482 8524 8498 8524 8500 8524 8500 8525 8501 8525 8482 8525 8482 8526 8501 8526 8483 8526 8483 8527 8526 8527 8484 8527 8484 8528 8526 8528 8525 8528 8478 8529 8484 8529 8525 8529 8530 8530 8531 8530 8529 8530 8529 8531 8531 8531 8532 8531 8533 8532 8531 8532 8534 8532 8537 8533 8539 8533 8538 8533 8539 8534 8540 8534 8541 8534 8542 8535 8535 8535 8538 8535 8542 8536 8544 8536 8543 8536 8542 8537 8545 8537 8544 8537 8548 53 8547 53 8549 53 8548 8538 8550 8538 8545 8538 8548 53 8551 53 8528 53 8552 8539 8553 8539 8546 8539 8557 8540 8555 8540 8558 8540 8559 8541 8560 8541 8492 8541 8551 53 8491 53 8524 53 8561 8542 8562 8542 8555 8542 8561 8543 8563 8543 8562 8543 8564 8544 8563 8544 8561 8544 8565 8545 8564 8545 8492 8545 8566 8546 8565 8546 8492 8546 8492 8547 8560 8547 8566 8547 8559 53 8492 53 8551 53 8491 53 8490 53 8486 53 8487 8548 8473 8548 8472 8548 8474 8549 8490 8549 8475 8549 8523 53 8485 53 8570 53 8570 8550 8485 8550 8571 8550 8571 8551 8485 8551 8572 8551 8571 8552 8572 8552 8573 8552 8577 8553 8578 8553 8575 8553 8575 8554 8578 8554 8579 8554 8581 8555 8582 8555 8580 8555 8583 8556 8572 8556 8584 8556 8585 8557 8584 8557 8586 8557 8583 8558 8584 8558 8585 8558 8587 8559 8583 8559 8585 8559 8587 8560 8588 8560 8583 8560 8589 8561 8588 8561 8458 8561 8586 8562 8584 8562 8591 8562 8592 8563 8586 8563 8591 8563 8593 8564 8591 8564 8459 8564 8594 8565 8459 8565 8458 8565 8596 8566 8453 8566 8454 8566 8465 8567 8597 8567 8596 8567 8469 53 8597 53 8466 53 8469 53 8598 53 8597 53 8598 8568 8469 8568 8467 8568 8599 8569 8600 8569 8468 8569 8461 8570 8460 8570 8607 8570 8607 53 8460 53 8503 53 8599 8571 8468 8571 8608 8571 8608 8572 8468 8572 8464 8572 8608 8573 8464 8573 8609 8573 8606 8574 8463 8574 8462 8574 8606 8575 8609 8575 8463 8575 8451 8576 8450 8576 8503 8576 8450 8577 8449 8577 8502 8577 8598 53 8576 53 8597 53 8597 8578 8576 8578 8574 8578 8575 8579 8579 8579 8580 8579 8523 53 8575 53 8580 53 8522 53 8514 53 8496 53 8550 53 8610 53 8545 53 8545 8580 8610 8580 8611 8580 8533 8581 8532 8581 8531 8581 8613 8582 8614 8582 8557 8582 8614 8583 8549 8583 8615 8583 8575 8584 8573 8584 8574 8584 8538 8585 8535 8585 8536 8585 8555 8586 8562 8586 8558 8586 8345 8587 8348 8587 8501 8587 8501 8588 8348 8588 8526 8588 8349 8589 8524 8589 8525 8589 8348 8590 8525 8590 8526 8590 8569 8591 8334 8591 8333 8591 8568 8592 8334 8592 8569 8592 8489 8593 8334 8593 8568 8593 8312 8594 8488 8594 8567 8594 8320 8595 8412 8595 8524 8595 8517 8596 8426 8596 8520 8596 8497 8597 8510 8597 8397 8597 8397 8598 8510 8598 8426 8598 8485 8599 8392 8599 8572 8599 4232 8600 4230 8600 8591 8600 8440 8601 4232 8601 8584 8601 8322 8602 8492 8602 8438 8602 1755 8603 8564 8603 529 8603 529 8604 8564 8604 8561 8604 7319 8605 8517 8605 6078 8605 8591 8606 4230 8606 8459 8606 8552 8607 8431 8607 8435 8607 8546 8608 8542 8608 8431 8608 8415 8609 2396 8609 8538 8609 2398 8610 8539 8610 8412 8610 8493 8611 8340 8611 8499 8611 8569 8612 8312 8612 8567 8612 8492 8613 8564 8613 8438 8613 8438 8614 8564 8614 1755 8614 8366 8615 8609 8615 8606 8615 8353 8616 8600 8616 8354 8616 8377 8617 8582 8617 8581 8617 8385 8618 8578 8618 8577 8618 8386 8619 8577 8619 8576 8619 8388 8620 8386 8620 8576 8620 8375 8621 8603 8621 8373 8621 8372 8622 8582 8622 8369 8622 8513 8623 8396 8623 8512 8623 8512 8624 8396 8624 8398 8624 8580 8625 8398 8625 8382 8625 8580 8626 8382 8626 8383 8626 8513 8627 8395 8627 8396 8627 8580 8628 8383 8628 8522 8628 8522 8629 8383 8629 8514 8629 8514 8630 8395 8630 8513 8630 8528 8631 8401 8631 8411 8631 8550 8632 8411 8632 8406 8632 8529 8633 8399 8633 8401 8633 8529 8634 8401 8634 8528 8634 8528 8635 8411 8635 8550 8635 8550 8636 8406 8636 8610 8636 8551 8637 8321 8637 8559 8637 8559 8638 8321 8638 8323 8638 8613 8639 8323 8639 8326 8639 8549 8640 8409 8640 8548 8640 8387 8641 8390 8641 8573 8641 8523 8642 8351 8642 8575 8642 8553 8643 8434 8643 8547 8643 8329 8644 8553 8644 8554 8644 8410 8645 8557 8645 8614 8645 8410 8646 8614 8646 8615 8646 8327 8647 8557 8647 8410 8647 8325 8648 8558 8648 8436 8648 8436 8649 8562 8649 8563 8649 8324 8650 8566 8650 8560 8650 8437 8651 8566 8651 8324 8651 8441 8652 8587 8652 8585 8652 8443 8653 8594 8653 8441 8653 8574 8654 8389 8654 8597 8654 8574 8655 8583 8655 8389 8655 8444 8656 8583 8656 8588 8656 8445 8657 8588 8657 8589 8657 8445 8658 8589 8658 8590 8658 8444 8659 8588 8659 8445 8659 8445 8660 8590 8660 8446 8660 8446 8661 8595 8661 8359 8661 8505 8662 8506 8662 8420 8662 8427 8663 8607 8663 8503 8663 8427 8664 8503 8664 8502 8664 8421 8665 8502 8665 8504 8665 8421 8666 8504 8666 8505 8666 8420 8667 8421 8667 8505 8667 8420 8668 8506 8668 8379 8668 8427 8669 8502 8669 8421 8669 8424 8670 8518 8670 8425 8670 8425 8671 8519 8671 8521 8671 8424 8672 8515 8672 8516 8672 8425 8673 8521 8673 8422 8673 8535 8674 8433 8674 8419 8674 8535 8675 8543 8675 8433 8675 8403 8676 8545 8676 8611 8676 8403 8677 8611 8677 8612 8677 8405 8678 8545 8678 8403 8678 8403 8679 8612 8679 8402 8679 8418 8680 8536 8680 8534 8680 8400 8681 8534 8681 8531 8681 8413 8682 8530 8682 8541 8682 8414 8683 8540 8683 8537 8683 8413 8684 8541 8684 8414 8684 8561 8685 8555 8685 529 8685 8616 8265 8617 8265 8618 8265 8627 8686 8629 8686 8628 8686 8635 8687 8634 8687 8636 8687 8637 8688 8636 8688 8638 8688 8639 8689 8638 8689 8640 8689 8643 8690 8642 8690 8644 8690 8625 8691 8657 8691 8624 8691 8656 8692 8657 8692 8655 8692 8628 8693 8630 8693 8631 8693 8659 8694 8631 8694 8660 8694 8659 8695 8628 8695 8631 8695 8631 8696 8632 8696 8633 8696 8660 8697 8631 8697 8633 8697 8662 8698 8637 8698 8663 8698 8662 8699 8635 8699 8637 8699 8637 8700 8638 8700 8639 8700 8663 8701 8639 8701 8664 8701 8664 8702 8639 8702 8641 8702 8641 8703 8642 8703 8643 8703 8643 8704 8644 8704 8645 8704 8666 8705 8645 8705 8667 8705 8666 8706 8643 8706 8645 8706 8668 8707 8647 8707 8649 8707 8669 8708 8651 8708 8670 8708 8669 8709 8649 8709 8651 8709 8671 8710 8653 8710 8655 8710 8672 8265 8627 8265 8673 8265 8676 427 8674 427 8677 427 8677 427 8674 427 8675 427 8617 427 8678 427 8619 427 8619 427 8678 427 8679 427 8679 8711 8662 8711 8663 8711 8679 8712 8661 8712 8662 8712 8679 8713 8673 8713 8659 8713 8679 53 8677 53 8675 53 8626 53 8628 53 8673 53 8673 53 8628 53 8659 53 8665 53 8666 53 8619 53 8619 8714 8666 8714 8667 8714 8671 53 8623 53 8619 53 8623 53 8658 53 8625 53 8623 53 8621 53 8619 53 8619 53 8621 53 8618 53 8617 8715 8646 8715 8644 8715 8617 8716 8648 8716 8646 8716 8617 6 8650 6 8648 6 8617 6 8652 6 8650 6 8617 6 8654 6 8652 6 8624 6 8656 6 8622 6 8622 6 8656 6 8654 6 8636 6 8634 6 8678 6 8678 6 8634 6 8632 6 8630 8717 8678 8717 8632 8717 8630 6 8629 6 8672 6 8672 6 8674 6 8678 6 8680 8718 8681 8718 8682 8718 8681 8719 8684 8719 8686 8719 8688 8720 8684 8720 8689 8720 8684 8721 8690 8721 8691 8721 8691 8722 8690 8722 8692 8722 8695 8723 8682 8723 8694 8723 8684 8724 8691 8724 8685 8724 8685 8725 8691 8725 8696 8725 8700 8726 8690 8726 8701 8726 8701 8727 8690 8727 8688 8727 8702 8728 8681 8728 8687 8728 8686 8729 8702 8729 8687 8729 8705 8730 8706 8730 8707 8730 8702 8731 8708 8731 8681 8731 8702 8732 8704 8732 8707 8732 8704 8733 8703 8733 8707 8733 8708 8734 8709 8734 8710 8734 8710 8735 8709 8735 8711 8735 8711 8736 8713 8736 8712 8736 8712 8737 8713 8737 8714 8737 8705 8738 8707 8738 8715 8738 8713 8739 8715 8739 8714 8739 8716 8740 8694 8740 8682 8740 8716 8741 8682 8741 8683 8741 8696 8742 8691 8742 8717 8742 8716 8743 8717 8743 8694 8743 8694 8744 8717 8744 8692 8744 8718 8745 8719 8745 8720 8745 8719 8746 8722 8746 8723 8746 8723 8747 8722 8747 8724 8747 8711 8748 8721 8748 8719 8748 8713 8749 8711 8749 8719 8749 8727 8750 8728 8750 8729 8750 8730 8751 8731 8751 8732 8751 8074 8752 8734 8752 8735 8752 8074 8753 8733 8753 8734 8753 8733 8754 8076 8754 8736 8754 8730 8755 8733 8755 8736 8755 8732 8756 8737 8756 8738 8756 8735 8757 8739 8757 8740 8757 8735 8758 8734 8758 8739 8758 8738 8759 8741 8759 8742 8759 8742 8760 8745 8760 8746 8760 8744 8761 8747 8761 8748 8761 8744 8762 8743 8762 8747 8762 8745 8763 8749 8763 8746 8763 8751 8764 8750 8764 8712 8764 8755 8765 8756 8765 8753 8765 8755 8766 8757 8766 8756 8766 8761 8767 8763 8767 8762 8767 8762 8768 8763 8768 8764 8768 8765 8769 8762 8769 8764 8769 8767 8770 8762 8770 8766 8770 8762 8771 8769 8771 8770 8771 8759 8772 8770 8772 8756 8772 8751 8773 8712 8773 8752 8773 8055 8774 8771 8774 8772 8774 8751 8775 8747 8775 8746 8775 8750 8776 8751 8776 8746 8776 8772 8777 8753 8777 8774 8777 8052 8778 8774 8778 8050 8778 8052 8779 8772 8779 8774 8779 8774 8780 8770 8780 8050 8780 8774 8781 8756 8781 8770 8781 8774 8782 8753 8782 8756 8782 8773 8783 8748 8783 8747 8783 8076 8784 8776 8784 8736 8784 8736 8785 8776 8785 8777 8785 8777 8786 8778 8786 8736 8786 8778 8787 8729 8787 8728 8787 8776 8788 8779 8788 8777 8788 8772 8789 8752 8789 8753 8789 8743 8790 8742 8790 8746 8790 8731 8791 8780 8791 8741 8791 8731 8792 8741 8792 8737 8792 8715 8793 8754 8793 8714 8793 8761 8794 8760 8794 8781 8794 8697 8795 8782 8795 8689 8795 8697 8796 8698 8796 8783 8796 8786 8797 8783 8797 8785 8797 8792 8798 8791 8798 8790 8798 8792 8799 8794 8799 8791 8799 8698 8800 8699 8800 8784 8800 8798 8801 8797 8801 8799 8801 8800 8802 8801 8802 8798 8802 8800 8803 8802 8803 8801 8803 8800 8804 8803 8804 8802 8804 8805 8805 8802 8805 8804 8805 8801 8806 8805 8806 8807 8806 8807 8807 8808 8807 8801 8807 8801 8808 8785 8808 8798 8808 8797 8809 8699 8809 8809 8809 8810 8810 8811 8810 8812 8810 8811 8811 8813 8811 8812 8811 8700 8812 8809 8812 8699 8812 8817 8813 8700 8813 8818 8813 8818 8814 8700 8814 8819 8814 8688 8815 8820 8815 8701 8815 8821 8816 8822 8816 8823 8816 8822 8817 8818 8817 8823 8817 8824 8818 8814 8818 8821 8818 8700 8819 8701 8819 8819 8819 8828 8820 8829 8820 8825 8820 8829 8821 8830 8821 8831 8821 8832 8822 8833 8822 8834 8822 8838 8823 8785 8823 8808 8823 8841 8824 8842 8824 8843 8824 8841 8825 8833 8825 8842 8825 8844 8826 8845 8826 8846 8826 8851 8827 8853 8827 8852 8827 8852 8828 8853 8828 8854 8828 8846 8829 8845 8829 8848 8829 8850 8830 8855 8830 8851 8830 8857 8831 8858 8831 8856 8831 8857 8832 8844 8832 8858 8832 8864 8833 8865 8833 8866 8833 8867 8834 8866 8834 8868 8834 8870 8835 8868 8835 8866 8835 8870 8836 8861 8836 8871 8836 8873 8837 8865 8837 8864 8837 8873 8838 8864 8838 8804 8838 8875 8839 8721 8839 8709 8839 8721 8840 8875 8840 8720 8840 8689 8841 8706 8841 8705 8841 8705 8842 8726 8842 8688 8842 8877 8843 8878 8843 8725 8843 8881 8844 8878 8844 8880 8844 8878 8845 8876 8845 8725 8845 8816 8846 8824 8846 8882 8846 8816 8847 8814 8847 8824 8847 8883 8848 8882 8848 8824 8848 8785 8849 8784 8849 8798 8849 8873 8850 8863 8850 8865 8850 8858 8851 8859 8851 8860 8851 8856 8852 8851 8852 8855 8852 8888 8853 8849 8853 8885 8853 8889 8854 8888 8854 8890 8854 8891 8855 8890 8855 8888 8855 8889 8856 8848 8856 8849 8856 8867 8857 8806 8857 8864 8857 8838 8858 8892 8858 8837 8858 8832 8859 8842 8859 8833 8859 8843 8860 8842 8860 8896 8860 8898 8861 8843 8861 8896 8861 8899 8862 8902 8862 8900 8862 8903 8863 8901 8863 8900 8863 8902 8864 8904 8864 8905 8864 8906 8865 8902 8865 8905 8865 8906 8866 8900 8866 8902 8866 8907 8867 8908 8867 8909 8867 8909 8868 8908 8868 8910 8868 8909 8869 8910 8869 8911 8869 8683 8870 8681 8870 8914 8870 8910 8871 8915 8871 8696 8871 8916 8872 8696 8872 8915 8872 8915 8873 8917 8873 8916 8873 8917 8874 8918 8874 8685 8874 8703 8875 8918 8875 8919 8875 8707 8876 8919 8876 8920 8876 8754 8877 8715 8877 8921 8877 8922 8878 8707 8878 8920 8878 8918 8879 8907 8879 8924 8879 8926 8880 8681 8880 8708 8880 8927 8881 8708 8881 8928 8881 8929 8882 8927 8882 8928 8882 8929 8883 8931 8883 8927 8883 8932 8884 8933 8884 8934 8884 8708 8885 8710 8885 8928 8885 8930 8886 8750 8886 8749 8886 8780 8887 8938 8887 8741 8887 8780 8888 8727 8888 8729 8888 8934 8889 8933 8889 8935 8889 8936 8890 8939 8890 8940 8890 8941 8891 8942 8891 8939 8891 8943 8892 8941 8892 8944 8892 8952 8893 8949 8893 8951 8893 8949 8894 8953 8894 8954 8894 8944 8895 8945 8895 8954 8895 8955 8896 8956 8896 8957 8896 8955 8897 8958 8897 8956 8897 8955 8898 8959 8898 8958 8898 8955 8899 8960 8899 8959 8899 8962 8900 8959 8900 8961 8900 8962 8901 8963 8901 8959 8901 8966 8902 8967 8902 8960 8902 8966 8903 8968 8903 8967 8903 8966 8904 8969 8904 8968 8904 8966 8905 8970 8905 8969 8905 8969 8906 8970 8906 8971 8906 8972 8907 8971 8907 8973 8907 8974 8908 8972 8908 8973 8908 8973 8909 8979 8909 8980 8909 8980 8910 8981 8910 8973 8910 8974 8911 8973 8911 8983 8911 8961 8912 8984 8912 8983 8912 8984 8913 8961 8913 8967 8913 8967 8914 8961 8914 8960 8914 8965 8915 8986 8915 8985 8915 8965 8916 8987 8916 8986 8916 8988 8917 8946 8917 8957 8917 8988 8918 8957 8918 8956 8918 8951 8919 8950 8919 8989 8919 8913 8920 8940 8920 8912 8920 8932 8921 8994 8921 8995 8921 8754 8922 8996 8922 8757 8922 8763 8923 8998 8923 8764 8923 8761 8924 8781 8924 8997 8924 8757 8925 8996 8925 9000 8925 9000 8926 8996 8926 8923 8926 8703 8927 8685 8927 8918 8927 8963 8928 8958 8928 8959 8928 8986 8929 8988 8929 8985 8929 8994 8930 8992 8930 8993 8930 8952 8931 8951 8931 9001 8931 8942 8932 9001 8932 8939 8932 8949 8933 8954 8933 8945 8933 8993 8934 8995 8934 8994 8934 8708 8935 8927 8935 8926 8935 8681 8936 8925 8936 8914 8936 8983 8937 8984 8937 8974 8937 8972 8938 8969 8938 8971 8938 8950 8939 8911 8939 8989 8939 8951 8940 8989 8940 8912 8940 9002 8941 8940 8941 8939 8941 8720 8942 8875 8942 8718 8942 9004 8943 9007 8943 9006 8943 8724 8944 9008 8944 8877 8944 8875 8945 9009 8945 9003 8945 9003 8946 9009 8946 9010 8946 9011 8947 9003 8947 9010 8947 9010 8948 8903 8948 8900 8948 9014 8949 8906 8949 8905 8949 9015 8950 8905 8950 8904 8950 9016 8951 9015 8951 8904 8951 9016 8952 9017 8952 9015 8952 9016 8953 9018 8953 9017 8953 9018 8954 9019 8954 9020 8954 9020 8955 9019 8955 9021 8955 9022 8956 9020 8956 9021 8956 9022 8957 9023 8957 9020 8957 9010 8958 8900 8958 9013 8958 9012 8959 9013 8959 9024 8959 9013 8960 8906 8960 9014 8960 9024 8961 9014 8961 9025 8961 9014 8962 8905 8962 9015 8962 9025 8963 9015 8963 9017 8963 9026 8964 9022 8964 9021 8964 9019 8965 8898 8965 9021 8965 9008 8966 9028 8966 9029 8966 9029 8967 9030 8967 9031 8967 8880 8968 9029 8968 9031 8968 9033 8969 9034 8969 9032 8969 9033 8970 8827 8970 9034 8970 8827 8971 9033 8971 8828 8971 9034 8972 8827 8972 8826 8972 9036 8973 8830 8973 8828 8973 9034 8974 9038 8974 9032 8974 9008 8975 8724 8975 9006 8975 9006 8976 8724 8976 8722 8976 9039 8977 9040 8977 9041 8977 9040 8978 9045 8978 9046 8978 9040 8979 9044 8979 9041 8979 9041 8980 9047 8980 9042 8980 9044 8981 9048 8981 9041 8981 9047 8982 9049 8982 9042 8982 9052 8983 9053 8983 9054 8983 9055 8984 9053 8984 9056 8984 9055 8985 9054 8985 9053 8985 9057 8986 9058 8986 9059 8986 9056 8987 9058 8987 9055 8987 9059 8988 9058 8988 9056 8988 9057 8989 9061 8989 9058 8989 9057 8990 9062 8990 9061 8990 9060 8991 9058 8991 9061 8991 9064 8992 9057 8992 9059 8992 9052 8993 9066 8993 9053 8993 9073 8994 9071 8994 9072 8994 9073 8995 9039 8995 9071 8995 9073 8996 9074 8996 9065 8996 9065 8997 9074 8997 9045 8997 9045 8998 9074 8998 9046 8998 9039 8999 9075 8999 9071 8999 9039 9000 9076 9000 9075 9000 9080 9001 9079 9001 9081 9001 9081 9002 9079 9002 9078 9002 9077 9003 9083 9003 9078 9003 9078 9004 9083 9004 9084 9004 9085 9005 9077 9005 9042 9005 9076 9006 9039 9006 9077 9006 9080 9007 9069 9007 9079 9007 9069 9008 9080 9008 9086 9008 9079 9009 9071 9009 9075 9009 9090 9010 9091 9010 9092 9010 9093 9011 9090 9011 9092 9011 9095 9012 9056 9012 9066 9012 9059 9013 9056 9013 9063 9013 9094 9014 9056 9014 9095 9014 9096 9015 9092 9015 9097 9015 9097 9016 9092 9016 9091 9016 9101 9017 9100 9017 9099 9017 9090 9018 9093 9018 9103 9018 9104 9019 9093 9019 9094 9019 9095 9020 9106 9020 9107 9020 9095 9021 9108 9021 9106 9021 9104 9022 9094 9022 9105 9022 9105 9023 9095 9023 9107 9023 9098 9024 9091 9024 9099 9024 9114 9025 9113 9025 9115 9025 9114 9026 9119 9026 9118 9026 9119 9027 9116 9027 9117 9027 9117 9028 9123 9028 9122 9028 9098 9029 9124 9029 9125 9029 9125 9030 9123 9030 9098 9030 8933 9031 9118 9031 9117 9031 9126 9032 9127 9032 9128 9032 9127 9033 9129 9033 9128 9033 9130 9034 9133 9034 9132 9034 9129 9035 9136 9035 9134 9035 9138 9036 9139 9036 9140 9036 9141 9037 9138 9037 9140 9037 9142 9038 9143 9038 9144 9038 9145 9039 9146 9039 9147 9039 9136 9040 9137 9040 9143 9040 9153 9041 9136 9041 9143 9041 9154 9042 9157 9042 9155 9042 9158 9043 9154 9043 9159 9043 9142 9044 9144 9044 9155 9044 9161 9045 9162 9045 9163 9045 9162 9046 9164 9046 9165 9046 9165 9047 9163 9047 9162 9047 9148 9048 9149 9048 9164 9048 9168 9049 9165 9049 9166 9049 9166 9050 9165 9050 9169 9050 9164 9051 9149 9051 9170 9051 9169 9052 9151 9052 9171 9052 9152 9053 9151 9053 8467 9053 9172 9054 9150 9054 9173 9054 9174 9055 9175 9055 9176 9055 9177 9056 9176 9056 9178 9056 9179 9057 9178 9057 9180 9057 9179 9058 9181 9058 9177 9058 9175 9059 9174 9059 9182 9059 9183 9060 9182 9060 9184 9060 9191 9061 9190 9061 9192 9061 9204 9062 9203 9062 9205 9062 9205 9063 9203 9063 9206 9063 9203 9064 9209 9064 9210 9064 9209 9065 9211 9065 9212 9065 9210 9066 9213 9066 9214 9066 9215 9067 9216 9067 9217 9067 9218 9068 9217 9068 9219 9068 9218 9069 9219 9069 9208 9069 8462 9070 9212 9070 9220 9070 9221 9071 9220 9071 9222 9071 9227 9072 9226 9072 9228 9072 9232 9073 9233 9073 9223 9073 9232 9074 9226 9074 9227 9074 9234 9075 9221 9075 9222 9075 9230 9076 9238 9076 9239 9076 9230 9077 9239 9077 9240 9077 9241 9078 9238 9078 9242 9078 9244 9079 9247 9079 9245 9079 9129 9080 9135 9080 9242 9080 9248 9081 9168 9081 9167 9081 9150 9082 8469 9082 9151 9082 9213 9083 9234 9083 9250 9083 9194 9084 9252 9084 9249 9084 9194 9085 9193 9085 9192 9085 9253 9086 9192 9086 9254 9086 9255 9087 9256 9087 9257 9087 9261 9088 9260 9088 9262 9088 9261 9089 9263 9089 9264 9089 9257 9090 9259 9090 9255 9090 9266 9091 9267 9091 9268 9091 9269 9092 9270 9092 9271 9092 9272 9093 9273 9093 9274 9093 9269 9094 9272 9094 9275 9094 9143 9095 9275 9095 9153 9095 9276 9096 9142 9096 9270 9096 9276 9097 9270 9097 9269 9097 9270 9098 9158 9098 9271 9098 9277 9099 9278 9099 9279 9099 9278 9100 9277 9100 9280 9100 9279 9101 9278 9101 9281 9101 8851 9102 9245 9102 9140 9102 9246 9103 9245 9103 8856 9103 9283 9104 9285 9104 9231 9104 9227 9105 9286 9105 9233 9105 9233 9106 9287 9106 9288 9106 9290 9107 9291 9107 9289 9107 9236 9108 9250 9108 9222 9108 9286 9109 9287 9109 9233 9109 9290 9110 9294 9110 9292 9110 9293 9111 9295 9111 9214 9111 9216 9112 9295 9112 9296 9112 9174 9113 9298 9113 9182 9113 9299 9114 9300 9114 9297 9114 9299 9115 9301 9115 9300 9115 9303 9116 9304 9116 9305 9116 9256 9117 9254 9117 9190 9117 9304 9118 9308 9118 9305 9118 9262 9119 9260 9119 9309 9119 9256 9120 9255 9120 9254 9120 9255 9121 9312 9121 9253 9121 9194 9122 9253 9122 9252 9122 9194 9123 9192 9123 9253 9123 9313 9124 9312 9124 9314 9124 9313 9125 9251 9125 9312 9125 9312 9126 9251 9126 9253 9126 9314 9127 9312 9127 9310 9127 9141 9128 9134 9128 9136 9128 9240 9129 9239 9129 9246 9129 9283 9130 9240 9130 9284 9130 9240 9131 9246 9131 9284 9131 9238 9132 9230 9132 9229 9132 9153 9133 9275 9133 9281 9133 9279 9134 9274 9134 9277 9134 9269 9135 9273 9135 9272 9135 9264 9136 9265 9136 9316 9136 9182 9137 9298 9137 9300 9137 9307 9138 9317 9138 9301 9138 9302 9139 9309 9139 9308 9139 9160 9140 9147 9140 9148 9140 9259 9141 9305 9141 9260 9141 9195 9142 9172 9142 9173 9142 9195 9143 9191 9143 9193 9143 9190 9144 9188 9144 9256 9144 9256 9145 9188 9145 9303 9145 9257 9146 9256 9146 9303 9146 9304 9147 9303 9147 9306 9147 9301 9148 9308 9148 9304 9148 9195 9149 9173 9149 9196 9149 9187 9150 9188 9150 9189 9150 9317 9151 9300 9151 9301 9151 9298 9152 9297 9152 9300 9152 9202 9153 9204 9153 9189 9153 9191 9154 9202 9154 9189 9154 9189 9155 9204 9155 9187 9155 9185 9156 9204 9156 9205 9156 9183 9157 9205 9157 9318 9157 9178 9158 9176 9158 9200 9158 9203 9159 9204 9159 9202 9159 9186 9160 9187 9160 9185 9160 9204 9161 9185 9161 9187 9161 9182 9162 9300 9162 9317 9162 9319 9163 9185 9163 9205 9163 9183 9164 9319 9164 9205 9164 9175 9165 9182 9165 9183 9165 9210 9166 9214 9166 9203 9166 9181 9167 9297 9167 9174 9167 9177 9168 9174 9168 9176 9168 9275 9169 9143 9169 9276 9169 9170 9170 9169 9170 9164 9170 9158 9171 9270 9171 9157 9171 9261 9172 9258 9172 9260 9172 9264 9173 9316 9173 9261 9173 9311 9174 9312 9174 9255 9174 9252 9175 9251 9175 9249 9175 9266 9176 9156 9176 9164 9176 9250 9177 9236 9177 9291 9177 9290 9178 9292 9178 9291 9178 9227 9179 9233 9179 9232 9179 9291 9180 9236 9180 9235 9180 9214 9181 9213 9181 9293 9181 9217 9182 9216 9182 9296 9182 9218 9183 9199 9183 9198 9183 9200 9184 9176 9184 9199 9184 9318 9185 9206 9185 9218 9185 9203 9186 9214 9186 9206 9186 9316 9187 9265 9187 9311 9187 9208 9188 9199 9188 9218 9188 9292 9189 9250 9189 9291 9189 9286 9190 9228 9190 9229 9190 9242 9191 9128 9191 9129 9191 9321 9192 9322 9192 9323 9192 9323 9193 9324 9193 9325 9193 9242 9194 9326 9194 9322 9194 9327 9195 9329 9195 9328 9195 9242 9196 9238 9196 9326 9196 9327 9197 9238 9197 9226 9197 9237 9198 9331 9198 9225 9198 9226 9199 9331 9199 9327 9199 9329 9200 9327 9200 9331 9200 9334 9201 9222 9201 9220 9201 9334 9202 9335 9202 9222 9202 9222 9203 9337 9203 9331 9203 9222 9204 9331 9204 9237 9204 9338 9205 8463 9205 9152 9205 9341 9206 9342 9206 9151 9206 9151 9207 9343 9207 8467 9207 9341 9208 9151 9208 9339 9208 9146 9209 9144 9209 9346 9209 9344 9210 9146 9210 9346 9210 9147 9211 9146 9211 9344 9211 9348 9212 9349 9212 9137 9212 9351 9213 9352 9213 9353 9213 9354 9214 9355 9214 9356 9214 9360 9215 9359 9215 9362 9215 9364 9216 9362 9216 9353 9216 9359 9217 9353 9217 9362 9217 9354 9218 9351 9218 9353 9218 9361 9219 9354 9219 9353 9219 9365 9220 9366 9220 9367 9220 9368 9221 9369 9221 9370 9221 9371 9222 9372 9222 9373 9222 9374 9223 9377 9223 9376 9223 9378 9224 9371 9224 9373 9224 9379 9225 9375 9225 9377 9225 9360 9226 9381 9226 9361 9226 9360 9227 9382 9227 9381 9227 9360 9228 9363 9228 9382 9228 9362 9229 9384 9229 9383 9229 9383 9230 9382 9230 9363 9230 9388 9231 9389 9231 9387 9231 9389 9232 9388 9232 9390 9232 9389 9233 9390 9233 9391 9233 9395 9234 9391 9234 9390 9234 9395 9235 9397 9235 9398 9235 9354 9236 9403 9236 9404 9236 9356 9237 9355 9237 9405 9237 9406 9238 9405 9238 9407 9238 9410 9239 9396 9239 9411 9239 9411 9240 9412 9240 9410 9240 9412 9241 9413 9241 9414 9241 9415 9242 9414 9242 9416 9242 9415 9243 9417 9243 9412 9243 9419 9244 9420 9244 9414 9244 9420 9245 9421 9245 9422 9245 9423 9246 9422 9246 9424 9246 9422 9247 9421 9247 9425 9247 9427 9248 9422 9248 9425 9248 9428 9249 9429 9249 9430 9249 9431 9250 9430 9250 9432 9250 9432 9251 9433 9251 9431 9251 9436 9252 9435 9252 9437 9252 9438 9253 9280 9253 9436 9253 9280 9254 9439 9254 9440 9254 9437 9255 9441 9255 9442 9255 9444 9256 9443 9256 9445 9256 9446 9257 9445 9257 9440 9257 9439 9258 9446 9258 9440 9258 8890 9259 8891 9259 9447 9259 9449 9260 9450 9260 9447 9260 9449 9261 8887 9261 8886 9261 9445 9262 9450 9262 9282 9262 9436 9263 9428 9263 9431 9263 9435 9264 9436 9264 9431 9264 9420 9265 9416 9265 9414 9265 9451 9266 9452 9266 9418 9266 9451 9267 9455 9267 9454 9267 9454 9268 9455 9268 9456 9268 9456 9269 9455 9269 9457 9269 9456 9270 9457 9270 9458 9270 9459 9271 9456 9271 9458 9271 9460 9272 9459 9272 9458 9272 9460 9273 9458 9273 9461 9273 9458 9274 9462 9274 9461 9274 9461 9275 9463 9275 9370 9275 9370 9276 9463 9276 9366 9276 9463 9277 9464 9277 9366 9277 9465 9278 9464 9278 9466 9278 9465 9279 9466 9279 9467 9279 9370 9280 9369 9280 9460 9280 9469 9281 9378 9281 9470 9281 9471 9282 9473 9282 9470 9282 9470 9283 9473 9283 9474 9283 9472 9284 9378 9284 9475 9284 9472 9285 9475 9285 9476 9285 9374 9286 9477 9286 9373 9286 9374 9287 9478 9287 9477 9287 9374 9288 9479 9288 9478 9288 9480 9289 9376 9289 9481 9289 9373 9290 9476 9290 9475 9290 9395 9291 9398 9291 9484 9291 9485 9292 9400 9292 9401 9292 9399 9293 9403 9293 9402 9293 9404 9294 9405 9294 9355 9294 9406 9295 9356 9295 9405 9295 9417 9296 9410 9296 9412 9296 9487 9297 9488 9297 9489 9297 9490 9298 9489 9298 9482 9298 9491 9299 9482 9299 9492 9299 9493 9300 9492 9300 9494 9300 9495 9301 9494 9301 9496 9301 9497 9302 9496 9302 9498 9302 9499 9303 9498 9303 9500 9303 9367 9304 9502 9304 9501 9304 9375 9305 9380 9305 9500 9305 9505 9306 9406 9306 9488 9306 9500 9307 9380 9307 9501 9307 9506 9308 9499 9308 9501 9308 9506 9309 9497 9309 9499 9309 9506 9310 9507 9310 9497 9310 9467 9311 9508 9311 9465 9311 9503 9312 9367 9312 9510 9312 9510 9313 9367 9313 9465 9313 9512 9314 9513 9314 9493 9314 9492 9315 9493 9315 9491 9315 9516 9316 9517 9316 9518 9316 9517 9317 9519 9317 9518 9317 9518 9318 9519 9318 9486 9318 9351 9319 9521 9319 9352 9319 9522 9320 9385 9320 9523 9320 9525 9321 9523 9321 9524 9321 9385 9322 9364 9322 9523 9322 9352 9323 9523 9323 9364 9323 9523 9324 9352 9324 9521 9324 9499 9325 9500 9325 9501 9325 9516 9326 9518 9326 9505 9326 9518 9327 9486 9327 9504 9327 9489 9328 9490 9328 9487 9328 9498 9329 9499 9329 9497 9329 9031 9330 9038 9330 8881 9330 9038 9331 9527 9331 8881 9331 9529 9332 8820 9332 8878 9332 9529 9333 8823 9333 8820 9333 8824 9334 8821 9334 8883 9334 9038 9335 9034 9335 9530 9335 8904 9336 9532 9336 9533 9336 9531 9337 8904 9337 9533 9337 8843 9338 8898 9338 9534 9338 8898 9339 9019 9339 9534 9339 8794 9340 8792 9340 9535 9340 9535 9341 9533 9341 8902 9341 9368 9342 9536 9342 9378 9342 9366 9343 9365 9343 9370 9343 9370 9344 9365 9344 9536 9344 9536 9345 9379 9345 9537 9345 9537 9346 9371 9346 9536 9346 9377 9347 9374 9347 9537 9347 9374 9348 9372 9348 9537 9348 9537 9349 9372 9349 9371 9349 9538 9350 9541 9350 9539 9350 9538 9351 9542 9351 9541 9351 9542 9352 9543 9352 9541 9352 9546 9353 9548 9353 9549 9353 9548 9354 9551 9354 9550 9354 9555 9355 9553 9355 9554 9355 9558 9356 9553 9356 9557 9356 9558 9357 9560 9357 9553 9357 9544 9358 9561 9358 9545 9358 9563 9359 9562 9359 9564 9359 9562 9360 9561 9360 9566 9360 9568 9361 9540 9361 9539 9361 9569 9362 9568 9362 9539 9362 8975 9363 9569 9363 8977 9363 9574 9364 9571 9364 9573 9364 9571 9365 9559 9365 9557 9365 9579 9366 9580 9366 9578 9366 9579 9367 9581 9367 9580 9367 9588 9368 9587 9368 9590 9368 9585 9369 9591 9369 9590 9369 9594 9370 9586 9370 9595 9370 9596 9371 9594 9371 9595 9371 9596 9372 9588 9372 9594 9372 9600 9373 9599 9373 9601 9373 9602 9374 9601 9374 9603 9374 9604 9375 9602 9375 9603 9375 9582 9376 9606 9376 9593 9376 9609 9377 9611 9377 9610 9377 9583 9378 9612 9378 9584 9378 9593 9379 9606 9379 9614 9379 9614 9380 9606 9380 9607 9380 9607 9381 9610 9381 9615 9381 9575 9382 9611 9382 9609 9382 9575 9383 9573 9383 9611 9383 9616 9384 9617 9384 9618 9384 9620 9385 9619 9385 9611 9385 9620 9386 9611 9386 9621 9386 9621 9387 9611 9387 9572 9387 9580 9388 9621 9388 9572 9388 9580 9389 9622 9389 9621 9389 9580 9390 9623 9390 9622 9390 9618 9391 9624 9391 9625 9391 9586 9392 9624 9392 9595 9392 9624 9393 9626 9393 9595 9393 9626 9394 9622 9394 9623 9394 9620 9395 9617 9395 9619 9395 9625 9396 9616 9396 9618 9396 9562 9397 9563 9397 9545 9397 9545 9398 9563 9398 9547 9398 9564 9399 9628 9399 9565 9399 9590 9400 9629 9400 9630 9400 9633 9401 9635 9401 9634 9401 9546 9402 9543 9402 9545 9402 9544 9403 9543 9403 9542 9403 9539 9404 9541 9404 9638 9404 9638 9405 9570 9405 9539 9405 8982 9406 9638 9406 8979 9406 8981 9407 8980 9407 9639 9407 9640 9408 9639 9408 9638 9408 9541 9409 9640 9409 9638 9409 9591 9410 9592 9410 9588 9410 9585 9411 9586 9411 9592 9411 8878 9412 9641 9412 9529 9412 9527 9413 9528 9413 9641 9413 9530 9414 9528 9414 9038 9414 9641 9415 8823 9415 9529 9415 8821 9416 8823 9416 9642 9416 9642 9417 9530 9417 8883 9417 9643 9418 9633 9418 9644 9418 9633 9419 9632 9419 9644 9419 9632 9420 9631 9420 9646 9420 9589 9421 9648 9421 9587 9421 9644 9422 9632 9422 9646 9422 8843 9423 9534 9423 8793 9423 9534 9424 9016 9424 9531 9424 9534 9425 9535 9425 8792 9425 8980 9426 9649 9426 8852 9426 8852 9427 9649 9427 8886 9427 8886 9428 9649 9428 8979 9428 9547 9429 9563 9429 9650 9429 9548 9430 9547 9430 9651 9430 9552 9431 9652 9431 9653 9431 9552 9432 9551 9432 9652 9432 9650 9433 9563 9433 9565 9433 9427 9434 9652 9434 9548 9434 9430 9435 9548 9435 9651 9435 9427 9436 9548 9436 9429 9436 9430 9437 9650 9437 9432 9437 9654 9438 9540 9438 9655 9438 9654 9439 9542 9439 9538 9439 9544 9440 9657 9440 9561 9440 9657 9441 9566 9441 9561 9441 9446 9442 9542 9442 9654 9442 9438 9443 9542 9443 9439 9443 9446 9444 9655 9444 9444 9444 8977 9445 9658 9445 8976 9445 8982 9446 8978 9446 9659 9446 8982 9447 9660 9447 9570 9447 9570 9448 9661 9448 9569 9448 9570 9449 9660 9449 9661 9449 8977 9450 9569 9450 9661 9450 8887 9451 9660 9451 8982 9451 8885 9452 8887 9452 9659 9452 8885 9453 9658 9453 8888 9453 9662 9454 9663 9454 8984 9454 9664 9455 8972 9455 8974 9455 8969 9456 8972 9456 9664 9456 8968 9457 9662 9457 8967 9457 8850 9458 8974 9458 8855 9458 8855 9459 8974 9459 8984 9459 8857 9460 8984 9460 9663 9460 9663 9461 9662 9461 8857 9461 8857 9462 9662 9462 8844 9462 9667 9463 9666 9463 8963 9463 9669 9464 8964 9464 8985 9464 9667 9465 8963 9465 8964 9465 8866 9466 9668 9466 8956 9466 8870 9467 8956 9467 9666 9467 8861 9468 8870 9468 9666 9468 8866 9469 8956 9469 8870 9469 9240 9470 9670 9470 9675 9470 9230 9471 9240 9471 9675 9471 9230 9472 9675 9472 9673 9472 9283 9473 9231 9473 9673 9473 9676 9474 9677 9474 9678 9474 9676 9475 9672 9475 9677 9475 9672 9476 9676 9476 9679 9476 9680 9477 9676 9477 9681 9477 9321 9478 9680 9478 9681 9478 9680 9479 9321 9479 9323 9479 9689 9480 9690 9480 9691 9480 9692 9481 9693 9481 9694 9481 9683 9482 9682 9482 9706 9482 9706 9483 9682 9483 9707 9483 8961 9484 9678 9484 9677 9484 9678 9485 8961 9485 8983 9485 9709 9486 9710 9486 9711 9486 9714 9487 9713 9487 9712 9487 9722 9488 9721 9488 9728 9488 9729 9489 9728 9489 9730 9489 9731 9490 9730 9490 9732 9490 9732 9491 9734 9491 9733 9491 9733 9492 9734 9492 9735 9492 9737 9493 9711 9493 9710 9493 9707 9494 9640 9494 9737 9494 9718 9495 9739 9495 9740 9495 9740 9496 9719 9496 9718 9496 9744 9497 9745 9497 9727 9497 9741 9498 9746 9498 9747 9498 9750 9499 9749 9499 9751 9499 9750 9500 9751 9500 9752 9500 9753 9501 9752 9501 9754 9501 9757 9502 9756 9502 9758 9502 9759 9503 9757 9503 9760 9503 9762 9504 9763 9504 9764 9504 9762 9505 9764 9505 9765 9505 9766 9506 9767 9506 9768 9506 9745 9507 9743 9507 9770 9507 9770 9508 9743 9508 9771 9508 9721 9509 9771 9509 9728 9509 9771 9510 9730 9510 9728 9510 9735 9511 9734 9511 9772 9511 9715 9512 9773 9512 9714 9512 9713 9513 9717 9513 9131 9513 9684 9514 9705 9514 9688 9514 9767 9515 9765 9515 9768 9515 9778 9516 9764 9516 9779 9516 9696 9517 9695 9517 9780 9517 9778 9518 9696 9518 9780 9518 9775 9519 9691 9519 9781 9519 9781 9520 9691 9520 9692 9520 9695 9521 9692 9521 9694 9521 9695 9522 9776 9522 9780 9522 9775 9523 9701 9523 9782 9523 9785 9524 9784 9524 9786 9524 9723 9525 9788 9525 9789 9525 9736 9526 9543 9526 9549 9526 9720 9527 9794 9527 9795 9527 9795 9528 9796 9528 9797 9528 9722 9529 9798 9529 9788 9529 9722 9530 9729 9530 9798 9530 9797 9531 9731 9531 9733 9531 9795 9532 9733 9532 9735 9532 9792 9533 9799 9533 9790 9533 9723 9534 9722 9534 9788 9534 9800 9535 9802 9535 9803 9535 9800 9536 9805 9536 9806 9536 9747 9537 9807 9537 9809 9537 9747 9538 9746 9538 9807 9538 9810 9539 9801 9539 9811 9539 9746 9540 9811 9540 9812 9540 9746 9541 9812 9541 9807 9541 9806 9542 9808 9542 9807 9542 9819 9543 9818 9543 9820 9543 9821 9544 9820 9544 8012 9544 9822 9545 8016 9545 9823 9545 9825 9546 9826 9546 9827 9546 9808 9547 9825 9547 9827 9547 9822 9548 9819 9548 9821 9548 9822 9549 9823 9549 9819 9549 9828 9550 9829 9550 9817 9550 9828 9551 9830 9551 9829 9551 9818 9552 9829 9552 9820 9552 9829 9553 9830 9553 9831 9553 9820 9554 9829 9554 9831 9554 9833 9555 9832 9555 9834 9555 9835 9556 9834 9556 9836 9556 9837 9557 9836 9557 9838 9557 9839 9558 9838 9558 9840 9558 9841 9559 9840 9559 9842 9559 9843 9560 9752 9560 9844 9560 9841 9561 9844 9561 9845 9561 9837 9562 9845 9562 9846 9562 9833 9563 9846 9563 9847 9563 9823 9564 9848 9564 9824 9564 8019 9565 9849 9565 8018 9565 8019 9566 9851 9566 9850 9566 8019 9567 8020 9567 9851 9567 9853 9568 9852 9568 9854 9568 9838 9569 9853 9569 9854 9569 9838 9570 9836 9570 9853 9570 9851 9571 9852 9571 9853 9571 8020 9572 8021 9572 9852 9572 9856 9573 9857 9573 9858 9573 9859 9574 9860 9574 9861 9574 9854 9575 9852 9575 9855 9575 9861 9576 9864 9576 9758 9576 9758 9577 9756 9577 9861 9577 9864 9578 9861 9578 9860 9578 8024 9579 9863 9579 8023 9579 8024 9580 9866 9580 9863 9580 9864 9581 9868 9581 9758 9581 9864 9582 9865 9582 9868 9582 9866 9583 9867 9583 9868 9583 9760 9584 9870 9584 9779 9584 9761 9585 9779 9585 9763 9585 9793 9586 9799 9586 9792 9586 9720 9587 9719 9587 9799 9587 9677 9588 9674 9588 9787 9588 9671 9589 9677 9589 9672 9589 9685 9590 9675 9590 9679 9590 9862 9591 8023 9591 9863 9591 9804 9592 9805 9592 9800 9592 9748 9593 9766 9593 9741 9593 9832 9594 8016 9594 8018 9594 9860 9595 9856 9595 9858 9595 9842 9596 9859 9596 9843 9596 9843 9597 9859 9597 9754 9597 9750 9598 9762 9598 9767 9598 9871 9599 9749 9599 9750 9599 9776 9600 9764 9600 9780 9600 9775 9601 9782 9601 9689 9601 9689 9602 9782 9602 9687 9602 9688 9603 9689 9603 9687 9603 9752 9604 9753 9604 9750 9604 9750 9605 9753 9605 9762 9605 9855 9606 9857 9606 9856 9606 9840 9607 9855 9607 9856 9607 9855 9608 9862 9608 9857 9608 9844 9609 9752 9609 9751 9609 9749 9610 9747 9610 9872 9610 9872 9611 9873 9611 9874 9611 9779 9612 9764 9612 9763 9612 9778 9613 9780 9613 9764 9613 9783 9614 9684 9614 9687 9614 9702 9615 9687 9615 9703 9615 9734 9616 9875 9616 9772 9616 9730 9617 9731 9617 9729 9617 9769 9618 9742 9618 9741 9618 9827 9619 9876 9619 9808 9619 9827 9620 9826 9620 9847 9620 9847 9621 9848 9621 9833 9621 9835 9622 9846 9622 9833 9622 9741 9623 9745 9623 9746 9623 9819 9624 9824 9624 9826 9624 9816 9625 9819 9625 9826 9625 9720 9626 9772 9626 9715 9626 9874 9627 9844 9627 9872 9627 9874 9628 9845 9628 9844 9628 9839 9629 9840 9629 9841 9629 9844 9630 9749 9630 9872 9630 9838 9631 9839 9631 9837 9631 9837 9632 9839 9632 9845 9632 9835 9633 9836 9633 9837 9633 9846 9634 9835 9634 9837 9634 9832 9635 8018 9635 9849 9635 9695 9636 9697 9636 9698 9636 9787 9637 9784 9637 9785 9637 9786 9638 9783 9638 9702 9638 9727 9639 9724 9639 9744 9639 9814 9640 9817 9640 9815 9640 9825 9641 9815 9641 9816 9641 9825 9642 9806 9642 9805 9642 9801 9643 9800 9643 9811 9643 9810 9644 9744 9644 9801 9644 9812 9645 9811 9645 9800 9645 9821 9646 9819 9646 9820 9646 9819 9647 9816 9647 9818 9647 9746 9648 9810 9648 9811 9648 9745 9649 9744 9649 9810 9649 9760 9650 9755 9650 9759 9650 9759 9651 9755 9651 9756 9651 9877 9652 9241 9652 9681 9652 9878 9653 9879 9653 9682 9653 9681 9654 9878 9654 9682 9654 9879 9655 9707 9655 9682 9655 9880 9656 9678 9656 9708 9656 9877 9657 9676 9657 9880 9657 9879 9658 9878 9658 9244 9658 9243 9659 9878 9659 9241 9659 9239 9660 9241 9660 9877 9660 9683 9661 9135 9661 9713 9661 9882 9662 9883 9662 9710 9662 9882 9663 9710 9663 9713 9663 9883 9664 9737 9664 9710 9664 9738 9665 9737 9665 9884 9665 9884 9666 9706 9666 9738 9666 9141 9667 9883 9667 9882 9667 9882 9668 9134 9668 9141 9668 9882 9669 9135 9669 9134 9669 9718 9670 9885 9670 9739 9670 9885 9671 9886 9671 9739 9671 9886 9672 9736 9672 9739 9672 9139 9673 9887 9673 9711 9673 9139 9674 9711 9674 9736 9674 9709 9675 9888 9675 9712 9675 9711 9676 9887 9676 9709 9676 9886 9677 9885 9677 9278 9677 9885 9678 9153 9678 9278 9678 9136 9679 9153 9679 9718 9679 9718 9680 9712 9680 9136 9680 9136 9681 9712 9681 9888 9681 9888 9682 9887 9682 9138 9682 9281 9683 9740 9683 9791 9683 9274 9684 9791 9684 9790 9684 9281 9685 9791 9685 9279 9685 9279 9686 9791 9686 9274 9686 9667 9687 8964 9687 8862 9687 8865 9688 8964 9688 9669 9688 9669 9689 9668 9689 8865 9689 8865 9690 9668 9690 8866 9690 9447 9691 9660 9691 9449 9691 8891 9692 8888 9692 8977 9692 8891 9693 9661 9693 9447 9693 9437 9694 9656 9694 9438 9694 9442 9695 9540 9695 9566 9695 9437 9696 9566 9696 9657 9696 9736 9697 9278 9697 9139 9697 9719 9698 9740 9698 9281 9698 9671 9699 9240 9699 9283 9699 9879 9700 9244 9700 9708 9700 9883 9701 9140 9701 9737 9701 9737 9702 9245 9702 9884 9702 9650 9703 9565 9703 9432 9703 9434 9704 9565 9704 9628 9704 9425 9705 9628 9705 9653 9705 9425 9706 9652 9706 9427 9706 8847 9707 8968 9707 9665 9707 8847 9708 8845 9708 8968 9708 8844 9709 8968 9709 8845 9709 9702 9710 9704 9710 9889 9710 9890 9711 9889 9711 9704 9711 9699 9712 9891 9712 9700 9712 9895 9713 9893 9713 9896 9713 9893 9714 9897 9714 9896 9714 9896 9715 9897 9715 9898 9715 9901 9716 9900 9716 9902 9716 9905 9717 9757 9717 9758 9717 9907 9718 9906 9718 8037 9718 8038 9719 9904 9719 9902 9719 9906 9720 9907 9720 9905 9720 9897 9721 9908 9721 9757 9721 9868 9722 9867 9722 9906 9722 9903 9723 9901 9723 9902 9723 9909 9724 9896 9724 9899 9724 9786 9725 9702 9725 9889 9725 9905 9726 9907 9726 9902 9726 9900 9727 9905 9727 9902 9727 9894 9728 9891 9728 9699 9728 9894 9729 9699 9729 9893 9729 9895 9730 9894 9730 9893 9730 8038 9731 9902 9731 9907 9731 9910 9732 9700 9732 9891 9732 9910 9733 9911 9733 9700 9733 9911 9734 9912 9734 9700 9734 9700 9735 9912 9735 9701 9735 9912 9736 9913 9736 9701 9736 9913 9737 9914 9737 9703 9737 9914 9738 9915 9738 9703 9738 9915 9739 9916 9739 9704 9739 9891 9740 9890 9740 9910 9740 9918 9741 9919 9741 9920 9741 9723 9742 9789 9742 9923 9742 9924 9743 9797 9743 9796 9743 9921 9744 9926 9744 9919 9744 9933 9745 9929 9745 9932 9745 9933 9746 8008 9746 9830 9746 9933 9747 9934 9747 8007 9747 8006 9748 8007 9748 9934 9748 9920 9749 9803 9749 9937 9749 9919 9750 9918 9750 9921 9750 9920 9751 9919 9751 9928 9751 9931 9752 9930 9752 9928 9752 9929 9753 9814 9753 9804 9753 9934 9754 9933 9754 9932 9754 9938 9755 9939 9755 9924 9755 9924 9756 9939 9756 9797 9756 9939 9757 9940 9757 9797 9757 9797 9758 9940 9758 9917 9758 9917 9759 9941 9759 9798 9759 9798 9760 9941 9760 9942 9760 9789 9761 9938 9761 9924 9761 9944 9762 9945 9762 9946 9762 9946 9763 9947 9763 9944 9763 9944 9764 9947 9764 9948 9764 9949 9765 9947 9765 9950 9765 9949 9766 9950 9766 9951 9766 9952 9767 9949 9767 9951 9767 9952 9768 9953 9768 9949 9768 9954 9769 9951 9769 9950 9769 9954 9770 9955 9770 9951 9770 9951 9771 9955 9771 9956 9771 9952 9772 9959 9772 9960 9772 9963 9773 9964 9773 9961 9773 9961 9774 9964 9774 9965 9774 9965 9775 9967 9775 9968 9775 9967 9776 9966 9776 9969 9776 9967 9777 9970 9777 9971 9777 9089 9778 9968 9778 9088 9778 9586 9779 9974 9779 9625 9779 9616 9780 9975 9780 9619 9780 9619 9781 9975 9781 9611 9781 9607 9782 9976 9782 9614 9782 9614 9783 9976 9783 9593 9783 9978 9784 9975 9784 9977 9784 9593 9785 9976 9785 9980 9785 9979 9786 9976 9786 9615 9786 9980 9787 9976 9787 9979 9787 9974 9788 9593 9788 9980 9788 8993 9789 9983 9789 8995 9789 8990 9790 8913 9790 8991 9790 8995 9791 9983 9791 8931 9791 8931 9792 9984 9792 8926 9792 8926 9793 8925 9793 8931 9793 8913 9794 8914 9794 9982 9794 8931 9795 9985 9795 9984 9795 8925 9796 8926 9796 9984 9796 9981 9797 8914 9797 9987 9797 9986 9798 9981 9798 9987 9798 9984 9799 9988 9799 8925 9799 9983 9800 9985 9800 8931 9800 9987 9801 8914 9801 8925 9801 9009 9802 9992 9802 9991 9802 9993 9803 8795 9803 8901 9803 9993 9804 9994 9804 8791 9804 8791 9805 8795 9805 9993 9805 8839 9806 8789 9806 8791 9806 9994 9807 9995 9807 8839 9807 8796 9808 8783 9808 9996 9808 9998 9809 8796 9809 9997 9809 8875 9810 8782 9810 9992 9810 8782 9811 8875 9811 8689 9811 8796 9812 8782 9812 8697 9812 8782 9813 9999 9813 9992 9813 9992 9814 10000 9814 9989 9814 8901 9815 9991 9815 9993 9815 8796 9816 9998 9816 9999 9816 9995 9817 10001 9817 10003 9817 10003 9818 10001 9818 10004 9818 10005 9819 10004 9819 10006 9819 10007 9820 10005 9820 10006 9820 10000 9821 8480 9821 9989 9821 8480 9822 10009 9822 9989 9822 9990 9823 9989 9823 10009 9823 9990 9824 10009 9824 10001 9824 10010 9825 10014 9825 10013 9825 10017 9826 10019 9826 10018 9826 10021 9827 10022 9827 10023 9827 10023 9828 10024 9828 10025 9828 10020 9829 10022 9829 10027 9829 10027 9830 10022 9830 10021 9830 10021 9831 10023 9831 10025 9831 10024 9832 10026 9832 10016 9832 10028 9833 10020 9833 10027 9833 10028 9834 10029 9834 10020 9834 10020 9835 10029 9835 10018 9835 10012 9836 10030 9836 10010 9836 10015 9837 10031 9837 10032 9837 10016 9838 10015 9838 10032 9838 10014 9839 10031 9839 10015 9839 10024 9840 10033 9840 10025 9840 10025 9841 10033 9841 10021 9841 9994 9842 10002 9842 9995 9842 10003 9843 10005 9843 9996 9843 9997 9844 10005 9844 10007 9844 10007 9845 10008 9845 9997 9845 9997 9846 10008 9846 9998 9846 9998 9847 10008 9847 10000 9847 9999 9848 9998 9848 10000 9848 10016 9849 10026 9849 10013 9849 9489 9850 9407 9850 9404 9850 9404 9851 9403 9851 9399 9851 9398 9852 9483 9852 10013 9852 9483 9853 9473 9853 10011 9853 9471 9854 9472 9854 10011 9854 10011 9855 9472 9855 10017 9855 9478 9856 9482 9856 9489 9856 10017 9857 9489 9857 10019 9857 10034 9858 10022 9858 10020 9858 9407 9859 9405 9859 9404 9859 9404 9860 9399 9860 10022 9860 10026 9861 10023 9861 10013 9861 9472 9862 9478 9862 10017 9862 10035 9863 9987 9863 10036 9863 9987 9864 10035 9864 9986 9864 10035 9865 10037 9865 9986 9865 9986 9866 10037 9866 9985 9866 9988 9867 10036 9867 9987 9867 9980 9868 10040 9868 9974 9868 9974 9869 10040 9869 10041 9869 9974 9870 10041 9870 10042 9870 9974 9871 10042 9871 9977 9871 10042 9872 10043 9872 9977 9872 9977 9873 10043 9873 9978 9873 10043 9874 10044 9874 9978 9874 9979 9875 10044 9875 10040 9875 9980 9876 9979 9876 10040 9876 10009 9877 10039 9877 10038 9877 10001 9878 10038 9878 10037 9878 8480 9879 10006 9879 10036 9879 10009 9880 10038 9880 10001 9880 10001 9881 10037 9881 10004 9881 10004 9882 10035 9882 10006 9882 10032 9883 10044 9883 10043 9883 10028 9884 10043 9884 10042 9884 10030 9885 10041 9885 10040 9885 10031 9886 10030 9886 10040 9886 10033 9887 10043 9887 10028 9887 10029 9888 10041 9888 10030 9888 10045 9889 10046 9889 10047 9889 10047 9890 10048 9890 10049 9890 8556 9891 8557 9891 10050 9891 10050 9892 8557 9892 10051 9892 10051 9893 8557 9893 10052 9893 10052 9894 8557 9894 8614 9894 10053 9895 8614 9895 8615 9895 10056 9896 8554 9896 10055 9896 10056 9897 10057 9897 8554 9897 8553 9898 10057 9898 10058 9898 8547 9899 10058 9899 10054 9899 8615 9900 8547 9900 10054 9900 8553 9901 10058 9901 8547 9901 10046 9902 10045 9902 9044 9902 9044 9903 10045 9903 9051 9903 9050 9904 10045 9904 10047 9904 10047 9905 10060 9905 9393 9905 9067 9906 10061 9906 9055 9906 9055 9907 10061 9907 10062 9907 10063 9908 10062 9908 10064 9908 10066 9909 10059 9909 10046 9909 10066 9910 10067 9910 10059 9910 10048 9911 10067 9911 10055 9911 10055 9912 10067 9912 10068 9912 10057 9913 10069 9913 10070 9913 10057 9914 10070 9914 10071 9914 10074 9915 9419 9915 10058 9915 10054 9916 9419 9916 10075 9916 10076 9917 10075 9917 10077 9917 9411 9918 10052 9918 10078 9918 10052 9919 9396 9919 10080 9919 10051 9920 10080 9920 10081 9920 10060 9921 10081 9921 9394 9921 10060 9922 10050 9922 10081 9922 10060 9923 10049 9923 10050 9923 10056 9924 10069 9924 10057 9924 10053 9925 9413 9925 10078 9925 10052 9926 10080 9926 10051 9926 10066 9927 10068 9927 10067 9927 10077 9928 10075 9928 9419 9928 9421 9929 9419 9929 10082 9929 10082 9930 10073 9930 10071 9930 9419 9931 10074 9931 10073 9931 10068 9932 10071 9932 10069 9932 9396 9933 9390 9933 10080 9933 9413 9934 9411 9934 10079 9934 10068 9935 9046 9935 9074 9935 9084 9936 9083 9936 10085 9936 10086 9937 10087 9937 8553 9937 8554 9938 10087 9938 10088 9938 8547 9939 10093 9939 10086 9939 8556 9940 10090 9940 8557 9940 8615 9941 10093 9941 8547 9941 9084 9942 10085 9942 9081 9942 9081 9943 10085 9943 10094 9943 9081 9944 10094 9944 9623 9944 9623 9945 10095 9945 9081 9945 10096 9946 9080 9946 9081 9946 9086 9947 10096 9947 10097 9947 9080 9948 10096 9948 9086 9948 10091 9949 10098 9949 10092 9949 10102 9950 10088 9950 10087 9950 10089 9951 10102 9951 10103 9951 10089 9952 10103 9952 10090 9952 9556 9953 10104 9953 10100 9953 10105 9954 10106 9954 10107 9954 10101 9955 10100 9955 10104 9955 10105 9956 10108 9956 10099 9956 10105 9957 10098 9957 10103 9957 10106 9958 10105 9958 10103 9958 10107 9959 10108 9959 10105 9959 10100 9960 10099 9960 10109 9960 9556 9961 10100 9961 10109 9961 10102 9962 10106 9962 10103 9962 10102 9963 10101 9963 9579 9963 9577 9964 10108 9964 9576 9964 9577 9965 10109 9965 10108 9965 9576 9966 10107 9966 9578 9966 9577 9967 9555 9967 10109 9967 9048 9968 9050 9968 9047 9968 9394 9969 10080 9969 9390 9969 10078 9970 10052 9970 10053 9970 10072 9971 10058 9971 10057 9971 9067 9972 9068 9972 10061 9972 10065 9973 9068 9973 8894 9973 10065 9974 8894 9974 8893 9974 10065 9975 8893 9975 10110 9975 10111 9976 10112 9976 8892 9976 10111 9977 10113 9977 10112 9977 10116 9978 8807 9978 10117 9978 8805 9979 10116 9979 10117 9979 8805 9980 10118 9980 10116 9980 8805 9981 10119 9981 10118 9981 10124 9982 10123 9982 8806 9982 10127 9983 8869 9983 10128 9983 10128 9984 8869 9984 10129 9984 10129 9985 8869 9985 10130 9985 10131 9986 10130 9986 10132 9986 10133 9987 10132 9987 10134 9987 10064 9988 10134 9988 10063 9988 10064 9989 10133 9989 10134 9989 10115 9990 8807 9990 10116 9990 10120 9991 10121 9991 10122 9991 10129 9992 10130 9992 10131 9992 10131 9993 10132 9993 10133 9993 10134 9994 9111 9994 10063 9994 8892 9995 10135 9995 10110 9995 10136 9996 10110 9996 8893 9996 10132 9997 10137 9997 10134 9997 10132 9998 10130 9998 10137 9998 8869 9999 10126 9999 8806 9999 8806 10000 10123 10000 10121 10000 8806 10001 10121 10001 8805 10001 8869 10002 10137 10002 10130 10002 10111 10003 8808 10003 8807 10003 8544 10004 10139 10004 10138 10004 10140 10005 8544 10005 8543 10005 10142 10006 8535 10006 8533 10006 10140 10007 8543 10007 10146 10007 10146 10008 8543 10008 10141 10008 10142 10009 8533 10009 10148 10009 10149 10010 8612 10010 10144 10010 10144 10011 8611 10011 10145 10011 10141 10012 10150 10012 10151 10012 10153 10013 10154 10013 10144 10013 10155 10014 10148 10014 10143 10014 10148 10015 10155 10015 10142 10015 10146 10016 10151 10016 10140 10016 10149 10017 10154 10017 10143 10017 9646 10018 10157 10018 9644 10018 9646 10019 9631 10019 10158 10019 10158 10020 9631 10020 9629 10020 10159 10021 9629 10021 9647 10021 9589 10022 10161 10022 9648 10022 10164 10023 10163 10023 10165 10023 10166 10024 10165 10024 10167 10024 10166 10025 7972 10025 10164 10025 10169 10026 7976 10026 10170 10026 10171 10027 10170 10027 10172 10027 10173 10028 10175 10028 10174 10028 10158 10029 10176 10029 10157 10029 10158 10030 10174 10030 10176 10030 10158 10031 10159 10031 10174 10031 10177 10032 10157 10032 10176 10032 10178 10033 10176 10033 10179 10033 10178 10034 10180 10034 10177 10034 10177 10035 10180 10035 10181 10035 10181 10036 9643 10036 10177 10036 10171 10037 10160 10037 10169 10037 10160 10038 9587 10038 10161 10038 7976 10039 10169 10039 10168 10039 9597 10040 9598 10040 10163 10040 10183 10041 9600 10041 9645 10041 9605 10042 10185 10042 9604 10042 10163 10043 9600 10043 10183 10043 10165 10044 10183 10044 10187 10044 10187 10045 10184 10045 10189 10045 10188 10046 10187 10046 10189 10046 10184 10047 9602 10047 10185 10047 10189 10048 10185 10048 10190 10048 7969 10049 10190 10049 10191 10049 7969 10050 10189 10050 10190 10050 10186 10051 10192 10051 10185 10051 10190 10052 10192 10052 10193 10052 10194 10053 10190 10053 10193 10053 10191 10054 10194 10054 10195 10054 10164 10055 7974 10055 10168 10055 10162 10056 10164 10056 10168 10056 10184 10057 10185 10057 10189 10057 10183 10058 10184 10058 10187 10058 10159 10059 10160 10059 10171 10059 8894 10060 10197 10060 8895 10060 10197 10061 9068 10061 9060 10061 9111 10062 10137 10062 9095 10062 10118 10063 10120 10063 10116 10063 10135 10064 8535 10064 10110 10064 10135 10065 8533 10065 8535 10065 10135 10066 10112 10066 8533 10066 8533 10067 10112 10067 10113 10067 10124 10068 8545 10068 8611 10068 10124 10069 10125 10069 8545 10069 8545 10070 10125 10070 8544 10070 10064 10071 8535 10071 8543 10071 8533 10072 10115 10072 8612 10072 10199 10073 8943 10073 8944 10073 10201 10074 10203 10074 10204 10074 10202 10075 10201 10075 10204 10075 10206 10076 10209 10076 10208 10076 10208 10077 10209 10077 10210 10077 10209 10078 10206 10078 10211 10078 10206 10079 10200 10079 10211 10079 10202 10080 10204 10080 10212 10080 10215 10081 10216 10081 10217 10081 10216 10082 10215 10082 10218 10082 10223 10083 10222 10083 10224 10083 10224 10084 10226 10084 10227 10084 10229 10085 10228 10085 10230 10085 10232 10086 10228 10086 10216 10086 10228 10087 10233 10087 10230 10087 10222 10088 10219 10088 10225 10088 10219 10089 10216 10089 10225 10089 10235 10090 9168 10090 10236 10090 10236 10091 10237 10091 10238 10091 10239 10092 9161 10092 9163 10092 10234 10093 9251 10093 9313 10093 9248 10094 10234 10094 9168 10094 10248 10095 10247 10095 10243 10095 9263 10096 9314 10096 9310 10096 10249 10097 10250 10097 10251 10097 10246 10098 10252 10098 10244 10098 10246 10099 10247 10099 10252 10099 10252 10100 10247 10100 10253 10100 9161 10101 10254 10101 10253 10101 10240 10102 10256 10102 10255 10102 10256 10103 9165 10103 10257 10103 10260 10104 10235 10104 10234 10104 10241 10105 10262 10105 10261 10105 10254 10106 10239 10106 10255 10106 10252 10107 10250 10107 10244 10107 10244 10108 10250 10108 10249 10108 9313 10109 9314 10109 10241 10109 10241 10110 9314 10110 10262 10110 10262 10111 9314 10111 9263 10111 10264 10112 10263 10112 9219 10112 9208 10113 10263 10113 9207 10113 9200 10114 9207 10114 9180 10114 10270 10115 10271 10115 10269 10115 10265 10116 9294 10116 10266 10116 10270 10117 10269 10117 10268 10117 10264 10118 9219 10118 10272 10118 10272 10119 9219 10119 9296 10119 9295 10120 10278 10120 9296 10120 9296 10121 10278 10121 10272 10121 9292 10122 10273 10122 10276 10122 10273 10123 10276 10123 10274 10123 10275 10124 10274 10124 9292 10124 10280 10125 10264 10125 10272 10125 9180 10126 10263 10126 10280 10126 9957 10127 9960 10127 10281 10127 10281 10128 9960 10128 9959 10128 9958 10129 10285 10129 9959 10129 10289 10130 10288 10130 9955 10130 10290 10131 10289 10131 9955 10131 10291 10132 9954 10132 9950 10132 10293 10133 10294 10133 10295 10133 8837 10134 8895 10134 10294 10134 9458 10135 10297 10135 9462 10135 10298 10136 10297 10136 9458 10136 10299 10137 9392 10137 10300 10137 10304 10138 10294 10138 10197 10138 10303 10139 10296 10139 10304 10139 8834 10140 8837 10140 10303 10140 8837 10141 10293 10141 10303 10141 8832 10142 8835 10142 10197 10142 8832 10143 10197 10143 9062 10143 8832 10144 9062 10144 10305 10144 8842 10145 8832 10145 10305 10145 8815 10146 10306 10146 10308 10146 8812 10147 8797 10147 8810 10147 10309 10148 8812 10148 10310 10148 10313 10149 10314 10149 8829 10149 10313 10150 8829 10150 10315 10150 6611 10151 10316 10151 6610 10151 10320 10152 10318 10152 10321 10152 10321 10153 10322 10153 10323 10153 10323 10154 10322 10154 10324 10154 8815 10155 10326 10155 10307 10155 10326 10156 8815 10156 8816 10156 10313 10157 10327 10157 10314 10157 10328 10158 10313 10158 10315 10158 6610 10159 10317 10159 10329 10159 10320 10160 10321 10160 10323 10160 10314 10161 10331 10161 10312 10161 10312 10162 10331 10162 10326 10162 10331 10163 10325 10163 10326 10163 10313 10164 10328 10164 10327 10164 10311 10165 8816 10165 8882 10165 8829 10166 8882 10166 8825 10166 10315 10167 8831 10167 8884 10167 10317 10168 8884 10168 10329 10168 9221 10169 9212 10169 8462 10169 8380 10170 8670 10170 10332 10170 10303 10171 10293 10171 10296 10171 10306 10172 10307 10172 10334 10172 10334 10173 10307 10173 10335 10173 10307 10174 10310 10174 10335 10174 10306 10175 10334 10175 10308 10175 10308 10176 10334 10176 10336 10176 10336 10177 10337 10177 10308 10177 10308 10178 10337 10178 8813 10178 10308 10179 8813 10179 8815 10179 10294 10180 10304 10180 10295 10180 8380 10181 8461 10181 9213 10181 9150 10182 8660 10182 10338 10182 9150 10183 9171 10183 8469 10183 9166 10184 8360 10184 8660 10184 9171 10185 9150 10185 10338 10185 8660 10186 8360 10186 10338 10186 9171 10187 10338 10187 8469 10187 8466 10188 9169 10188 10338 10188 9388 10189 9386 10189 10342 10189 9388 10190 10342 10190 10340 10190 10301 10191 10300 10191 10341 10191 10343 10192 10300 10192 10302 10192 9388 10193 10343 10193 10302 10193 10299 10194 10301 10194 10340 10194 10340 10195 10342 10195 10299 10195 9392 10196 10342 10196 9386 10196 10344 10197 10345 10197 10346 10197 10348 10198 10344 10198 10346 10198 10347 10199 10348 10199 10298 10199 10298 10200 9457 10200 10347 10200 9462 10201 10297 10201 10349 10201 10348 10202 10346 10202 9462 10202 10297 10203 10298 10203 10349 10203 9796 10204 9794 10204 9612 10204 9583 10205 9923 10205 9612 10205 9583 10206 9925 10206 9923 10206 9925 10207 9583 10207 10351 10207 9921 10208 10351 10208 10352 10208 10354 10209 10353 10209 10355 10209 10358 10210 10359 10210 10360 10210 10361 10211 10360 10211 10362 10211 9922 10212 10351 10212 9921 10212 9931 10213 10364 10213 10358 10213 10365 10214 10366 10214 10367 10214 9931 10215 10367 10215 9935 10215 10364 10216 9931 10216 9928 10216 10364 10217 10357 10217 10359 10217 10367 10218 10358 10218 10363 10218 10358 10219 10360 10219 10363 10219 7995 10220 9936 10220 10369 10220 10364 10221 9928 10221 10356 10221 9928 10222 9927 10222 10356 10222 10357 10223 10364 10223 10356 10223 9575 10224 9609 10224 9794 10224 9609 10225 9612 10225 9794 10225 9585 10226 9590 10226 10352 10226 10352 10227 9590 10227 10353 10227 9590 10228 9630 10228 10353 10228 10353 10229 9634 10229 9635 10229 10355 10230 10353 10230 9635 10230 10357 10231 9635 10231 9637 10231 10357 10232 9637 10232 10359 10232 10359 10233 10370 10233 10360 10233 10359 10234 9637 10234 10370 10234 10344 10235 10373 10235 10345 10235 10374 10236 10345 10236 10375 10236 10374 10237 10375 10237 10376 10237 10373 10238 10375 10238 10345 10238 10382 10239 10378 10239 10376 10239 10384 10240 10385 10240 10380 10240 10245 10241 10387 10241 10383 10241 10245 10242 10385 10242 10387 10242 10388 10243 10389 10243 10386 10243 10390 10244 10388 10244 10391 10244 4752 10245 10393 10245 10392 10245 10393 10246 10394 10246 10395 10246 10393 10247 10396 10247 10392 10247 10384 10248 10396 10248 10387 10248 10387 10249 10396 10249 10379 10249 10378 10250 10377 10250 10374 10250 10374 10251 9462 10251 10345 10251 10384 10252 10392 10252 10396 10252 9461 10253 9462 10253 10374 10253 9463 10254 10377 10254 9464 10254 9463 10255 10374 10255 10377 10255 9466 10256 10396 10256 9468 10256 10393 10257 9468 10257 10396 10257 9638 10258 9449 10258 8886 10258 9638 10259 8886 10259 8979 10259 9638 10260 9639 10260 9450 10260 9450 10261 9639 10261 8854 10261 10397 10262 10398 10262 9725 10262 10399 10263 9918 10263 10400 10263 10399 10264 10401 10264 9918 10264 10400 10265 9918 10265 10402 10265 10403 10266 9920 10266 9937 10266 10404 10267 9937 10267 9813 10267 10405 10268 10402 10268 9920 10268 9920 10269 10402 10269 9918 10269 9725 10270 10407 10270 9724 10270 9744 10271 10409 10271 9801 10271 9801 10272 10410 10272 10411 10272 10415 10273 10416 10273 10399 10273 10400 10274 10402 10274 10413 10274 10417 10275 10403 10275 10418 10275 10422 10276 10421 10276 10411 10276 10410 10277 10409 10277 10425 10277 10426 10278 10409 10278 10408 10278 10406 10279 10429 10279 10407 10279 10406 10280 10430 10280 10429 10280 10430 10281 10406 10281 10398 10281 10397 10282 10431 10282 10398 10282 10397 10283 10432 10283 10431 10283 10397 10284 10401 10284 10432 10284 10432 10285 10401 10285 10399 10285 10416 10286 10433 10286 10432 10286 10432 10287 10433 10287 10431 10287 10431 10288 10433 10288 10434 10288 10430 10289 10434 10289 10429 10289 10407 10290 10429 10290 10428 10290 10431 10291 10434 10291 10430 10291 10428 10292 10435 10292 10427 10292 10427 10293 10435 10293 10436 10293 10425 10294 10437 10294 10424 10294 10425 10295 10426 10295 10437 10295 10427 10296 10436 10296 10426 10296 10421 10297 10419 10297 10420 10297 10420 10298 10419 10298 10404 10298 10413 10299 10405 10299 10414 10299 10385 10300 10245 10300 10249 10300 10249 10301 10245 10301 10244 10301 10391 10302 10388 10302 10251 10302 10233 10303 10232 10303 10438 10303 10439 10304 9340 10304 9345 10304 10441 10305 9343 10305 9342 10305 9339 10306 10443 10306 9341 10306 9339 10307 10444 10307 10443 10307 10444 10308 9339 10308 9340 10308 10442 10309 9341 10309 10443 10309 10389 10310 9936 10310 10366 10310 10389 10311 10366 10311 10386 10311 8463 10312 10445 10312 9333 10312 8463 10313 10446 10313 10445 10313 10447 10314 10446 10314 8463 10314 8463 10315 9338 10315 10447 10315 10451 10316 10450 10316 10452 10316 10440 10317 10454 10317 10455 10317 10453 6 9333 6 10452 6 10445 10318 10451 10318 9333 10318 9333 10319 10451 10319 10452 10319 9335 10320 10457 10320 9337 10320 9335 10321 9334 10321 10458 10321 10460 10322 9336 10322 9211 10322 10453 10323 10460 10323 9211 10323 10458 10324 9220 10324 10459 10324 10461 10325 10446 10325 10462 10325 10463 10326 10447 10326 10449 10326 10465 10327 10466 10327 10467 10327 10470 10328 10265 10328 10471 10328 10267 10329 10472 10329 10471 10329 10267 10330 10268 10330 10472 10330 10472 10331 10268 10331 10269 10331 10473 10332 10269 10332 10271 10332 10473 10333 10271 10333 10474 10333 10470 10334 10475 10334 9294 10334 10275 10335 10475 10335 10274 10335 10274 10336 10475 10336 10476 10336 10273 10337 10476 10337 10276 10337 10476 10338 10477 10338 10276 10338 10478 10339 10479 10339 9295 10339 9295 10340 10479 10340 10278 10340 10278 10341 10479 10341 10480 10341 10482 10342 10484 10342 9893 10342 9893 10343 10481 10343 10483 10343 10486 10344 10487 10344 9897 10344 8909 10345 9889 10345 8907 10345 8907 10346 9892 10346 8924 10346 8924 10347 9892 10347 9894 10347 10490 10348 9896 10348 9909 10348 10492 10349 9899 10349 10493 10349 10494 10350 9901 10350 10495 10350 9901 10351 10494 10351 9900 10351 8924 10352 9894 10352 10488 10352 9895 10353 9896 10353 10489 10353 10493 10354 9899 10354 9900 10354 9901 10355 9903 10355 10495 10355 10495 10356 9903 10356 10497 10356 10497 10357 9903 10357 9904 10357 10499 10358 9904 10358 8033 10358 10497 10359 9904 10359 10499 10359 10494 10360 10502 10360 9900 10360 9900 10361 10502 10361 10493 10361 10502 10362 10492 10362 10493 10362 10490 10363 10489 10363 9896 10363 9618 10364 9617 10364 10503 10364 9624 10365 10504 10365 9626 10365 9617 10366 10506 10366 10503 10366 10504 10367 10509 10367 10508 10367 9622 10368 10508 10368 10509 10368 10510 10369 10505 10369 10511 10369 10510 10370 10506 10370 9620 10370 9620 10371 10506 10371 9617 10371 9622 10372 9626 10372 10508 10372 10509 10373 10511 10373 9622 10373 10507 10374 10521 10374 10522 10374 10523 10375 10510 10375 10514 10375 10520 10376 10507 10376 10522 10376 10516 10377 8558 10377 10514 10377 10516 10378 10515 10378 8558 10378 8562 10379 10515 10379 10517 10379 8562 10380 10517 10380 10518 10380 8566 10381 10513 10381 10512 10381 8563 10382 10520 10382 8565 10382 8565 10383 10521 10383 8566 10383 10525 10384 8558 10384 10526 10384 10528 10385 8562 10385 8563 10385 10528 10386 8563 10386 10529 10386 10530 10387 8565 10387 8566 10387 10531 10388 10530 10388 8566 10388 10529 10389 8565 10389 10530 10389 8566 10390 8560 10390 10532 10390 10537 10391 9070 10391 9069 10391 10537 10392 9069 10392 9972 10392 9972 10393 9086 10393 9088 10393 10083 10394 9074 10394 9969 10394 10529 10395 10538 10395 10528 10395 10529 10396 10539 10396 10538 10396 10539 10397 10529 10397 9381 10397 10540 10398 10530 10398 10531 10398 10541 10399 10530 10399 10540 10399 9485 10400 10531 10400 10532 10400 9485 10401 10532 10401 10542 10401 10532 10402 10533 10402 10542 10402 10542 10403 10533 10403 10543 10403 9391 10404 10543 10404 10524 10404 9391 10405 10525 10405 10544 10405 9389 10406 10527 10406 10545 10406 10538 10407 9387 10407 10528 10407 10545 10408 10528 10408 9387 10408 10541 10409 10540 10409 9402 10409 9485 10410 9401 10410 10540 10410 10538 10411 10539 10411 9382 10411 9485 10412 10542 10412 9395 10412 9391 10413 10544 10413 9389 10413 10550 10414 8588 10414 8589 10414 10551 10415 8590 10415 10552 10415 10549 10416 8588 10416 10553 10416 10553 10417 8588 10417 10550 10417 10550 10418 8589 10418 10551 10418 10554 10419 8595 10419 8596 10419 10554 10420 8596 10420 10555 10420 10552 10421 8595 10421 10556 10421 10556 10422 8595 10422 10554 10422 10555 10423 8596 10423 8597 10423 10558 10424 10550 10424 10551 10424 10553 10425 10550 10425 10559 10425 10549 10426 9159 10426 9154 10426 10560 10427 10547 10427 9154 10427 10555 10428 9156 10428 9268 10428 10562 10429 10554 10429 9268 10429 10552 10430 10372 10430 10551 10430 10548 10431 9154 10431 10547 10431 10546 10432 10561 10432 10555 10432 10557 10433 10556 10433 9267 10433 10350 10434 10559 10434 10372 10434 10372 10435 10557 10435 9267 10435 9582 10436 10564 10436 9606 10436 9613 10437 10565 10437 10563 10437 9606 10438 10567 10438 9608 10438 10567 10439 10570 10439 10569 10439 10573 10440 10568 10440 10570 10440 10577 10441 10566 10441 10579 10441 10563 10442 10565 10442 10580 10442 10582 10443 8586 10443 8585 10443 8586 10444 10574 10444 10575 10444 8593 10445 10578 10445 10577 10445 8593 10446 10577 10446 10579 10446 8594 10447 10579 10447 10580 10447 8594 10448 10580 10448 10572 10448 8587 10449 10572 10449 10571 10449 8587 10450 10571 10450 10581 10450 8585 10451 10581 10451 10573 10451 8586 10452 10575 10452 8592 10452 8593 10453 10579 10453 8594 10453 10438 10454 10218 10454 10583 10454 10584 10455 10215 10455 10217 10455 10217 10456 10221 10456 10585 10456 10585 10457 10221 10457 10220 10457 10583 10458 10215 10458 10584 10458 8585 10459 8586 10459 10586 10459 10586 10460 8586 10460 10588 10460 10589 10461 8586 10461 8592 10461 10590 10462 8592 10462 8593 10462 10590 10463 8593 10463 10591 10463 10591 10464 8593 10464 8594 10464 10592 10465 8594 10465 8587 10465 10593 10466 8587 10466 10594 10466 10593 10467 10592 10467 8587 10467 10591 10468 8594 10468 10592 10468 10595 10469 8587 10469 8585 10469 9267 10470 9162 10470 10373 10470 9267 10471 10373 10471 10372 10471 10382 10472 10243 10472 10245 10472 9161 10473 10243 10473 10373 10473 10591 10474 10596 10474 10590 10474 10596 10475 10591 10475 9459 10475 9459 10476 10591 10476 10592 10476 9459 10477 10592 10477 9456 10477 9454 10478 10597 10478 10594 10478 9454 10479 10595 10479 10598 10479 10598 10480 10595 10480 10587 10480 10599 10481 10598 10481 10587 10481 10587 10482 10586 10482 10599 10482 10599 10483 10586 10483 9474 10483 9474 10484 10588 10484 9470 10484 9470 10485 10589 10485 9469 10485 9469 10486 10589 10486 10590 10486 10596 10487 10600 10487 10590 10487 10599 10488 9453 10488 10598 10488 9469 10489 10600 10489 9460 10489 9454 10490 10598 10490 10599 10490 10250 10491 10412 10491 10251 10491 10250 10492 10416 10492 10412 10492 10250 10493 10252 10493 10416 10493 10434 6 10253 6 10255 6 10256 10494 10257 10494 10429 10494 10436 10495 10258 10495 10259 10495 10437 10496 10436 10496 10259 10496 10435 10497 10258 10497 10436 10497 10438 10498 10262 10498 9263 10498 10230 10499 9263 10499 8010 10499 10422 6 10261 6 10583 6 10419 10500 10584 10500 10585 10500 10414 10501 10223 10501 10251 10501 10412 10502 10414 10502 10251 10502 10583 10503 10262 10503 10438 10503 10438 10504 9263 10504 10230 10504 8012 10505 9263 10505 9261 10505 8016 10506 9262 10506 9309 10506 8019 10507 9302 10507 9299 10507 8020 10508 9299 10508 9297 10508 8024 10509 9179 10509 9180 10509 10601 10510 9180 10510 10280 10510 10212 10511 10280 10511 10602 10511 10211 10512 10603 10512 10604 10512 10209 10513 10604 10513 10605 10513 10473 6 10606 6 10607 6 10472 6 10607 6 10608 6 10471 6 10608 6 10609 6 10470 6 10609 6 10475 6 8012 10514 9261 10514 8017 10514 8016 10515 9309 10515 8018 10515 8024 10516 9180 10516 8035 10516 8035 10517 10601 10517 8037 10517 10610 10518 8037 10518 10601 10518 8033 10519 10611 10519 10210 10519 10324 10520 10210 10520 10209 10520 10474 10521 10324 10521 10209 10521 10612 10522 10280 10522 10480 10522 10615 6 10478 6 10477 6 10616 10523 10477 10523 10476 10523 10617 10524 10476 10524 10609 10524 10612 10525 10480 10525 10613 10525 10613 10526 10479 10526 10614 10526 10473 10527 10474 10527 10606 10527 10499 10528 8033 10528 10210 10528 8010 10529 8008 10529 10230 10529 10229 10530 8007 10530 8006 10530 10227 10531 8006 10531 7995 10531 10224 10532 10369 10532 10391 10532 10229 10533 8006 10533 10227 10533 10369 10534 10390 10534 10391 10534 10212 6 10602 6 10213 6 10211 6 10604 6 10209 6 10212 10535 10214 10535 10280 10535 10414 10536 10417 10536 10223 10536 10618 10537 9697 10537 9696 10537 10619 10538 9696 10538 9778 10538 9779 10539 10623 10539 10620 10539 10620 10540 10619 10540 9778 10540 10604 10541 10625 10541 10605 10541 9908 10542 10487 10542 10626 10542 10612 10543 10613 10543 10621 10543 10621 10544 10613 10544 10623 10544 10623 10545 10613 10545 10628 10545 10620 10546 10628 10546 10614 10546 10629 10547 10614 10547 10615 10547 10630 10548 10615 10548 10616 10548 10631 10549 10616 10549 10617 10549 9697 10550 10618 10550 10617 10550 10631 10551 10618 10551 9696 10551 9696 10552 10630 10552 10631 10552 10629 10553 10619 10553 10620 10553 10614 10554 10629 10554 10620 10554 10481 10555 10632 10555 10633 10555 10481 10556 9697 10556 10632 10556 10483 10557 10634 10557 10482 10557 10483 10558 10633 10558 10634 10558 10483 10559 10481 10559 10633 10559 10608 10560 10607 10560 10634 10560 10484 10561 10607 10561 10635 10561 10485 10562 10635 10562 10636 10562 10607 10563 10606 10563 10635 10563 10636 10564 10605 10564 10625 10564 10617 10565 10618 10565 10631 10565 10605 10566 10636 10566 10635 10566 10270 10567 10328 10567 10271 10567 10271 10568 10328 10568 10320 10568 10323 10569 10474 10569 10271 10569 10204 10570 10637 10570 10214 10570 10214 10571 10637 10571 10601 10571 10321 10572 10497 10572 10322 10572 10322 10573 10497 10573 10499 10573 10639 10574 9743 10574 9742 10574 9771 10575 9743 10575 10641 10575 10642 53 10643 53 10644 53 10642 10576 10646 10576 10645 10576 10648 10577 9742 10577 10463 10577 10644 10578 10464 10578 10461 10578 10461 10579 9769 10579 10644 10579 10461 10580 10462 10580 9769 10580 10462 10581 10463 10581 9742 10581 10648 10582 10463 10582 10649 10582 10649 10583 10463 10583 10643 10583 10643 10584 10464 10584 10644 10584 8936 10585 8940 10585 10651 10585 8932 10586 10652 10586 8994 10586 10652 10587 10650 10587 8994 10587 8940 10588 8990 10588 10651 10588 10653 10589 10654 10589 10650 10589 8935 10590 10657 10590 8934 10590 8934 10591 10657 10591 10658 10591 10651 10592 10650 10592 10656 10592 10657 10593 10662 10593 10663 10593 10657 10594 10655 10594 10662 10594 10653 10595 10669 10595 10668 10595 10667 10596 8530 10596 10666 10596 8537 10597 10659 10597 10660 10597 8536 10598 10661 10598 10663 10598 8534 10599 10663 10599 10662 10599 8530 10600 10665 10600 10666 10600 8541 10601 10669 10601 8540 10601 8540 10602 10659 10602 8537 10602 8537 10603 10670 10603 8536 10603 8536 10604 10663 10604 8534 10604 8531 10605 10665 10605 8530 10605 8530 10606 8541 10606 10671 10606 10671 10607 8541 10607 10673 10607 10673 10608 8541 10608 10674 10608 10674 10609 8541 10609 8540 10609 10678 10610 8536 10610 8534 10610 10679 10611 8531 10611 10680 10611 10680 10612 8531 10612 10681 10612 10681 10613 8531 10613 8530 10613 10672 10614 10681 10614 8530 10614 9062 10615 10197 10615 9061 10615 10197 10616 9060 10616 9061 10616 8998 10617 10494 10617 8999 10617 8999 10618 10494 10618 10500 10618 10502 10619 10491 10619 10492 10619 8997 10620 9000 10620 10491 10620 9000 10621 8923 10621 10490 10621 10488 10622 8921 10622 8920 10622 9122 10623 10682 10623 8939 10623 8941 10624 8939 10624 10682 10624 10684 10625 10685 10625 10686 10625 9125 10626 10684 10626 9123 10626 9125 10627 10688 10627 10685 10627 10685 10628 10688 10628 10686 10628 10687 10629 10686 10629 10682 10629 9122 10630 10687 10630 10682 10630 10687 10631 9122 10631 9123 10631 10689 10632 10688 10632 9124 10632 9124 10633 9098 10633 9100 10633 10674 10634 8840 10634 10692 10634 10674 10635 10692 10635 8790 10635 10673 10636 10693 10636 10671 10636 10693 10637 10672 10637 10671 10637 10695 10638 10680 10638 10681 10638 10695 10639 8836 10639 10680 10639 10696 10640 10678 10640 10679 10640 10678 10641 10697 10641 10698 10641 10691 10642 10677 10642 10698 10642 10674 10643 8790 10643 10673 10643 10672 10644 10694 10644 10681 10644 10678 10645 10698 10645 10677 10645 10266 10646 10265 10646 10325 10646 10309 10647 9287 10647 9286 10647 10327 10648 10328 10648 10270 10648 10637 10649 10203 10649 10201 10649 10690 10650 10201 10650 10700 10650 10207 10651 10208 10651 10701 10651 10611 10652 10699 10652 10701 10652 10701 10653 10699 10653 10700 10653 10201 10654 10205 10654 10700 10654 10610 10655 10601 10655 10690 10655 10690 10656 10700 10656 10699 10656 10610 10657 10690 10657 10699 10657 8833 10658 10691 10658 10698 10658 10693 10659 8790 10659 8788 10659 8787 10660 10694 10660 10693 10660 8789 10661 8839 10661 8790 10661 10698 10662 10697 10662 8834 10662 10694 10663 8786 10663 8836 10663 8840 10664 10675 10664 10691 10664 8787 10665 8786 10665 10694 10665 10692 10666 8840 10666 8790 10666 10702 10667 8818 10667 8822 10667 10703 10668 10704 10668 8814 10668 8822 10669 8814 10669 10704 10669 8814 10670 8811 10670 10705 10670 8814 10671 10705 10671 10706 10671 10706 10672 10703 10672 8814 10672 10713 10673 10709 10673 10714 10673 10713 10674 10714 10674 10715 10674 10714 10675 10718 10675 10716 10675 10716 10676 10718 10676 10719 10676 10711 10677 10721 10677 10710 10677 10718 10678 10717 10678 10723 10678 10286 10679 10720 10679 10283 10679 10724 10680 10708 10680 10717 10680 10726 10681 10536 10681 10537 10681 9956 10682 10711 10682 9951 10682 10716 10683 9952 10683 10715 10683 9951 10684 10712 10684 10713 10684 10712 10685 9951 10685 10711 10685 10711 10686 10288 10686 10721 10686 10719 10687 10285 10687 10716 10687 10285 10688 9958 10688 10716 10688 10284 10689 10718 10689 10729 10689 10729 10690 10723 10690 10730 10690 10289 10691 10292 10691 10710 10691 10728 10692 9580 10692 9581 10692 10728 10693 9581 10693 10731 10693 9962 10694 10730 10694 10291 10694 9961 10695 10724 10695 10729 10695 10732 10696 10281 10696 10724 10696 10729 10697 10281 10697 10282 10697 10724 10698 10717 10698 10732 10698 10714 10699 9957 10699 10732 10699 10709 10700 10708 10700 9961 10700 10709 10701 9961 10701 9949 10701 10683 10702 10733 10702 10734 10702 10683 10703 9944 10703 9948 10703 10737 10704 10736 10704 9087 10704 10683 10705 10689 10705 9944 10705 9101 10706 10689 10706 9100 10706 9101 10707 9944 10707 10689 10707 10689 10708 9124 10708 9100 10708 9109 10709 9107 10709 10738 10709 10534 10710 10728 10710 9971 10710 10732 10711 9957 10711 10281 10711 10683 10712 8955 10712 8941 10712 8955 10713 8944 10713 8941 10713 10734 10714 8970 10714 8955 10714 8970 10715 8960 10715 8955 10715 8970 10716 10734 10716 10735 10716 10733 10717 10743 10717 9562 10717 9581 10718 9554 10718 10743 10718 10743 10719 9564 10719 9562 10719 10733 10720 10731 10720 10743 10720 10731 10721 9581 10721 10743 10721 10737 10722 10097 10722 10725 10722 10727 10723 10726 10723 10096 10723 10725 10724 10097 10724 10726 10724 10726 10725 10097 10725 10096 10725 10731 10726 10736 10726 10741 10726 10741 10727 10736 10727 10740 10727 10745 10728 10689 10728 10683 10728 10688 10729 10739 10729 9110 10729 10682 10730 9105 10730 9109 10730 10739 10731 10745 10731 10738 10731 10739 10732 10744 10732 10745 10732 9104 10733 9105 10733 10686 10733 10686 10734 9105 10734 10682 10734 10746 10735 10747 10735 10748 10735 10746 10736 10748 10736 10750 10736 10746 10737 10750 10737 9448 10737 10071 10738 10084 10738 10082 10738 10082 10739 10747 10739 10746 10739 9421 10740 10082 10740 9433 10740 9433 10741 10746 10741 9448 10741 9443 10742 9441 10742 9448 10742 9441 10743 9435 10743 9433 10743 10749 10744 9947 10744 9946 10744 10747 10745 9947 10745 10749 10745 9945 10746 9106 10746 9108 10746 9963 10747 10747 10747 9964 10747 10084 10748 10083 10748 9966 10748 9947 10749 9963 10749 9962 10749 10748 10750 10749 10750 10751 10750 10750 10751 8872 10751 8846 10751 10748 10752 10751 10752 8872 10752 8869 10753 10751 10753 9108 10753 8846 10754 8889 10754 9448 10754 8889 10755 8890 10755 9448 10755 10097 10756 9087 10756 9086 10756 9057 10757 9113 10757 9121 10757 9057 10758 9064 10758 9113 10758 10094 10759 9083 10759 9082 10759 9637 10760 10156 10760 10371 10760 10156 10761 10362 10761 10371 10761 9560 10762 10753 10762 9549 10762 9549 10763 10753 10763 9792 10763 9558 10764 9559 10764 10753 10764 9792 10765 10754 10765 9793 10765 9792 10766 10753 10766 10754 10766 9559 10767 9574 10767 10754 10767 9793 10768 10754 10768 9794 10768 9574 10769 9575 10769 10754 10769 10754 10770 9575 10770 9794 10770 9599 10771 9603 10771 9601 10771 10755 10772 10094 10772 10752 10772 9596 10773 9595 10773 10757 10773 9595 10774 9623 10774 10757 10774 10757 10775 9623 10775 10094 10775 10757 10776 10755 10776 9603 10776 9599 10777 10757 10777 9603 10777 8929 10778 10758 10778 8933 10778 10758 10779 8929 10779 8938 10779 8938 10780 8729 10780 9120 10780 8938 10781 8780 10781 8729 10781 8933 10782 10758 10782 9118 10782 10760 10783 9787 10783 9785 10783 10760 10784 9786 10784 8911 10784 8950 10785 10760 10785 8911 10785 10760 10786 8948 10786 10759 10786 8981 10787 9640 10787 8973 10787 9707 10788 8983 10788 8973 10788 10759 10789 9677 10789 9787 10789 8965 10790 9677 10790 10759 10790 8947 10791 8987 10791 10759 10791 8961 10792 8965 10792 8962 10792 10762 10793 8917 10793 8915 10793 10762 10794 10761 10794 8917 10794 8915 10795 8910 10795 10763 10795 8729 10796 10765 10796 10766 10796 9120 10797 8729 10797 10766 10797 9121 10798 9120 10798 10766 10798 10768 10799 9026 10799 10767 10799 10767 10800 9026 10800 10305 10800 9057 10801 10767 10801 10305 10801 9284 10802 8856 10802 8863 10802 9284 10803 8863 10803 8873 10803 9284 10804 8873 10804 10769 10804 8874 10805 8803 10805 10769 10805 8803 10806 8800 10806 10769 10806 10769 10807 8800 10807 10770 10807 9229 10808 10770 10808 9286 10808 9440 10809 9282 10809 9280 10809 9428 10810 9436 10810 9280 10810 8853 10811 8851 10811 9282 10811 9139 10812 9280 10812 9282 10812 10772 10813 9269 10813 9271 10813 10772 10814 9271 10814 9451 10814 10772 10815 9415 10815 10771 10815 9273 10816 10772 10816 10771 10816 9423 10817 9277 10817 10771 10817 9416 10818 10771 10818 9415 10818 9467 10819 9468 10819 9509 10819 10395 10820 9509 10820 9468 10820 9386 10821 10773 10821 9047 10821 9522 10822 9384 10822 9385 10822 9383 10823 9386 10823 9382 10823 9522 10824 10773 10824 9384 10824 9383 10825 9384 10825 10773 10825 10774 10826 10775 10826 9042 10826 9042 10827 10773 10827 10774 10827 9522 10828 10774 10828 10773 10828 10774 10829 9522 10829 10776 10829 10756 10830 10755 10830 10775 10830 10778 10831 10779 10831 10756 10831 10775 10832 10755 10832 9085 10832 9085 10833 10755 10833 10752 10833 10182 10834 10362 10834 10156 10834 10361 10835 10395 10835 10394 10835 10361 10836 10362 10836 10395 10836 10362 10837 10182 10837 10395 10837 10395 10838 10182 10838 9509 10838 8999 10839 10500 10839 8764 10839 10330 10840 10329 10840 10501 10840 10780 10841 10782 10841 10781 10841 10783 10842 10784 10842 10763 10842 8915 10843 10763 10843 10784 10843 10762 10844 10785 10844 10761 10844 8918 10845 10786 10845 10780 10845 10783 10846 10763 10846 8910 10846 8952 10847 10198 10847 10155 10847 8942 10848 10788 10848 10150 10848 10155 10849 10154 10849 8952 10849 8952 10850 10154 10850 8953 10850 10199 10851 10153 10851 8943 10851 9027 10852 10765 10852 10764 10852 10768 10853 10766 10853 10765 10853 9022 10854 8778 10854 8777 10854 9022 10855 9027 10855 8778 10855 8778 10856 9027 10856 10764 10856 9022 10857 8777 10857 9023 10857 8779 10858 8776 10858 9023 10858 9020 6 8776 6 8076 6 9025 6 8735 6 8740 6 9024 10859 8740 10859 8744 10859 9012 10860 8744 10860 8748 10860 9005 10861 8773 10861 9004 10861 9005 10862 9011 10862 8773 10862 9020 6 8076 6 9018 6 9018 6 8074 6 9017 6 9024 6 8744 6 9012 6 9012 6 8748 6 9011 6 8773 10863 8055 10863 9004 10863 9004 10864 8055 10864 9007 10864 9028 10865 8053 10865 8052 10865 9032 10866 8050 10866 8775 10866 9035 6 8767 6 8768 6 9030 10867 8050 10867 9032 10867 9032 10868 8775 10868 9033 10868 9036 10869 9035 10869 8766 10869 8765 10870 9036 10870 8766 10870 10789 10871 10790 10871 10703 10871 8822 10872 10790 10872 10791 10872 10705 10873 10792 10873 10706 10873 10705 10874 10793 10874 10792 10874 8810 10875 10794 10875 8811 10875 8810 10876 10795 10876 10794 10876 10796 10877 8810 10877 10707 10877 10707 10878 10797 10878 10796 10878 8817 10879 8818 10879 10798 10879 10798 10880 8818 10880 10799 10880 10791 10881 10799 10881 8818 10881 10789 10882 10706 10882 10792 10882 10797 10883 8809 10883 10798 10883 9271 10884 9455 10884 9451 10884 10776 10885 10777 10885 10778 10885 10778 6 10777 6 10779 6 10193 10886 10777 10886 9526 10886 9526 10887 10777 10887 9522 10887 10182 10888 9508 10888 9509 10888 10195 10889 9524 10889 10191 10889 9521 10890 10191 10890 9524 10890 10166 10891 9519 10891 9517 10891 7974 10892 9514 10892 9515 10892 9512 10893 9507 10893 10170 10893 10172 10894 9507 10894 9506 10894 10173 10895 9506 10895 9501 10895 10180 10896 9503 10896 9511 10896 7974 10897 9515 10897 7976 10897 10172 6 9506 6 10173 6 10173 10898 9501 10898 10175 10898 10193 10899 9526 10899 9525 10899 10192 10900 10186 10900 10756 10900 10193 10901 10192 10901 10779 10901 4752 10902 10363 10902 10394 10902 10394 10903 10363 10903 10361 10903 10367 10904 10381 10904 10365 10904 10381 10905 10366 10905 10365 10905 10390 10906 10369 10906 9936 10906 9350 10907 10800 10907 10801 10907 9129 10908 9716 10908 9714 10908 10802 10909 9716 10909 10803 10909 10803 10910 9716 10910 9127 10910 9717 10911 10806 10911 10805 10911 9717 10912 9126 10912 9128 10912 10807 10913 10808 10913 10809 10913 9242 10914 9774 10914 9320 10914 9680 10915 9323 10915 10810 10915 9680 10916 9705 10916 9686 10916 9765 10917 10811 10917 10644 10917 10812 10918 9777 10918 9694 10918 10812 10919 9694 10919 10466 10919 9768 10920 9765 10920 10644 10920 9771 10921 10641 10921 9730 10921 9875 10922 9734 10922 10813 10922 9730 10923 10814 10923 9732 10923 10497 10924 10319 10924 10498 10924 10496 10925 10495 10925 6610 10925 10330 10926 10496 10926 6610 10926 10816 10927 10818 10927 10783 10927 10783 10928 10818 10928 10784 10928 10784 10929 10818 10929 10819 10929 10785 10930 10819 10930 10820 10930 10785 10931 10820 10931 10821 10931 10784 10932 10819 10932 10785 10932 10823 10933 10824 10933 10786 10933 10826 10934 10827 10934 10782 10934 10783 10935 10827 10935 10817 10935 10828 10936 9289 10936 9288 10936 9288 10937 9287 10937 10830 10937 10829 10938 10831 10938 9290 10938 10560 10939 9156 10939 10561 10939 10562 10940 9267 10940 10556 10940 10560 10941 9154 10941 9156 10941 9347 10942 9350 10942 10833 10942 9348 10943 10834 10943 10444 10943 10834 10944 9348 10944 10835 10944 9347 10945 10835 10945 9348 10945 9347 10946 10833 10946 10835 10946 9322 10947 9326 10947 10836 10947 10836 10948 9326 10948 10837 10948 10837 10949 9326 10949 9330 10949 9330 10950 9328 10950 10838 10950 9329 10951 10456 10951 10457 10951 9128 10952 9320 10952 9130 10952 9130 10953 9320 10953 10808 10953 9126 10954 10805 10954 9127 10954 9127 10955 10805 10955 10803 10955 10806 10956 10802 10956 10840 10956 10809 10957 9132 10957 10840 10957 10804 10958 10801 10958 10802 10958 9350 10959 10801 10959 10833 10959 10833 10960 10801 10960 10835 10960 10801 10961 10804 10961 10440 10961 10440 10962 10804 10962 10843 10962 10843 10963 9133 10963 10453 10963 10837 10964 10807 10964 9324 10964 10805 10965 10804 10965 10803 10965 10807 10966 9133 10966 9130 10966 10807 10967 9130 10967 10808 10967 10802 10968 10806 10968 9716 10968 9716 10969 10806 10969 9717 10969 10840 10970 9133 10970 10843 10970 9132 10971 9133 10971 10840 10971 9131 10972 9132 10972 9774 10972 9774 10973 9132 10973 10809 10973 10841 10974 9324 10974 10807 10974 10807 10975 10809 10975 10841 10975 10810 10976 9325 10976 10842 10976 10465 10977 10468 10977 10844 10977 10844 10978 10468 10978 10469 10978 9680 10979 10844 10979 10469 10979 9680 10980 10845 10980 10844 10980 10842 10981 9680 10981 10810 10981 10642 10982 10811 10982 10846 10982 10812 10983 10845 10983 9777 10983 10812 10984 10844 10984 10845 10984 10844 10985 10466 10985 10465 10985 9742 10986 10647 10986 10847 10986 10640 10987 10847 10987 10848 10987 10639 10988 10640 10988 10848 10988 9742 10989 10847 10989 10640 10989 10814 10990 10850 10990 10813 10990 10813 10991 10849 10991 10815 10991 10819 10992 8521 10992 8519 10992 10820 10993 8519 10993 8518 10993 10822 10994 8518 10994 8516 10994 10824 10995 8516 10995 8515 10995 10820 10996 8518 10996 10821 10996 10821 10997 8518 10997 10822 10997 10822 10998 8516 10998 10823 10998 10823 10999 8516 10999 10824 10999 10825 11000 8515 11000 10826 11000 10826 11001 8507 11001 10827 11001 10309 11002 10851 11002 9287 11002 10852 11003 9290 11003 10853 11003 9290 11004 10831 11004 10853 11004 10852 11005 10309 11005 9290 11005 10856 11006 10857 11006 10830 11006 9288 11007 10858 11007 10859 11007 10859 11008 10828 11008 9288 11008 9289 11009 10860 11009 10829 11009 10861 11010 10862 11010 10831 11010 10852 11011 10853 11011 10854 11011 10443 11012 10835 11012 10442 11012 10801 11013 10441 11013 10835 11013 10648 11014 10448 11014 10646 11014 10646 11015 10454 11015 10645 11015 10645 11016 10454 11016 10643 11016 10457 11017 10458 11017 10838 11017 10459 11018 10460 11018 10837 11018 10460 11019 10453 11019 10837 11019 8518 11020 10789 11020 8516 11020 10790 11021 8518 11021 8519 11021 10799 11022 8521 11022 10798 11022 10792 11023 10793 11023 8515 11023 8507 11024 10793 11024 10794 11024 10795 11025 8507 11025 10794 11025 8509 11026 10797 11026 8521 11026 10792 11027 8516 11027 10789 11027 10863 11028 9942 11028 9941 11028 10875 11029 10876 11029 9911 11029 9916 11030 9915 11030 10879 11030 10879 11031 9915 11031 10880 11031 10881 11032 9915 11032 9914 11032 10878 11033 10881 11033 9914 11033 10880 11034 9915 11034 10881 11034 9913 11035 9912 11035 10877 11035 9916 11036 10875 11036 9910 11036 10847 11037 10800 11037 10839 11037 10848 11038 10847 11038 10839 11038 10841 11039 10845 11039 10842 11039 8595 11040 10868 11040 10867 11040 8597 11041 10863 11041 10864 11041 8589 11042 10870 11042 8590 11042 8590 11043 10868 11043 8595 11043 8596 11044 10863 11044 8597 11044 10877 11045 8502 11045 8503 11045 8504 11046 10876 11046 10875 11046 8506 11047 10879 11047 10880 11047 8508 11048 10880 11048 10881 11048 8607 11049 10881 11049 10878 11049 8503 11050 8607 11050 10878 11050 8502 11051 10876 11051 8504 11051 8504 11052 10875 11052 8505 11052 8508 11053 10881 11053 8511 11053 10855 11054 8506 11054 10856 11054 10858 11055 10857 11055 8508 11055 8502 11056 10861 11056 10832 11056 10860 11057 8502 11057 10832 11057 10860 11058 8503 11058 8502 11058 10860 11059 10828 11059 8503 11059 8511 11060 10828 11060 10859 11060 10857 11061 10856 11061 8506 11061 10884 11062 10883 11062 10885 11062 10883 11063 10886 11063 10885 11063 10885 11064 10886 11064 10887 11064 10887 11065 10886 11065 10888 11065 10882 11066 10892 11066 10893 11066 10891 11067 10892 11067 10889 11067 10885 11068 10887 11068 10892 11068 10896 11069 10895 11069 10897 11069 10894 11070 10898 11070 10895 11070 10895 11071 10898 11071 10899 11071 10900 11072 10897 11072 10901 11072 10898 11073 10900 11073 10899 11073 10899 11074 10901 11074 10895 11074 10895 11075 10901 11075 10897 11075 10902 11076 10903 11076 10904 11076 10904 11077 10903 11077 10905 11077 10905 11078 10906 11078 10907 11078 10902 11079 10904 11079 10908 11079 10908 11080 10904 11080 10909 11080 10910 11081 10911 11081 10912 11081 10910 11082 10915 11082 10911 11082 10916 11083 10912 11083 10917 11083 10917 11084 10912 11084 10913 11084 10915 11085 10916 11085 10917 11085 10913 53 10915 53 10917 53 10920 11086 10919 11086 10921 11086 10920 11087 10921 11087 10924 11087 10923 11088 10924 11088 10925 11088 10923 53 10925 53 10919 53 10929 11089 10931 11089 10932 11089 10931 11090 10933 11090 10932 11090 10932 11091 10933 11091 10934 11091 10926 11092 10928 11092 10935 11092 10935 11093 10928 11093 10934 11093 10936 11094 10937 11094 10938 11094 10940 11095 10936 11095 10941 11095 10941 11096 10942 11096 10940 11096 10943 11097 10940 11097 10942 11097 10942 11098 10944 11098 10943 11098 10946 11099 10947 11099 10948 11099 10945 11100 10947 11100 10946 11100 10948 11101 10949 11101 10946 11101 10938 11102 10939 11102 10949 11102 10946 11103 10940 11103 10945 11103 10946 11104 10950 11104 10937 11104 10937 11105 10950 11105 10939 11105 10951 11106 10952 11106 10953 11106 10958 11107 10957 11107 10959 11107 10960 11108 10959 11108 10961 11108 10953 11109 10952 11109 10963 11109 10953 11110 10963 11110 10965 11110 10967 11111 10968 11111 10966 11111 10966 11112 10968 11112 10969 11112 10969 11113 10968 11113 10970 11113 10971 11114 10970 11114 10972 11114 10973 11115 10972 11115 10974 11115 10975 11116 10973 11116 10974 11116 10975 11117 10976 11117 10973 11117 10976 11118 10977 11118 10978 11118 10979 11119 10982 11119 10978 11119 10978 11120 10982 11120 10976 11120 10974 11121 10972 11121 10983 11121 10983 11122 10968 11122 10984 11122 10962 11123 10988 11123 10987 11123 10961 11124 10988 11124 10962 11124 10955 11125 10958 11125 10954 11125 10989 11126 10990 11126 10991 11126 10992 11127 10990 11127 10993 11127 10995 11128 10996 11128 10997 11128 11001 11129 11002 11129 10998 11129 11001 11130 11003 11130 11002 11130 11002 11131 11003 11131 11004 11131 11005 11132 11002 11132 11004 11132 10998 11133 11006 11133 10999 11133 11010 11134 11011 11134 11012 11134 11013 11135 11014 11135 11015 11135 11013 11136 11016 11136 11014 11136 11017 11137 11018 11137 11016 11137 11019 11138 11018 11138 11017 11138 11019 11139 11020 11139 11018 11139 11019 11140 11021 11140 11020 11140 11019 11141 11022 11141 11021 11141 10957 11142 11023 11142 11021 11142 11023 11143 10956 11143 11024 11143 11025 11144 11026 11144 11020 11144 11021 11145 11025 11145 11020 11145 11021 11146 11023 11146 11025 11146 11022 11147 10961 11147 10959 11147 10988 11148 10986 11148 10987 11148 10978 11149 11027 11149 10980 11149 11031 11150 11030 11150 11032 11150 11033 11151 11032 11151 11034 11151 11033 11152 11034 11152 11035 11152 11032 11153 11033 11153 11031 11153 10980 11154 11028 11154 11029 11154 10981 11155 11029 11155 11036 11155 10981 11156 10980 11156 11029 11156 11036 11157 11029 11157 11031 11157 11037 11158 8165 11158 11038 11158 11038 11159 8165 11159 8132 11159 10982 11160 11039 11160 10976 11160 10976 11161 11039 11161 10973 11161 10966 11162 10965 11162 10964 11162 11024 11163 11012 11163 11026 11163 11026 11164 11012 11164 11041 11164 11014 11165 11043 11165 11015 11165 11015 11166 11043 11166 11003 11166 11010 11167 11007 11167 11009 11167 11008 11168 11007 11168 11043 11168 11043 11169 11007 11169 11004 11169 11003 11170 11043 11170 11004 11170 11024 11171 11025 11171 11023 11171 11016 11172 11042 11172 11014 11172 11016 11173 11041 11173 11042 11173 11016 11174 11018 11174 11041 11174 10997 11175 10999 11175 10995 11175 11020 11176 11026 11176 11018 11176 11044 11177 10893 11177 11045 11177 10888 11178 11046 11178 10890 11178 10888 11179 10886 11179 11047 11179 11049 11180 11050 11180 11046 11180 11050 11181 11049 11181 11051 11181 11050 11182 11045 11182 10890 11182 11046 11183 11050 11183 10890 11183 11047 11184 11052 11184 11048 11184 11048 11185 11052 11185 11053 11185 11052 11186 11054 11186 10930 11186 11052 11187 10930 11187 11053 11187 11057 11188 10944 11188 10942 11188 11057 11189 10947 11189 10944 11189 10947 11190 11057 11190 10948 11190 10949 11191 11058 11191 11059 11191 11061 11192 11065 11192 11066 11192 11066 11193 11065 11193 11067 11193 11069 11194 11071 11194 11070 11194 11057 11195 11072 11195 11058 11195 11058 11196 11072 11196 11059 11196 11059 11197 11072 11197 11073 11197 11075 11198 11078 11198 11077 11198 11080 11199 11083 11199 11082 11199 11084 11200 11083 11200 11085 11200 11086 11201 11085 11201 11087 11201 11092 11202 11093 11202 11090 11202 11092 11203 11094 11203 11093 11203 11096 11204 11095 11204 11094 11204 11096 11205 11098 11205 11095 11205 11100 11206 11101 11206 11102 11206 11102 11207 11101 11207 11103 11207 11105 11208 11104 11208 11106 11208 11108 11209 11109 11209 11110 11209 11108 11210 11110 11210 11089 11210 11119 11211 11121 11211 11120 11211 11119 11212 11122 11212 11121 11212 11121 11213 11122 11213 11123 11213 11124 11214 11123 11214 11125 11214 11126 11215 11127 11215 11128 11215 11126 11216 11128 11216 11129 11216 11124 11217 11125 11217 11130 11217 11133 11218 11134 11218 11123 11218 11138 11219 11135 11219 11137 11219 11138 11220 11140 11220 11135 11220 11133 11221 11135 11221 11134 11221 11133 11222 11136 11222 11135 11222 11136 11223 11133 11223 11144 11223 11146 11224 11137 11224 11145 11224 11146 11225 11147 11225 11137 11225 11147 11226 11148 11226 11149 11226 11152 11227 11151 11227 11153 11227 11157 11228 11156 11228 11158 11228 11157 11229 11158 11229 11159 11229 11139 11230 11147 11230 11150 11230 11150 11231 11151 11231 11152 11231 11155 11232 11156 11232 11157 11232 11134 11233 11140 11233 11125 11233 11123 11234 11134 11234 11125 11234 11140 11235 11126 11235 11125 11235 11162 11236 11128 11236 11127 11236 11162 11237 11163 11237 11128 11237 11162 11238 11064 11238 11163 11238 11163 11239 11064 11239 11164 11239 11163 11240 11164 11240 11165 11240 11060 11241 11166 11241 11167 11241 11164 11242 11064 11242 11063 11242 11167 11243 11165 11243 11164 11243 11063 11244 11167 11244 11164 11244 11168 11245 11169 11245 11065 11245 11175 11246 11176 11246 11177 11246 11178 11247 11175 11247 11179 11247 11180 11248 11178 11248 11179 11248 11179 11249 11181 11249 11180 11249 11090 11250 11177 11250 11091 11250 11176 11251 11091 11251 11177 11251 11182 11252 11183 11252 11077 11252 11182 11253 11184 11253 11183 11253 11184 11254 11118 11254 11115 11254 11116 11255 11112 11255 11114 11255 11089 11256 11112 11256 11185 11256 11112 11257 11186 11257 11185 11257 11186 11258 11187 11258 11188 11258 11186 11259 11189 11259 11187 11259 11190 11260 11189 11260 11191 11260 11079 11261 11191 11261 11078 11261 11190 11262 11191 11262 11079 11262 11077 11263 11183 11263 11076 11263 11120 11264 11114 11264 11113 11264 11196 11265 11195 11265 11197 11265 11055 11266 11070 11266 11056 11266 11056 11267 11199 11267 11053 11267 11171 11268 11200 11268 11170 11268 11066 11269 11067 11269 10935 11269 10926 11270 11067 11270 11068 11270 10927 11271 10926 11271 11068 11271 11054 11272 10931 11272 10930 11272 11054 11273 10942 11273 10931 11273 10931 11274 10942 11274 10941 11274 10926 11275 10935 11275 11067 11275 10935 11276 10933 11276 10936 11276 10949 11277 10948 11277 11058 11277 10947 11278 10945 11278 10944 11278 10893 11279 10890 11279 11045 11279 11137 11280 11136 11280 11144 11280 11166 11281 11163 11281 11165 11281 11166 11282 11192 11282 11163 11282 11062 11283 11061 11283 11201 11283 11060 11284 11167 11284 11062 11284 11130 11285 11126 11285 11129 11285 11202 11286 11203 11286 11204 11286 11203 11287 11202 11287 11205 11287 11206 11288 11205 11288 11207 11288 11210 11289 11209 11289 11211 11289 11212 11290 11211 11290 11213 11290 11215 11291 11216 11291 11217 11291 11217 11292 11216 11292 11218 11292 11218 11293 11219 11293 11217 11293 11213 11294 11218 11294 11212 11294 11210 11295 11208 11295 11209 11295 11208 11296 11205 11296 11206 11296 11223 11297 11224 11297 11225 11297 11223 11298 11226 11298 11224 11298 11223 11299 11227 11299 11226 11299 11224 11300 11231 11300 11232 11300 11233 11301 11232 11301 11234 11301 11235 11302 11234 11302 11236 11302 11235 11303 11237 11303 11238 11303 11238 11304 11240 11304 11239 11304 11239 11305 11240 11305 11241 11305 11224 11306 11233 11306 11225 11306 11227 11307 11242 11307 11228 11307 11244 11308 11243 11308 11245 11308 11244 11309 11228 11309 11243 11309 11228 11310 11244 11310 11230 11310 11243 11311 11242 11311 11246 11311 11248 11312 11249 11312 11250 11312 11248 11313 11251 11313 11249 11313 11252 11314 11251 11314 11248 11314 11257 11315 11258 11315 11256 11315 11259 11316 11261 11316 11260 11316 11263 11317 11207 11317 11262 11317 11268 11318 11267 11318 11269 11318 11266 11319 11267 11319 11270 11319 11270 11320 11267 11320 11268 11320 11268 11321 11269 11321 11241 11321 11271 11322 11240 11322 11272 11322 11273 11323 11274 11323 11272 11323 11273 11324 11275 11324 11274 11324 11273 11325 11276 11325 11275 11325 11275 11326 11276 11326 11277 11326 11277 11327 11276 11327 11278 11327 11258 11328 11277 11328 11278 11328 11258 11329 11257 11329 11277 11329 11260 11330 11261 11330 11279 11330 11280 11331 11260 11331 11279 11331 11272 11332 11240 11332 11288 11332 11271 11333 11272 11333 11274 11333 11222 11334 11213 11334 11290 11334 11288 11335 11213 11335 11289 11335 11287 11336 11289 11336 11291 11336 11293 11337 11292 11337 11294 11337 11293 11338 11294 11338 11295 11338 11287 11339 11285 11339 11288 11339 11271 11340 11268 11340 11241 11340 10990 11341 11297 11341 11298 11341 10994 11342 11299 11342 11300 11342 11301 11343 11302 11343 11303 11343 11253 11344 11307 11344 11251 11344 11253 11345 11306 11345 11307 11345 11304 11346 11305 11346 11306 11346 11307 11347 11308 11347 11251 11347 11251 11348 11308 11348 11249 11348 11249 11349 11308 11349 11247 11349 11246 11350 11250 11350 11249 11350 11246 11351 11242 11351 11250 11351 11239 11352 11233 11352 11235 11352 11309 11353 11236 11353 11310 11353 11311 11354 11310 11354 11312 11354 11311 11355 11314 11355 11310 11355 11312 11356 11315 11356 11313 11356 11215 11357 11202 11357 11204 11357 11304 11358 11301 11358 11303 11358 11323 11359 11324 11359 11320 11359 11320 11360 11324 11360 11322 11360 11322 11361 11324 11361 11325 11361 11327 11362 11324 11362 11328 11362 11329 11363 11328 11363 11330 11363 11331 11364 11329 11364 11330 11364 11329 11365 11334 11365 11327 11365 11326 11366 11325 11366 11337 11366 11337 11367 11325 11367 11335 11367 11339 11368 11341 11368 11340 11368 11341 11369 11343 11369 11344 11369 11345 11370 11341 11370 11344 11370 11343 11371 11346 11371 11344 11371 11344 11372 11346 11372 11347 11372 11354 11373 11353 11373 11348 11373 11355 11374 11354 11374 11348 11374 11348 11375 11350 11375 11355 11375 11334 11376 11357 11376 11327 11376 11327 11377 11357 11377 11336 11377 11357 11378 11334 11378 11329 11378 11358 11379 11357 11379 11329 11379 11331 11380 11359 11380 11358 11380 11360 11381 11320 11381 11319 11381 11359 11382 11330 11382 11332 11382 11345 11383 11351 11383 11362 11383 11352 11384 11353 11384 11354 11384 11362 11385 11340 11385 11345 11385 11345 11386 11340 11386 11341 11386 11350 11387 11349 11387 11356 11387 11356 11388 11349 11388 11364 11388 11342 11389 11363 11389 11365 11389 11343 11390 11342 11390 11365 11390 11343 11391 11366 11391 11346 11391 11377 11392 11378 11392 11379 11392 11122 11393 11377 11393 11380 11393 11379 11394 11381 11394 11377 11394 11113 11395 11378 11395 11119 11395 11119 11396 11378 11396 11122 11396 11382 11397 11383 11397 11384 11397 11383 11398 11382 11398 11385 11398 11384 11399 11386 11399 11132 11399 11377 11400 11143 11400 11141 11400 11380 11401 11141 11401 11131 11401 11387 11402 11160 11402 11383 11402 11383 11403 11160 11403 11133 11403 11386 11404 11383 11404 11133 11404 11388 11405 11390 11405 11389 11405 11392 11406 11391 11406 11393 11406 11392 11407 11389 11407 11391 11407 11392 11408 11394 11408 11389 11408 11389 11409 11394 11409 11220 11409 11390 11410 11395 11410 11391 11410 11391 11411 11395 11411 11396 11411 11393 11412 11396 11412 8279 11412 11395 11413 11397 11413 11396 11413 11398 11414 11288 11414 11400 11414 11399 11415 11400 11415 11401 11415 11399 11416 11398 11416 11400 11416 11288 11417 11402 11417 11400 11417 11400 11418 11402 11418 11403 11418 11401 11419 11403 11419 11404 11419 11404 11420 11403 11420 11406 11420 11408 11421 11409 11421 11410 11421 8281 11422 11408 11422 11410 11422 11409 11423 11238 11423 11410 11423 11410 11424 11238 11424 11411 11424 11412 11425 11411 11425 11237 11425 11413 11426 11237 11426 11414 11426 11415 11427 11414 11427 11309 11427 11416 11428 11309 11428 11314 11428 8282 11429 11412 11429 11420 11429 11412 11430 11237 11430 11413 11430 11421 11431 11413 11431 11422 11431 11421 11432 11420 11432 11412 11432 11422 11433 11415 11433 11416 11433 11422 11434 11413 11434 11415 11434 11415 11435 11309 11435 11416 11435 11418 11436 11423 11436 11313 11436 11419 11437 11418 11437 11313 11437 11219 11438 11222 11438 11388 11438 11402 11439 11288 11439 11405 11439 11240 11440 11405 11440 11288 11440 11411 11441 11238 11441 11237 11441 11236 11442 11309 11442 11237 11442 11313 11443 11423 11443 11311 11443 11098 11444 11424 11444 11099 11444 11099 11445 11424 11445 11425 11445 11424 11446 11426 11446 11425 11446 11424 11447 11427 11447 11426 11447 11426 11448 11427 11448 11428 11448 11432 11449 11437 11449 11438 11449 11439 11450 11438 11450 11437 11450 11439 11451 11436 11451 11440 11451 11441 11452 11434 11452 11438 11452 11432 11453 11438 11453 11434 11453 11444 11454 11443 11454 11445 11454 11446 11455 11445 11455 11443 11455 11446 11456 11447 11456 11445 11456 11092 11457 11445 11457 11447 11457 11451 11458 11452 11458 11453 11458 11451 11459 11454 11459 11452 11459 11451 11460 11455 11460 11454 11460 11458 11461 11457 11461 11459 11461 11451 11462 11460 11462 11461 11462 11462 11463 11464 11463 11466 11463 11466 11464 11464 11464 11467 11464 11464 11465 11463 11465 11467 11465 11468 11466 11467 11466 11463 11466 11463 11467 11465 11467 11459 11467 11469 11468 11463 11468 11459 11468 11469 11469 11470 11469 11463 11469 11472 11470 11470 11470 11450 11470 11475 11471 11473 11471 11472 11471 11477 11472 11472 11472 11450 11472 11477 11473 11478 11473 11479 11473 11465 11474 11480 11474 11459 11474 11459 11475 11481 11475 11482 11475 11465 11476 11483 11476 11480 11476 11484 11477 11469 11477 11457 11477 11479 11478 11485 11478 11486 11478 11485 11479 11478 11479 11449 11479 11430 11480 11429 11480 11433 11480 11448 11481 11487 11481 11445 11481 11451 11482 11461 11482 11457 11482 11457 11483 11461 11483 11484 11483 11444 11484 11489 11484 11442 11484 11444 11485 11490 11485 11489 11485 11444 11486 11487 11486 11491 11486 11491 11487 11487 11487 11492 11487 11493 11488 11487 11488 11471 11488 11443 11489 11442 11489 11489 11489 11489 11490 11494 11490 11443 11490 11494 11491 11446 11491 11443 11491 11435 11492 11434 11492 11495 11492 11495 11493 11434 11493 11441 11493 11496 11494 11460 11494 11453 11494 11496 11495 11461 11495 11460 11495 11469 11496 11484 11496 11499 11496 11461 11497 11498 11497 11484 11497 11458 11498 11459 11498 11482 11498 11482 11499 11481 11499 11500 11499 11470 11500 11474 11500 11505 11500 11474 11501 11473 11501 11505 11501 11496 11502 11453 11502 11452 11502 11427 11503 11098 11503 11096 11503 11096 11504 11097 11504 11427 11504 11427 11505 11097 11505 11506 11505 8168 11506 11508 11506 11509 11506 11509 11507 11508 11507 11510 11507 10961 11508 11511 11508 10988 11508 10961 11509 11022 11509 11511 11509 11512 11510 11019 11510 11513 11510 11512 11511 11513 11511 11510 11511 11514 11512 11508 11512 11515 11512 10986 11513 10988 11513 11511 11513 11514 11514 11515 11514 11516 11514 10986 11515 11516 11515 11517 11515 10984 11516 11517 11516 10983 11516 10984 11517 10986 11517 11517 11517 11030 11518 11518 11518 11032 11518 11517 11519 11519 11519 10975 11519 8165 11520 11032 11520 8166 11520 11519 11521 8167 11521 11520 11521 8166 11522 11032 11522 11520 11522 11520 11523 8167 11523 8166 11523 10977 11524 10975 11524 11518 11524 10974 11525 10983 11525 11517 11525 11019 11526 11017 11526 11521 11526 11022 11527 11512 11527 11511 11527 11517 11528 10975 11528 10974 11528 11022 11529 11019 11529 11512 11529 11511 11530 11512 11530 11514 11530 11516 11531 11511 11531 11514 11531 11519 11532 11516 11532 11515 11532 11518 11533 10975 11533 11519 11533 11522 11534 11509 11534 11510 11534 11522 11535 11510 11535 11513 11535 11521 11536 11013 11536 11523 11536 11523 11537 11205 11537 11202 11537 11521 11538 11202 11538 11513 11538 8273 11539 11509 11539 11524 11539 11254 11540 11000 11540 11253 11540 11254 11541 11258 11541 11000 11541 11525 11542 11001 11542 11000 11542 11003 11543 11523 11543 11015 11543 11003 11544 11525 11544 11523 11544 11523 11545 11525 11545 11207 11545 11523 11546 11207 11546 11205 11546 10996 11547 11304 11547 10997 11547 11301 11548 11304 11548 10994 11548 11306 11549 11253 11549 10997 11549 11304 11550 11306 11550 10997 11550 11258 11551 11260 11551 11525 11551 11260 11552 11207 11552 11525 11552 10997 11553 11253 11553 11000 11553 11202 11554 11526 11554 11513 11554 11513 11555 11526 11555 11522 11555 11524 11556 11509 11556 11522 11556 11527 11557 11498 11557 11497 11557 11530 11558 11529 11558 11531 11558 11532 11559 11533 11559 11534 11559 11530 11560 11528 11560 11529 11560 11456 11561 11536 11561 11529 11561 11529 11562 11536 11562 11537 11562 11533 11563 11528 11563 11530 11563 11539 11564 11074 11564 11072 11564 10908 11565 11072 11565 11057 11565 11540 11566 11054 11566 11052 11566 11539 11567 11072 11567 10908 11567 11540 11568 10902 11568 11057 11568 11047 11569 11540 11569 11052 11569 11080 11570 11075 11570 11090 11570 11054 11571 11540 11571 11057 11571 11100 11572 11099 11572 11101 11572 11544 11573 11506 11573 11447 11573 11506 11574 11094 11574 11447 11574 11499 11575 11498 11575 11502 11575 11502 11576 11498 11576 11492 11576 10898 11577 11547 11577 10900 11577 10894 11578 10902 11578 11540 11578 11549 11579 11047 11579 10886 11579 10894 11580 10896 11580 10902 11580 10902 11581 10896 11581 10918 11581 11550 11582 10920 11582 11551 11582 11550 11583 10918 11583 10920 11583 11550 11584 11552 11584 10918 11584 11550 11585 11553 11585 11552 11585 11554 11586 11553 11586 11555 11586 11556 11587 11555 11587 11557 11587 11558 11588 11557 11588 11547 11588 11542 11589 11375 11589 11373 11589 11475 11590 11373 11590 11372 11590 11560 11591 11376 11591 11561 11591 11562 11592 11561 11592 11563 11592 11562 11593 11369 11593 11560 11593 11564 11594 11559 11594 11565 11594 11467 11595 11338 11595 11501 11595 11466 11596 11467 11596 11501 11596 10918 11597 10900 11597 10922 11597 10922 11598 10900 11598 11547 11598 11557 11599 10924 11599 11547 11599 10920 11600 11567 11600 11551 11600 10906 11601 11539 11601 10908 11601 10906 11602 10910 11602 11539 11602 10906 11603 10903 11603 10914 11603 10914 11604 10903 11604 10918 11604 10912 11605 11569 11605 11558 11605 11547 11606 10912 11606 11558 11606 10918 11607 10903 11607 10902 11607 10910 11608 10912 11608 11539 11608 11570 11609 11571 11609 11541 11609 10924 11610 10922 11610 11547 11610 11332 11611 11333 11611 11361 11611 11573 11612 11358 11612 11359 11612 11357 11613 11574 11613 11336 11613 11357 11614 11575 11614 11574 11614 11575 11615 11576 11615 11537 11615 11577 11616 11579 11616 11530 11616 11531 11617 11577 11617 11530 11617 11581 11618 11572 11618 11580 11618 11581 11619 11583 11619 11582 11619 11585 11620 11584 11620 11586 11620 11585 11621 11586 11621 11587 11621 11588 11622 11587 11622 11589 11622 11321 11623 11591 11623 11319 11623 11321 11624 11337 11624 11591 11624 11591 11625 11337 11625 11592 11625 11574 11626 11351 11626 11352 11626 11365 11627 11363 11627 11366 11627 11364 11628 11363 11628 11566 11628 11593 11629 11355 11629 11356 11629 11593 11630 11592 11630 11352 11630 11363 11631 11338 11631 11566 11631 11340 11632 11594 11632 11338 11632 11536 11633 11351 11633 11440 11633 11488 11634 11429 11634 11537 11634 11439 11635 11575 11635 11438 11635 11439 11636 11574 11636 11575 11636 11439 11637 11440 11637 11574 11637 11574 11638 11440 11638 11351 11638 11356 11639 11364 11639 11566 11639 11558 11640 11556 11640 11557 11640 11595 11641 11369 11641 11596 11641 11595 11642 11565 11642 11560 11642 11368 11643 11596 11643 11369 11643 11596 11644 11597 11644 11598 11644 11599 11645 11598 11645 11571 11645 11599 11646 11571 11646 11570 11646 11563 11647 11600 11647 11597 11647 11563 11648 11561 11648 11600 11648 11598 11649 11600 11649 11375 11649 11571 11650 11375 11650 11542 11650 11541 11651 11571 11651 11542 11651 11486 11652 11542 11652 11475 11652 11542 11653 11485 11653 11090 11653 11561 11654 11376 11654 11600 11654 11576 11655 11578 11655 11531 11655 11538 11656 11530 11656 11590 11656 11579 11657 11590 11657 11530 11657 11590 11658 11583 11658 11585 11658 11585 11659 11583 11659 11584 11659 11601 11660 11594 11660 11362 11660 11504 11661 11503 11661 11559 11661 11559 11662 11503 11662 11505 11662 11541 11663 11539 11663 11570 11663 11570 11664 11539 11664 11547 11664 11602 11665 11540 11665 11548 11665 11603 11666 11047 11666 11549 11666 11602 11667 10894 11667 11540 11667 11599 11668 11596 11668 11598 11668 11591 11669 11580 11669 11319 11669 11319 11670 11580 11670 11360 11670 11605 11671 11584 11671 11581 11671 11586 11672 11606 11672 11587 11672 11609 11673 11607 11673 11608 11673 11609 11674 11610 11674 11607 11674 11609 11675 11611 11675 11610 11675 11610 11676 11611 11676 11612 11676 11613 11677 11612 11677 11614 11677 11613 11678 11610 11678 11612 11678 11589 11679 11587 11679 11607 11679 11615 11680 11607 11680 11610 11680 11587 11681 11606 11681 11607 11681 11612 11682 11616 11682 11617 11682 11617 11683 11616 11683 11618 11683 11618 11684 11619 11684 11617 11684 11619 11685 11618 11685 11620 11685 11623 11686 11622 11686 11624 11686 11625 11687 11624 11687 8139 11687 11626 11688 11627 11688 11619 11688 11614 11689 11617 11689 11627 11689 11622 11690 11623 11690 11621 11690 11601 11691 11536 11691 11456 11691 11594 11692 11601 11692 11456 11692 11597 11693 11600 11693 11598 11693 11338 11694 11467 11694 11566 11694 11628 11695 11629 11695 11630 11695 11632 11696 11631 11696 11633 11696 11632 11697 11633 11697 11634 11697 11635 11698 11634 11698 11636 11698 11630 11699 11631 11699 11632 11699 11637 11700 11634 11700 11635 11700 11638 11701 11639 11701 11640 11701 11646 11702 11647 11702 11648 11702 11646 11703 11648 11703 11650 11703 11650 11704 11648 11704 11651 11704 11651 11705 11652 11705 11650 11705 11640 11706 11639 11706 11653 11706 11655 11707 11656 11707 11657 11707 11658 11708 11655 11708 11659 11708 11658 11709 11661 11709 11660 11709 11660 11710 11661 11710 11662 11710 11662 11711 11663 11711 11664 11711 11664 11712 11663 11712 11665 11712 11668 11713 11666 11713 11667 11713 11663 11714 11669 11714 11670 11714 11671 11715 11669 11715 11645 11715 11672 11716 11673 11716 11674 11716 11672 11717 11674 11717 11675 11717 11669 11718 11676 11718 11643 11718 11643 11719 11676 11719 11641 11719 11641 11720 11676 11720 11677 11720 11642 11721 11678 11721 11679 11721 11641 11722 11677 11722 11642 11722 11657 11723 11638 11723 11679 11723 11666 11724 11668 11724 11681 11724 11682 11725 11681 11725 11668 11725 11682 11726 11683 11726 11681 11726 11683 11727 11684 11727 11685 11727 11686 11728 11687 11728 11688 11728 11686 11729 11688 11729 11656 11729 11691 11730 11688 11730 11690 11730 11691 11731 11692 11731 11688 11731 11691 11732 11693 11732 11692 11732 11691 11733 11695 11733 11694 11733 11698 11734 11699 11734 11700 11734 11706 11735 11707 11735 11708 11735 11708 11736 11707 11736 11690 11736 11705 11737 11702 11737 11703 11737 11665 11738 11701 11738 11667 11738 11713 11739 11714 11739 11711 11739 11713 11740 11716 11740 11715 11740 11713 11741 11717 11741 11716 11741 10991 11742 11719 11742 11720 11742 11710 11743 11721 11743 11712 11743 11721 11744 11723 11744 11722 11744 11722 11745 11723 11745 11724 11745 11724 11746 11723 11746 11725 11746 11726 11747 11725 11747 11727 11747 11729 11748 11728 11748 11730 11748 11701 11749 11734 11749 11699 11749 11701 11750 11735 11750 11734 11750 11734 11751 11735 11751 11736 11751 11732 11752 11733 11752 11734 11752 11659 11753 11655 11753 11657 11753 11666 11754 11664 11754 11665 11754 11673 11755 11645 11755 11649 11755 11646 11756 11738 11756 11647 11756 11646 11757 11739 11757 11738 11757 11646 11758 11650 11758 11739 11758 11739 11759 11650 11759 11652 11759 11297 11760 10991 11760 11720 11760 11649 11761 11647 11761 11737 11761 11740 11762 11673 11762 11672 11762 11742 11763 11743 11763 11736 11763 11748 11764 11676 11764 11749 11764 11677 11765 11748 11765 11678 11765 11678 11766 11748 11766 11750 11766 11750 11767 11679 11767 11678 11767 11676 11768 11669 11768 11749 11768 11657 11769 11679 11769 11751 11769 11657 11770 11751 11770 11659 11770 11663 11771 11752 11771 11747 11771 11753 11772 11750 11772 11754 11772 11754 11773 11750 11773 11748 11773 11755 11774 11749 11774 11669 11774 11754 11775 11748 11775 11756 11775 11757 11776 11747 11776 11758 11776 11758 11777 11747 11777 11752 11777 11761 11778 11752 11778 11759 11778 11763 11779 11681 11779 11683 11779 11764 11780 11664 11780 11666 11780 11765 11781 11655 11781 11660 11781 11660 11782 11662 11782 11765 11782 11765 11783 11662 11783 11766 11783 11662 11784 11664 11784 11766 11784 11767 11785 11686 11785 11656 11785 11768 11786 11656 11786 11762 11786 11690 11787 11769 11787 11708 11787 11702 11788 11770 11788 11771 11788 11770 11789 11705 11789 11706 11789 11667 11790 11772 11790 11668 11790 11684 11791 11772 11791 11687 11791 11773 11792 11689 11792 11687 11792 11697 11793 11696 11793 11776 11793 11691 11794 11776 11794 11696 11794 11779 11795 11704 11795 11703 11795 11707 11796 11779 11796 11775 11796 11780 11797 11776 11797 11691 11797 11782 11798 11710 11798 11693 11798 11783 11799 11728 11799 11725 11799 11783 11800 11784 11800 11728 11800 11723 11801 11782 11801 11783 11801 11730 11802 11784 11802 11731 11802 11784 11803 11733 11803 11731 11803 11785 11804 11700 11804 11699 11804 11700 11805 11785 11805 11786 11805 11786 11806 11694 11806 11695 11806 11790 11807 11252 11807 11248 11807 11791 11808 11267 11808 11264 11808 11225 11809 11241 11809 11792 11809 11793 11810 11242 11810 11227 11810 11790 11811 11248 11811 11250 11811 11792 11812 11223 11812 11225 11812 11792 11813 11227 11813 11223 11813 11795 11814 11277 11814 11794 11814 11795 11815 11275 11815 11277 11815 11795 11816 11271 11816 11274 11816 11279 11817 11261 11817 11798 11817 11798 11818 11286 11818 11282 11818 11285 11819 11286 11819 11799 11819 11285 11820 11799 11820 11272 11820 11273 11821 11272 11821 11799 11821 11287 11822 11801 11822 11285 11822 11802 11823 11260 11823 11280 11823 11281 11824 11802 11824 11280 11824 11283 11825 11802 11825 11281 11825 11293 11826 11804 11826 11291 11826 11803 11827 11293 11827 11295 11827 11260 11828 11802 11828 11079 11828 11187 11829 11802 11829 11801 11829 11086 11830 11287 11830 11804 11830 11089 11831 11287 11831 11086 11831 11084 11832 11804 11832 11803 11832 11081 11833 11803 11833 11263 11833 11086 11834 11804 11834 11084 11834 11213 11835 11805 11835 11289 11835 11294 11836 11807 11836 11806 11836 11806 11837 11263 11837 11296 11837 11209 11838 11809 11838 11211 11838 11211 11839 11809 11839 11213 11839 11087 11840 11807 11840 11805 11840 11085 11841 11807 11841 11087 11841 11087 11842 11805 11842 11088 11842 11805 11843 11213 11843 11108 11843 11088 11844 11805 11844 11108 11844 11108 11845 11213 11845 11180 11845 11180 11846 11213 11846 11809 11846 11176 11847 11809 11847 11808 11847 11810 11848 11205 11848 11208 11848 11212 11849 11810 11849 11210 11849 11811 11850 11204 11850 11203 11850 11812 11851 11218 11851 11216 11851 11216 11852 11214 11852 11812 11852 11175 11853 11810 11853 11212 11853 11175 11854 11212 11854 11179 11854 11103 11855 11212 11855 11218 11855 11181 11856 11212 11856 11103 11856 11103 11857 11218 11857 11102 11857 11102 11858 11218 11858 11100 11858 11100 11859 11812 11859 11095 11859 11095 11860 11811 11860 11093 11860 11649 11861 11814 11861 11648 11861 11654 11862 11651 11862 11815 11862 11648 11863 11815 11863 11651 11863 11641 11864 11816 11864 11644 11864 11641 11865 11817 11865 11816 11865 11817 11866 11641 11866 11640 11866 11649 11867 11645 11867 11813 11867 11813 11868 11645 11868 11818 11868 11818 11869 11645 11869 11644 11869 11750 11870 11753 11870 11679 11870 11679 11871 11753 11871 11751 11871 11819 11872 11779 11872 11778 11872 11779 11873 11821 11873 11781 11873 11775 11874 11779 11874 11781 11874 11697 11875 11822 11875 11777 11875 11697 11876 11823 11876 11822 11876 11823 11877 11697 11877 11824 11877 11825 11878 11777 11878 11822 11878 11826 11879 11698 11879 11777 11879 11826 11880 11777 11880 11825 11880 11827 11881 11699 11881 11733 11881 11784 11882 11783 11882 11829 11882 11829 11883 11783 11883 11831 11883 11831 11884 11783 11884 11832 11884 11787 11885 11832 11885 11783 11885 11833 11886 11786 11886 11785 11886 11765 11887 11835 11887 11836 11887 11763 11888 11838 11888 11837 11888 11840 11889 11766 11889 11664 11889 11840 11890 11664 11890 11764 11890 11840 11891 11764 11891 11837 11891 11841 11892 11667 11892 11771 11892 11770 11893 11842 11893 11771 11893 11770 11894 11843 11894 11842 11894 11843 11895 11770 11895 11844 11895 11774 11896 11844 11896 11769 11896 11772 11897 11667 11897 11845 11897 11772 11898 11846 11898 11847 11898 11772 11899 11847 11899 11773 11899 11841 11900 11845 11900 11667 11900 11203 11901 11093 11901 11811 11901 11286 11902 11189 11902 11186 11902 11078 11903 11191 11903 11798 11903 11797 11904 11800 11904 11077 11904 11273 11905 11118 11905 11800 11905 11112 11906 11286 11906 11285 11906 11260 11907 11079 11907 11262 11907 11269 11908 11791 11908 11195 11908 11195 11909 11791 11909 11197 11909 11073 11910 11791 11910 11789 11910 11227 11911 11792 11911 11121 11911 11227 11912 11129 11912 11793 11912 11060 11913 11793 11913 11166 11913 11793 11914 11059 11914 11790 11914 11120 11915 11792 11915 11241 11915 11795 11916 11184 11916 11115 11916 11184 11917 11795 11917 11183 11917 11076 11918 11183 11918 11794 11918 11194 11919 11796 11919 11268 11919 11194 11920 11196 11920 11796 11920 11796 11921 11196 11921 11198 11921 11271 11922 11115 11922 11114 11922 11194 11923 11268 11923 11114 11923 11207 11924 11080 11924 11091 11924 11207 11925 11091 11925 11808 11925 11848 11926 11850 11926 10964 11926 10985 11927 11850 11927 11852 11927 11853 11928 10987 11928 11852 11928 10987 11929 10985 11929 11852 11929 10985 11930 10968 11930 11850 11930 10964 11931 10963 11931 11849 11931 11578 11932 11576 11932 11854 11932 11856 11933 11582 11933 11857 11933 11856 11934 11857 11934 11858 11934 11854 11935 11858 11935 11859 11935 11859 11936 11855 11936 11854 11936 11575 11937 11861 11937 11854 11937 11575 11938 11357 11938 11573 11938 11572 11939 11582 11939 11856 11939 11573 11940 11572 11940 11856 11940 11579 11941 11578 11941 11860 11941 11583 11942 11863 11942 11582 11942 11865 11943 11862 11943 11860 11943 11866 11944 11860 11944 11855 11944 11859 11945 11867 11945 11855 11945 11868 11946 11858 11946 11857 11946 11869 11947 11857 11947 11582 11947 11863 11948 11862 11948 11870 11948 11870 11949 11862 11949 11871 11949 11871 11950 11862 11950 11865 11950 11865 11951 11860 11951 11866 11951 11859 11952 11858 11952 11872 11952 11872 11953 11858 11953 11868 11953 11868 11954 11857 11954 11869 11954 11867 11955 11873 11955 11866 11955 11876 11956 11868 11956 11869 11956 11877 11957 11869 11957 11864 11957 11880 11958 11871 11958 11865 11958 11873 11959 11859 11959 11874 11959 11876 11960 11869 11960 11877 11960 11877 11961 11863 11961 11883 11961 11883 11962 11863 11962 11878 11962 10962 11963 11884 11963 10960 11963 10954 11964 11885 11964 11886 11964 10952 11965 10954 11965 11886 11965 10952 11966 11877 11966 11849 11966 11874 11967 11885 11967 11884 11967 11873 11968 11884 11968 10962 11968 11853 11969 11881 11969 10962 11969 11875 11970 11885 11970 11874 11970 11874 11971 11884 11971 11873 11971 11879 11972 11851 11972 11878 11972 11883 11973 11848 11973 11877 11973 11887 11974 11888 11974 11889 11974 11888 11975 11892 11975 11893 11975 11069 11976 11887 11976 11071 11976 11069 11977 11894 11977 11887 11977 11895 11978 11170 11978 11897 11978 11898 11979 11173 11979 11891 11979 11891 11980 11890 11980 11888 11980 11200 11981 11896 11981 11897 11981 11887 11982 11902 11982 11888 11982 11903 11983 11904 11983 11905 11983 11905 11984 11906 11984 11903 11984 11905 11985 11907 11985 11906 11985 11910 11986 11906 11986 11909 11986 11912 11987 11913 11987 11911 11987 11917 11988 11919 11988 11918 11988 11918 11989 11919 11989 11903 11989 11904 11990 11903 11990 11919 11990 11918 11991 11920 11991 11922 11991 11913 11992 11922 11992 11923 11992 11913 11993 11923 11993 11911 11993 11923 11994 11921 11994 11911 11994 11911 11995 11921 11995 11906 11995 11903 11996 11906 11996 11921 11996 11924 11997 11925 11997 11926 11997 11934 11998 11935 11998 11924 11998 11933 11999 11939 11999 11934 11999 11928 12000 11940 12000 11938 12000 11938 12001 11940 12001 11941 12001 11925 12002 11942 12002 11943 12002 11935 12003 11941 12003 11924 12003 11925 12004 11943 12004 11930 12004 11950 12005 11951 12005 11949 12005 11945 12006 11952 12006 11953 12006 11953 12007 11946 12007 11945 12007 11955 12008 11956 12008 11944 12008 11957 12009 11958 12009 11956 12009 11952 12010 11960 12010 11953 12010 11947 12011 11958 12011 11962 12011 11963 12012 11951 12012 11964 12012 11947 12013 11963 12013 11965 12013 11956 12014 11966 12014 11967 12014 11947 12015 11965 12015 11958 12015 11956 12016 11967 12016 11944 12016 11951 12017 11945 12017 11964 12017 11970 12018 11904 12018 11919 12018 11908 12019 11905 12019 11972 12019 11973 12020 11974 12020 11975 12020 11974 12021 11910 12021 11975 12021 11976 12022 11977 12022 11978 12022 11981 12023 11982 12023 11983 12023 11985 12024 11981 12024 11984 12024 11981 12025 11985 12025 11987 12025 11989 12026 11990 12026 11991 12026 11989 12027 11991 12027 11992 12027 11995 12028 11994 12028 11996 12028 11977 12029 11996 12029 11997 12029 11998 12030 11997 12030 11999 12030 11970 12031 12002 12031 11968 12031 11045 12032 12003 12032 11044 12032 12004 12033 12005 12033 11969 12033 11968 12034 12004 12034 11969 12034 12008 12035 12001 12035 12009 12035 11968 12036 12002 12036 12004 12036 12002 12037 12010 12037 12004 12037 12003 12038 11050 12038 11051 12038 11172 12039 11907 12039 12011 12039 11172 12040 11973 12040 11907 12040 11172 12041 11168 12041 11973 12041 11973 12042 11168 12042 11974 12042 11065 12043 11971 12043 11168 12043 11971 12044 11061 12044 12012 12044 11998 12045 11980 12045 11978 12045 11996 12046 11977 12046 11995 12046 11982 12047 12016 12047 11983 12047 11988 12048 12018 12048 12019 12048 12021 12049 12022 12049 12023 12049 11995 12050 12021 12050 11993 12050 12025 12051 12026 12051 12027 12051 12028 12052 12029 12052 12030 12052 11993 12053 12021 12053 12031 12053 12028 12054 12031 12054 12032 12054 12033 12055 12025 12055 12032 12055 8216 12056 12027 12056 12026 12056 12029 12057 12034 12057 12030 12057 12030 12058 12034 12058 12035 12058 11993 12059 12036 12059 11989 12059 11990 12060 11989 12060 12037 12060 11973 12061 11909 12061 11907 12061 12011 12062 11908 12062 11972 12062 11916 12063 11912 12063 11168 12063 12035 12064 12034 12064 12037 12064 12025 12065 12027 12065 12028 12065 11999 12066 12040 12066 12041 12066 12001 12067 12008 12067 12002 12067 12043 12068 12042 12068 12009 12068 12044 12069 11997 12069 11996 12069 11989 12070 12036 12070 12035 12070 11977 12071 11998 12071 11978 12071 11982 12072 12043 12072 12001 12072 11982 12073 12015 12073 12041 12073 12015 12074 11999 12074 12041 12074 11993 12075 11994 12075 11995 12075 12028 12076 12032 12076 12025 12076 12045 12077 12032 12077 12023 12077 12022 12078 12021 12078 11979 12078 11979 12079 12021 12079 11976 12079 11979 12080 11980 12080 11988 12080 12012 12081 12013 12081 11970 12081 12013 12082 12012 12082 11162 12082 12014 12083 12013 12083 11162 12083 12023 12084 12032 12084 12031 12084 12039 12085 12031 12085 12028 12085 11988 12086 11980 12086 11999 12086 11971 12087 12012 12087 11917 12087 12035 12088 12036 12088 12039 12088 12039 12089 12028 12089 12030 12089 11995 12090 11977 12090 11976 12090 12046 12091 12047 12091 12048 12091 12047 12092 11921 12092 11923 12092 12048 12093 11923 12093 11922 12093 12048 12094 11922 12094 12046 12094 12050 12095 11939 12095 11933 12095 12051 12096 12052 12096 11932 12096 12054 12097 12053 12097 12051 12097 12054 12098 11926 12098 12053 12098 12054 12099 11933 12099 11926 12099 12055 12100 12008 12100 12009 12100 12060 12101 12061 12101 12062 12101 12065 12102 12064 12102 12066 12102 12067 12103 12069 12103 12070 12103 8207 12104 12071 12104 12073 12104 11044 12105 12003 12105 12074 12105 12057 12106 12009 12106 12042 12106 12058 12107 12042 12107 12040 12107 12075 12108 12044 12108 11994 12108 12010 12109 12002 12109 12008 12109 12059 12110 12007 12110 12006 12110 12077 12111 12075 12111 11994 12111 12057 12112 12042 12112 12058 12112 12058 12113 12040 12113 12007 12113 12006 12114 11997 12114 12075 12114 12075 12115 11997 12115 12044 12115 12078 12116 11991 12116 11990 12116 12079 12117 12080 12117 12081 12117 12006 12118 12061 12118 12059 12118 12063 12119 12092 12119 12093 12119 12094 12120 12093 12120 12095 12120 12049 12121 11929 12121 12100 12121 12104 12122 11931 12122 12049 12122 12104 12123 11932 12123 11931 12123 12051 12124 12105 12124 12054 12124 11933 12125 12054 12125 12105 12125 12004 12126 12106 12126 12005 12126 12100 12127 11929 12127 12107 12127 12089 12128 12108 12128 12102 12128 12089 12129 12098 12129 12090 12129 12109 12130 11936 12130 11937 12130 12107 12131 11936 12131 12109 12131 12080 12132 12073 12132 12072 12132 12076 12133 12079 12133 12111 12133 12078 12134 12113 12134 12112 12134 12078 12135 12110 12135 12111 12135 12077 12136 12114 12136 12084 12136 12061 12137 12075 12137 12085 12137 12062 12138 12061 12138 12085 12138 12088 12139 12115 12139 12108 12139 12090 12140 12056 12140 12088 12140 12008 12141 12055 12141 12010 12141 12055 12142 12109 12142 12010 12142 12055 12143 12107 12143 12109 12143 12074 12144 12005 12144 12050 12144 11990 12145 12110 12145 12078 12145 11990 12146 12076 12146 12110 12146 12086 12147 12112 12147 12113 12147 12113 12148 12078 12148 12111 12148 12086 12149 12113 12149 12081 12149 12115 12150 12060 12150 12094 12150 12062 12151 12085 12151 12064 12151 12063 12152 12094 12152 12060 12152 12088 12153 12056 12153 12057 12153 12083 12154 12084 12154 12114 12154 12078 12155 12083 12155 12114 12155 12086 12156 12069 12156 12112 12156 12069 12157 12068 12157 12112 12157 12098 12158 12099 12158 12107 12158 12099 12159 12100 12159 12107 12159 12108 12160 12089 12160 12088 12160 12095 12161 12102 12161 12108 12161 12009 12162 12056 12162 12055 12162 12116 12163 12117 12163 12118 12163 12117 12164 11942 12164 12118 12164 11940 12165 11943 12165 12119 12165 12119 12166 11943 12166 12117 12166 12118 12167 11942 12167 11941 12167 12053 12168 11926 12168 12052 12168 12106 12169 11934 12169 11939 12169 12122 12170 12123 12170 12121 12170 12124 12171 12122 12171 12121 12171 12122 12172 12124 12172 12125 12172 12126 12173 12127 12173 12128 12173 11962 12174 11959 12174 12129 12174 12130 12175 12128 12175 12127 12175 12130 12176 12127 12176 11952 12176 11946 12177 12125 12177 12124 12177 10893 12178 12131 12178 10882 12178 10893 12179 11044 12179 12131 12179 10882 12180 12131 12180 12132 12180 12136 12181 11955 12181 12120 12181 12136 12182 12123 12182 12137 12182 11602 12183 12137 12183 12138 12183 11602 12184 11548 12184 12136 12184 12139 12185 12129 12185 12140 12185 12139 12186 12142 12186 12129 12186 12139 12187 12143 12187 12142 12187 12139 12188 12144 12188 12143 12188 12146 12189 12126 12189 12145 12189 12146 12190 12147 12190 12126 12190 12146 12191 12148 12191 12149 12191 12151 12192 12150 12192 12152 12192 11829 12193 12153 12193 12154 12193 12156 12194 11828 12194 12157 12194 12160 12195 12162 12195 12158 12195 12158 12196 12162 12196 12163 12196 12148 12197 12164 12197 12150 12197 12150 12198 12164 12198 12152 12198 12165 12199 12166 12199 12167 12199 12165 12200 12168 12200 12155 12200 12165 12201 12167 12201 12168 12201 12163 12202 12157 12202 12158 12202 12161 12203 12159 12203 12169 12203 12175 12204 12176 12204 11826 12204 11841 12205 11778 12205 11826 12205 11841 12206 11842 12206 11778 12206 12177 12207 12178 12207 11840 12207 11757 12208 12179 12208 11755 12208 12179 12209 12180 12209 11813 12209 11814 12210 12183 12210 11815 12210 12184 12211 12185 12211 11815 12211 11815 12212 12185 12212 11654 12212 12185 12213 12186 12213 11654 12213 11654 12214 12186 12214 11653 12214 11753 12215 12187 12215 11760 12215 12188 12216 11780 12216 11773 12216 11773 12217 11780 12217 11774 12217 11844 12218 11821 12218 11820 12218 11842 12219 11843 12219 11819 12219 12189 12220 11787 12220 11788 12220 12189 12221 12190 12221 11787 12221 12189 12222 12191 12222 12190 12222 12192 12223 12122 12223 11953 12223 11953 12224 11960 12224 12192 12224 12194 12225 12147 12225 12146 12225 11832 12226 12146 12226 12149 12226 12151 12227 12149 12227 12150 12227 12151 12228 11832 12228 12149 12228 12151 12229 12152 12229 11831 12229 12133 12230 11603 12230 10883 12230 10882 12231 12132 12231 12133 12231 10883 12232 11549 12232 10886 12232 11755 12233 11813 12233 11818 12233 11749 12234 11818 12234 11816 12234 11749 12235 11816 12235 11756 12235 11755 12236 11818 12236 11749 12236 11756 12237 11817 12237 11754 12237 11840 12238 11757 12238 11766 12238 11766 12239 11757 12239 11758 12239 11766 12240 11758 12240 11761 12240 11760 12241 12187 12241 11768 12241 11768 12242 12187 12242 11767 12242 11766 12243 11761 12243 11835 12243 11835 12244 11759 12244 11836 12244 11844 12245 11820 12245 11843 12245 11819 12246 11778 12246 11842 12246 11785 12247 11822 12247 11833 12247 11785 12248 11825 12248 11822 12248 11833 12249 11822 12249 11823 12249 11833 12250 11823 12250 11834 12250 11834 12251 11780 12251 11788 12251 11828 12252 11830 12252 12155 12252 12153 12253 11829 12253 12152 12253 12152 12254 11829 12254 11831 12254 12146 12255 11832 12255 12194 12255 11841 12256 11840 12256 11837 12256 11845 12257 11837 12257 11838 12257 11846 12258 11839 12258 11847 12258 12123 12259 12122 12259 12137 12259 12126 12260 12128 12260 12145 12260 12145 12261 12128 12261 11950 12261 12142 12262 11962 12262 12129 12262 12196 12263 12141 12263 12140 12263 12196 12264 12197 12264 12134 12264 12135 12265 12197 12265 11961 12265 12131 12266 12141 12266 12132 12266 12134 12267 12197 12267 12135 12267 11787 12268 12147 12268 12194 12268 11787 12269 12194 12269 11832 12269 12190 12270 12191 12270 12192 12270 12198 12271 12199 12271 12200 12271 11963 12272 12199 12272 11965 12272 12200 12273 11963 12273 11964 12273 12198 12274 11964 12274 11967 12274 12200 12275 11964 12275 12198 12275 12201 12276 11967 12276 11966 12276 12199 12277 11966 12277 11965 12277 12121 12278 11954 12278 11946 12278 12121 12279 11946 12279 12124 12279 12130 12280 11952 12280 11950 12280 11962 12281 12202 12281 11947 12281 12143 12282 11947 12282 12202 12282 12203 12283 11956 12283 11961 12283 12129 12284 11957 12284 12204 12284 12204 12285 11957 12285 12203 12285 12204 12286 12197 12286 12196 12286 12202 12287 12142 12287 12143 12287 11170 12288 12208 12288 11067 12288 11069 12289 11067 12289 11895 12289 11049 12290 12206 12290 11890 12290 11053 12291 11893 12291 11892 12291 11893 12292 11199 12292 11889 12292 11056 12293 12210 12293 11199 12293 12210 12294 11056 12294 11070 12294 12212 12295 11899 12295 12213 12295 11899 12296 11902 12296 12213 12296 12213 12297 11902 12297 12214 12297 11901 12298 11900 12298 12211 12298 12211 12299 11900 12299 12212 12299 12205 12300 11071 12300 11889 12300 12209 12301 11890 12301 12206 12301 12207 12302 11898 12302 12216 12302 12216 12303 11898 12303 12215 12303 11067 12304 12217 12304 11895 12304 12100 12305 12099 12305 12218 12305 12099 12306 12097 12306 12218 12306 12220 12307 12218 12307 12219 12307 12224 12308 12157 12308 12167 12308 12225 12309 12224 12309 12167 12309 12166 12310 12164 12310 12226 12310 12220 12311 12164 12311 12148 12311 12146 12312 12103 12312 12218 12312 12103 12313 12145 12313 12104 12313 12141 12314 12131 12314 12074 12314 12221 12315 12227 12315 12170 12315 12228 12316 12227 12316 12229 12316 11717 12317 11713 12317 12233 12317 12235 12318 11712 12318 11722 12318 12234 12319 11712 12319 12235 12319 11722 12320 11724 12320 12237 12320 12237 12321 11724 12321 12238 12321 12238 12322 11724 12322 11726 12322 12238 12323 11726 12323 12239 12323 12240 12324 11729 12324 12241 12324 12241 12325 11729 12325 11732 12325 12242 12326 11732 12326 11736 12326 12243 12327 11736 12327 11743 12327 12245 12328 11746 12328 12246 12328 12250 12329 12247 12329 12249 12329 12241 12330 11732 12330 12242 12330 12242 12331 11736 12331 12243 12331 12244 12332 11746 12332 12245 12332 12245 12333 12246 12333 12247 12333 12234 12334 12251 12334 12233 12334 12232 12335 12252 12335 11297 12335 8248 12336 8249 12336 12253 12336 12257 12337 12259 12337 12260 12337 12265 12338 12263 12338 12264 12338 12270 12339 12271 12339 8246 12339 8247 12340 12272 12340 12270 12340 8247 12341 12273 12341 12272 12341 8247 12342 8248 12342 12273 12342 12254 12343 12253 12343 12255 12343 12277 12344 12278 12344 12279 12344 12280 12345 12281 12345 12282 12345 12275 12346 12284 12346 12285 12346 12287 12347 12288 12347 12289 12347 12295 12348 12296 12348 12252 12348 12236 12349 12237 12349 12297 12349 12297 12350 12237 12350 12289 12350 12235 12351 12236 12351 12300 12351 12233 12352 12251 12352 12232 12352 12295 12353 12251 12353 12234 12353 12302 12354 12264 12354 12262 12354 12262 12355 12260 12355 12302 12355 12302 12356 12260 12356 12303 12356 12306 12357 12307 12357 12264 12357 12268 12358 12265 12358 12308 12358 12309 12359 12308 12359 12310 12359 8245 12360 12311 12360 12310 12360 8245 12361 12312 12361 12311 12361 8245 12362 8246 12362 12312 12362 12268 12363 12308 12363 12313 12363 12271 12364 12309 12364 12312 12364 8246 12365 12271 12365 12312 12365 12309 12366 12310 12366 12311 12366 12291 12367 12290 12367 12315 12367 12315 12368 12290 12368 12284 12368 12315 12369 12284 12369 12283 12369 12259 12370 12303 12370 12260 12370 12305 12371 12316 12371 12317 12371 12317 12372 12259 12372 12258 12372 12316 12373 12259 12373 12317 12373 12300 12374 12296 12374 12295 12374 12284 12375 12290 12375 12285 12375 12304 12376 12305 12376 12281 12376 12257 12377 12256 12377 12258 12377 12257 12378 12319 12378 12256 12378 12256 12379 12320 12379 12254 12379 12261 12380 12322 12380 12257 12380 12275 12381 12281 12381 12280 12381 12276 12382 12285 12382 12286 12382 12294 12383 12299 12383 12298 12383 12298 12384 12292 12384 12294 12384 12323 12385 12281 12385 12274 12385 12323 12386 12274 12386 12279 12386 12304 12387 12281 12387 12324 12387 12303 12388 12259 12388 12316 12388 12319 12389 12320 12389 12256 12389 12273 12390 12321 12390 12272 12390 12272 12391 12325 12391 12270 12391 12324 12392 12281 12392 12323 12392 12274 12393 12281 12393 12275 12393 12275 12394 12285 12394 12276 12394 12324 12395 12301 12395 12306 12395 12267 12396 12319 12396 12322 12396 12325 12397 12319 12397 12267 12397 12270 12398 12325 12398 12271 12398 12297 12399 12299 12399 12236 12399 12277 12400 12274 12400 12276 12400 12271 12401 12325 12401 12269 12401 12267 12402 12269 12402 12325 12402 12301 12403 12324 12403 12323 12403 12264 12404 12302 12404 12306 12404 12322 12405 12261 12405 12263 12405 12262 12406 12263 12406 12261 12406 12313 12407 12269 12407 12268 12407 12289 12408 12288 12408 12297 12408 12287 12409 12277 12409 12286 12409 12278 12410 12277 12410 12287 12410 12307 12411 12306 12411 12301 12411 12307 12412 12301 12412 12278 12412 12326 12413 12070 12413 8180 12413 12326 12414 12067 12414 12070 12414 12326 12415 12087 12415 12067 12415 12070 12416 12071 12416 8180 12416 8180 12417 8181 12417 12326 12417 12326 12418 8181 12418 12327 12418 12327 12419 8181 12419 12328 12419 8182 12420 8183 12420 12092 12420 12092 12421 8183 12421 12093 12421 12093 12422 8183 12422 8184 12422 8189 12423 12331 12423 12330 12423 8189 12424 8185 12424 12332 12424 12335 12425 8190 12425 8186 12425 12334 12426 8190 12426 12335 12426 12338 12427 8188 12427 12339 12427 12340 12428 12338 12428 12339 12428 12338 12429 12337 12429 8188 12429 12339 12430 12341 12430 12340 12430 12339 12431 12342 12431 12341 12431 12339 12432 12343 12432 12342 12432 12339 12433 8187 12433 12343 12433 12344 12434 8187 12434 8206 12434 12345 12435 12343 12435 12346 12435 12348 12436 12345 12436 12347 12436 12349 12437 12344 12437 12350 12437 12350 12438 12347 12438 12349 12438 12349 12439 12347 12439 12346 12439 12351 12440 12352 12440 12353 12440 12351 12441 12222 12441 12354 12441 12222 12442 12223 12442 12356 12442 12355 12443 12341 12443 12342 12443 12345 12444 12355 12444 12342 12444 12354 12445 12341 12445 12352 12445 12345 12446 12348 12446 12355 12446 12355 12447 12353 12447 12352 12447 12350 12448 8205 12448 12231 12448 12353 12449 12227 12449 12351 12449 12221 12450 12222 12450 12351 12450 12357 12451 12231 12451 8204 12451 8204 12452 12231 12452 8205 12452 12228 12453 12230 12453 12357 12453 8203 12454 12170 12454 12228 12454 8259 12455 8258 12455 12246 12455 12360 12456 12362 12456 12250 12456 8258 12457 12364 12457 12250 12457 12250 12458 12364 12458 12361 12458 12363 12459 12365 12459 12244 12459 12244 12460 12365 12460 12366 12460 12366 12461 12243 12461 12244 12461 12250 12462 12362 12462 12247 12462 12247 12463 12362 12463 12363 12463 12244 12464 12245 12464 12363 12464 12360 12465 12368 12465 12362 12465 12369 12466 12361 12466 12370 12466 8258 12467 8255 12467 12371 12467 12371 12468 8255 12468 12372 12468 12364 12469 12371 12469 12372 12469 12370 12470 12373 12470 12369 12470 12368 12471 12373 12471 12374 12471 12375 12472 12374 12472 12376 12472 12365 12473 12377 12473 12366 12473 12365 12474 12363 12474 12378 12474 12368 12475 12374 12475 12362 12475 12363 12476 12375 12476 12376 12476 12242 12477 12366 12477 12379 12477 12242 12478 12379 12478 12367 12478 12363 12479 12362 12479 12375 12479 12371 12480 12364 12480 8258 12480 12278 12481 12287 12481 12367 12481 12379 12482 12366 12482 12377 12482 12265 12483 12380 12483 12308 12483 12378 12484 12376 12484 12374 12484 8244 12485 12310 12485 8257 12485 12380 12486 12374 12486 12383 12486 12373 12487 12372 12487 12383 12487 12383 12488 8256 12488 12384 12488 12383 12489 12372 12489 8256 12489 8256 12490 8257 12490 12384 12490 12266 12491 12307 12491 12382 12491 12384 12492 12380 12492 12383 12492 12385 12493 8177 12493 12386 12493 12385 12494 12387 12494 8177 12494 8175 12495 12390 12495 12391 12495 8179 12496 12392 12496 12393 12496 8178 12497 12395 12497 12396 12497 8175 12498 12391 12498 8179 12498 8178 12499 12396 12499 8177 12499 12397 12500 12398 12500 12399 12500 12398 12501 12400 12501 12401 12501 8295 12502 12402 12502 8294 12502 12403 12503 12399 12503 12401 12503 12403 12504 12404 12504 12405 12504 12406 12505 12399 12505 12403 12505 12406 12506 12397 12506 12399 12506 12401 12507 12402 12507 8295 12507 8296 12508 12404 12508 8295 12508 12403 12509 12408 12509 12407 12509 12409 12510 12408 12510 8296 12510 12403 12511 12405 12511 12408 12511 12405 12512 8296 12512 12408 12512 12406 12513 12407 12513 12410 12513 12406 12514 12410 12514 12411 12514 12415 12515 12413 12515 12414 12515 12415 12516 12416 12516 12413 12516 12415 12517 12417 12517 12416 12517 12416 12518 12417 12518 12418 12518 12410 12519 12419 12519 12411 12519 12412 12520 12420 12520 12414 12520 12412 12521 12398 12521 12420 12521 12412 12522 12400 12522 12398 12522 12400 12523 8299 12523 12402 12523 12402 12524 8299 12524 8294 12524 12226 12525 12097 12525 12101 12525 12219 12526 12097 12526 12226 12526 12421 12527 12338 12527 12354 12527 12354 12528 12340 12528 12341 12528 12421 12529 12354 12529 12356 12529 12421 12530 12356 12530 12225 12530 12225 12531 12101 12531 12421 12531 12421 12532 12101 12532 12335 12532 12063 12533 12065 12533 12328 12533 12328 12534 12065 12534 12091 12534 12246 12535 11746 12535 12359 12535 12237 12536 12238 12536 12289 12536 12367 12537 12239 12537 11727 12537 12367 12538 12287 12538 12289 12538 12289 12539 12239 12539 12367 12539 12249 12540 12248 12540 12246 12540 12329 12541 12328 12541 12092 12541 12330 12542 12331 12542 12093 12542 12331 12543 12095 12543 12093 12543 12101 12544 12333 12544 12335 12544 12421 12545 12336 12545 12337 12545 12421 12546 12335 12546 12336 12546 12406 12547 12411 12547 12419 12547 12406 12548 12419 12548 12417 12548 12417 12549 12414 12549 12397 12549 12417 12550 12415 12550 12414 12550 12420 12551 12397 12551 12414 12551 12396 12552 12422 12552 12386 12552 12396 12553 12423 12553 12422 12553 12427 12554 12426 12554 12428 12554 12428 12555 12429 12555 12427 12555 12429 12556 12428 12556 12430 12556 12431 12557 12432 12557 12430 12557 12431 12558 12433 12558 12432 12558 12433 12559 12431 12559 12434 12559 12390 12560 12434 12560 12391 12560 12433 12561 12389 12561 12432 12561 12425 12562 12436 12562 12437 12562 12425 12563 12424 12563 12436 12563 12394 12564 12393 12564 12436 12564 12436 12565 12393 12565 12438 12565 12437 12566 12439 12566 12440 12566 12392 12567 12391 12567 12439 12567 12440 12568 12439 12568 12434 12568 12427 12569 12385 12569 12435 12569 12426 12570 12427 12570 12435 12570 12440 12571 12431 12571 12426 12571 12440 12572 12426 12572 12425 12572 11174 12573 11172 12573 11051 12573 12441 12574 11244 12574 11245 12574 12442 12575 11307 12575 12443 12575 11297 12576 11299 12576 11298 12576 11297 12577 12252 12577 11299 12577 12443 12578 11307 12578 11305 12578 11307 12579 12442 12579 11308 12579 12444 12580 12252 12580 12296 12580 12445 12581 12446 12581 12447 12581 12448 12582 12449 12582 12450 12582 12454 12583 12453 12583 12455 12583 12454 12584 12455 12584 12456 12584 12457 12585 12456 12585 12458 12585 12457 12586 12458 12586 12459 12586 8253 12587 12464 12587 8252 12587 8253 12588 8254 12588 12465 12588 12465 12589 8254 12589 12466 12589 12293 12590 12291 12590 12446 12590 12470 12591 12283 12591 12471 12591 12472 12592 12471 12592 12282 12592 12472 12593 12282 12593 12305 12593 12473 12594 12305 12594 12317 12594 12474 12595 12317 12595 12475 12595 8251 12596 12480 12596 8250 12596 8251 12597 12481 12597 12480 12597 12462 12598 12482 12598 12478 12598 12462 12599 12461 12599 12482 12599 12472 12600 12450 12600 12449 12600 12470 12601 12449 12601 12486 12601 12283 12602 12280 12602 12471 12602 12471 12603 12280 12603 12282 12603 12487 12604 12474 12604 12476 12604 12318 12605 12477 12605 12475 12605 12318 12606 12256 12606 12255 12606 12479 12607 12255 12607 12489 12607 8250 12608 12480 12608 12489 12608 12253 12609 8249 12609 12489 12609 12463 12610 12466 12610 12460 12610 12462 12611 12463 12611 12460 12611 12460 12612 12490 12612 12461 12612 12461 12613 12468 12613 12459 12613 12491 12614 12492 12614 12454 12614 12454 12615 12492 12615 12493 12615 12454 12616 12493 12616 12453 12616 12492 12617 12494 12617 12493 12617 12496 12618 12445 12618 12497 12618 12496 12619 12497 12619 11247 12619 12442 12620 12498 12620 11308 12620 12448 12621 12494 12621 12499 12621 12499 12622 12495 12622 12500 12622 12501 12623 12499 12623 12494 12623 12441 12624 11245 12624 12497 12624 11247 12625 11308 12625 12498 12625 12442 12626 11302 12626 12444 12626 12502 12627 12442 12627 12296 12627 12464 12628 12478 12628 12481 12628 12479 12629 12478 12629 12488 12629 12488 12630 12478 12630 12482 12630 12477 12631 12488 12631 12483 12631 12477 12632 12483 12632 12476 12632 12487 12633 12484 12633 12474 12633 12487 12634 12458 12634 12456 12634 12484 12635 12487 12635 12456 12635 12453 12636 12485 12636 12455 12636 12449 12637 12447 12637 12486 12637 12296 12638 12314 12638 12502 12638 12446 12639 12496 12639 12293 12639 12473 12640 12472 12640 12305 12640 12472 12641 12473 12641 12450 12641 12479 12642 12488 12642 12318 12642 12479 12643 12489 12643 12480 12643 12495 12644 12447 12644 12500 12644 12502 12645 12496 12645 12498 12645 12442 12646 12502 12646 12498 12646 11247 12647 12498 12647 12496 12647 12468 12648 12457 12648 12459 12648 12494 12649 12448 12649 12452 12649 12466 12650 12490 12650 12460 12650 12490 12651 12468 12651 12461 12651 12493 12652 12494 12652 12452 12652 12291 12653 12315 12653 12446 12653 12503 12654 12024 12654 12020 12654 12503 12655 12033 12655 12045 12655 12503 12656 8217 12656 12033 12656 8228 12657 8227 12657 12505 12657 12505 12658 8227 12658 12506 12658 12507 12659 12505 12659 12506 12659 12506 12660 8227 12660 12508 12660 12508 12661 8227 12661 8226 12661 12510 12662 12509 12662 8225 12662 12508 12663 8226 12663 12509 12663 8225 12664 8224 12664 12510 12664 12510 12665 8224 12665 11986 12665 12511 12666 8223 12666 11985 12666 8223 12667 8222 12667 11985 12667 12512 12668 8222 12668 12513 12668 8219 12669 8218 12669 12514 12669 12505 12670 12516 12670 8228 12670 12505 12671 12517 12671 12516 12671 12505 12672 12518 12672 12517 12672 12505 12673 12519 12673 12518 12673 12505 12674 12507 12674 12519 12674 8228 12675 12516 12675 12520 12675 12520 12676 12521 12676 12522 12676 8230 12677 8229 12677 12520 12677 12523 12678 12521 12678 12516 12678 12524 12679 12525 12679 12526 12679 12518 12680 12519 12680 12527 12680 12528 12681 12529 12681 12527 12681 12524 12682 12516 12682 12525 12682 12530 12683 12528 12683 12532 12683 12526 12684 12527 12684 12533 12684 12529 12685 12533 12685 12527 12685 12525 12686 12517 12686 12518 12686 12516 12687 12517 12687 12525 12687 12524 12688 12526 12688 11157 12688 11152 12689 11155 12689 12529 12689 11139 12690 12529 12690 12530 12690 11159 12691 12522 12691 12523 12691 12533 12692 11155 12692 11157 12692 12526 12693 12533 12693 11157 12693 11150 12694 11152 12694 12529 12694 12529 12695 11155 12695 12533 12695 8230 12696 11159 12696 8231 12696 11156 12697 8231 12697 11158 12697 12534 12698 11312 12698 12535 12698 11312 12699 11310 12699 12535 12699 12535 12700 11310 12700 11236 12700 12536 12701 11236 12701 11234 12701 12537 12702 11232 12702 11231 12702 12536 12703 12541 12703 12535 12703 11312 12704 12534 12704 11315 12704 12539 12705 12542 12705 11318 12705 12538 12706 12540 12706 12547 12706 12550 12707 12549 12707 12551 12707 12543 12708 12548 12708 8286 12708 12542 12709 12543 12709 8286 12709 12549 12710 12534 12710 12551 12710 12548 12711 8287 12711 8286 12711 12548 12712 12546 12712 12545 12712 12501 12713 12494 12713 12554 12713 12550 12714 12551 12714 12553 12714 12548 12715 12545 12715 12556 12715 12557 12716 12467 12716 12555 12716 12555 12717 12467 12717 12469 12717 12469 12718 12466 12718 12558 12718 12466 12719 8254 12719 12558 12719 8287 12720 12556 12720 8254 12720 12552 12721 12541 12721 12554 12721 12557 12722 12550 12722 12553 12722 12550 12723 12557 12723 12555 12723 12491 12724 12467 12724 12557 12724 12552 12725 12554 12725 12492 12725 12553 12726 12552 12726 12557 12726 12492 12727 12557 12727 12552 12727 12554 12728 12494 12728 12492 12728 8173 12729 12561 12729 12562 12729 8171 12730 12565 12730 12566 12730 8169 12731 12568 12731 12569 12731 8174 12732 12570 12732 12560 12732 8173 12733 12562 12733 8172 12733 8172 12734 12564 12734 8171 12734 8171 12735 12566 12735 8170 12735 8169 12736 12570 12736 8174 12736 12572 12737 12574 12737 12573 12737 8290 12738 8291 12738 12571 12738 12576 12739 12577 12739 12578 12739 12571 12740 12580 12740 8290 12740 12578 12741 12573 12741 12576 12741 8289 12742 12580 12742 12578 12742 12582 12743 8293 12743 12581 12743 12582 12744 12577 12744 12583 12744 12579 12745 12583 12745 12577 12745 12583 12746 12579 12746 12584 12746 12587 12747 12586 12747 12588 12747 12593 12748 12592 12748 12583 12748 12586 12749 8292 12749 12588 12749 12589 12750 12590 12750 12591 12750 12592 12751 8293 12751 12583 12751 12593 12752 12591 12752 12592 12752 11984 12753 12014 12753 11162 12753 12507 12754 12528 12754 12519 12754 12507 12755 12532 12755 12528 12755 12531 12756 12532 12756 12508 12756 12019 12757 12515 12757 12020 12757 11226 12758 12537 12758 11231 12758 12441 12759 12537 12759 11230 12759 11316 12760 8285 12760 11313 12760 12019 12761 12514 12761 12515 12761 11985 12762 12513 12762 12512 12762 12512 12763 11987 12763 11985 12763 12506 12764 12532 12764 12507 12764 12579 12765 12575 12765 12584 12765 12584 12766 12575 12766 12593 12766 12585 12767 12591 12767 12575 12767 12575 12768 12591 12768 12593 12768 12570 12769 12594 12769 12560 12769 12600 12770 12601 12770 12599 12770 12604 12771 12600 12771 12605 12771 12606 12772 12605 12772 12607 12772 12564 12773 12607 12773 12565 12773 12606 12774 12563 12774 12604 12774 12603 12775 12562 12775 12561 12775 12601 12776 12559 12776 12560 12776 12568 12777 12567 12777 12608 12777 12610 12778 12608 12778 12609 12778 12566 12779 12565 12779 12611 12779 12611 12780 12565 12780 12607 12780 12612 12781 12611 12781 12607 12781 12603 12782 12561 12782 12602 12782 12602 12783 12559 12783 12601 12783 12610 12784 12599 12784 12598 12784 12610 12785 12612 12785 12599 12785 12600 12786 12612 12786 12605 12786 11113 12787 11111 12787 11379 12787 12613 12788 11111 12788 12614 12788 12615 12789 12614 12789 12616 12789 11109 12790 12618 12790 11110 12790 11109 12791 11107 12791 12618 12791 8238 12792 12620 12792 12618 12792 11110 12793 12620 12793 12614 12793 11111 12794 11110 12794 12614 12794 12619 12795 11105 12795 12621 12795 12619 12796 12621 12796 8239 12796 8236 12797 11387 12797 12622 12797 8236 12798 12623 12798 11387 12798 8236 12799 12624 12799 12623 12799 12623 12800 12624 12800 12625 12800 11161 12801 12625 12801 11145 12801 11161 12802 11160 12802 11387 12802 11145 12803 12626 12803 11146 12803 11145 12804 12625 12804 12626 12804 11146 12805 12627 12805 11148 12805 11146 12806 12626 12806 12627 12806 12628 12807 12629 12807 12630 12807 11151 12808 12633 12808 11153 12808 11151 12809 12631 12809 12633 12809 12627 12810 12629 12810 11148 12810 11153 12811 12634 12811 11154 12811 11153 12812 12633 12812 12634 12812 12633 12813 8232 12813 12634 12813 8231 12814 11156 12814 12635 12814 12634 12815 8232 12815 12635 12815 11385 12816 12622 12816 11387 12816 11381 12817 11379 12817 12622 12817 11379 12818 12617 12818 12622 12818 8202 12819 8261 12819 12637 12819 12639 12820 8262 12820 8263 12820 8263 12821 12641 12821 12640 12821 12643 12822 12641 12822 12644 12822 8266 12823 12645 12823 12644 12823 8266 12824 8198 12824 12645 12824 8266 12825 8267 12825 8198 12825 12646 12826 12647 12826 12648 12826 12637 12827 8261 12827 12638 12827 12638 12828 8262 12828 12639 12828 12643 12829 12644 12829 12645 12829 12648 12830 12647 12830 8269 12830 8192 12831 8129 12831 8128 12831 8128 12832 12649 12832 12650 12832 12654 12833 12653 12833 12655 12833 12654 12834 12655 12834 8126 12834 12651 12835 12653 12835 12656 12835 12656 12836 12653 12836 12654 12836 8099 12837 8120 12837 8122 12837 8099 12838 8124 12838 8101 12838 8107 12839 8100 12839 8106 12839 8097 12840 8109 12840 8110 12840 8098 12841 8111 12841 8112 12841 8098 12842 8112 12842 8113 12842 8099 12843 8113 12843 8114 12843 8115 12844 8131 12844 8127 12844 8165 12845 8164 12845 8162 12845 8140 53 8155 53 8151 53 8140 12846 8141 12846 8137 12846 8137 12847 8141 12847 8135 12847 8135 12848 8141 12848 8142 12848 8134 12849 8146 12849 8147 12849 8137 12850 8157 12850 8158 12850 8161 12851 8155 12851 8137 12851 8241 12852 8273 12852 8274 12852 8276 53 8240 53 8275 53 8239 12853 8277 12853 11394 12853 8241 12854 8274 12854 8240 12854 11394 12855 11392 12855 8238 12855 8238 12856 11392 12856 12620 12856 12620 12857 11392 12857 11393 12857 11404 53 12617 53 11401 53 11404 12858 8236 12858 12617 12858 11404 12859 11407 12859 8236 12859 8236 12860 11407 12860 12624 12860 12626 12861 8281 12861 8282 12861 12630 12862 8282 12862 11420 12862 11421 53 12628 53 12630 53 12632 12863 11422 12863 11416 12863 12633 12864 11416 12864 11417 12864 12620 12865 11393 12865 12616 12865 11417 12866 11419 12866 8232 12866 8232 12867 11419 12867 8231 12867 8231 12868 11419 12868 8284 12868 8229 12869 8286 12869 12581 12869 8228 12870 12581 12870 8293 12870 12588 12871 8172 12871 12590 12871 8172 12872 8292 12872 8173 12872 8173 12873 8292 12873 8217 12873 8174 12874 8218 12874 8219 12874 8221 12875 8222 12875 8174 12875 8174 12876 8222 12876 8169 12876 8171 12877 8226 12877 8227 12877 8293 12878 8171 12878 8228 12878 8288 12879 8287 12879 8289 12879 8253 12880 8216 12880 8254 12880 8253 53 8252 53 12027 53 12027 12881 8252 12881 12029 12881 12029 12882 8252 12882 8251 12882 12034 53 8251 53 8250 53 12038 53 8249 53 12076 53 12034 53 8250 53 12037 53 8249 12883 8248 12883 12076 12883 12073 53 8246 53 8245 53 8180 12884 8299 12884 8178 12884 12080 53 8246 53 12073 53 12073 53 8245 53 8207 53 8296 12885 8257 12885 8256 12885 8187 12886 12409 12886 8206 12886 8187 12887 8298 12887 12409 12887 8176 12888 8191 12888 8186 12888 8177 12889 8190 12889 8185 12889 8177 12890 8185 12890 8189 12890 8255 12891 8258 12891 8206 12891 8258 12892 8259 12892 8205 12892 8229 12893 12581 12893 8228 12893 8171 12894 12592 12894 8172 12894 8298 12895 8175 12895 12418 12895 12416 12896 12418 12896 8179 12896 12413 12897 8179 12897 8299 12897 12409 12898 8296 12898 8255 12898 8136 12899 8135 12899 8144 12899 8125 12900 8132 12900 8102 12900 8103 12901 8124 12901 8125 12901 8098 12902 8097 12902 8111 12902 11665 12903 11670 12903 11671 12903 11701 12904 12659 12904 11735 12904 12359 12905 11746 12905 11745 12905 12662 12906 12659 12906 11701 12906 12636 12907 12358 12907 12663 12907 8262 12908 12665 12908 12666 12908 12668 12909 12664 12909 12663 12909 11744 12910 12668 12910 12663 12910 8263 12911 12671 12911 12641 12911 8263 12912 12666 12912 12671 12912 12672 12913 11735 12913 12659 12913 12662 12914 12672 12914 12659 12914 12662 12915 12673 12915 12672 12915 12673 12916 12674 12916 12675 12916 12644 12917 12676 12917 8266 12917 12672 12918 12678 12918 12679 12918 12672 12919 12679 12919 12669 12919 12670 12920 12679 12920 12678 12920 12641 12921 12671 12921 12677 12921 12674 12922 12657 12922 11665 12922 12680 12923 11665 12923 12660 12923 11671 12924 12658 12924 12660 12924 12658 12925 11672 12925 12681 12925 12682 12926 12683 12926 8267 12926 12674 12927 11665 12927 12680 12927 12682 12928 12660 12928 12683 12928 12683 12929 12681 12929 12647 12929 8269 12930 12647 12930 12681 12930 8262 12931 8261 12931 12665 12931 8261 12932 12636 12932 12663 12932 12675 12933 12674 12933 12680 12933 12682 12934 12680 12934 12660 12934 12675 12935 12676 12935 12673 12935 12673 12936 12676 12936 12677 12936 12672 12937 12677 12937 12678 12937 12666 12938 12667 12938 12669 12938 12664 12939 12668 12939 12665 12939 8203 12940 8202 12940 12684 12940 12639 12941 12685 12941 12638 12941 12639 12942 12640 12942 12685 12942 12638 12943 12689 12943 12690 12943 12638 12944 12685 12944 12689 12944 12689 12945 12685 12945 12687 12945 12161 12946 12689 12946 12687 12946 12640 12947 12642 12947 12686 12947 12686 12948 12642 12948 12692 12948 12688 12949 12692 12949 12693 12949 12692 12950 12643 12950 12694 12950 12693 12951 12694 12951 12695 12951 12643 12952 12645 12952 12694 12952 12696 12953 12698 12953 12699 12953 12177 12954 12699 12954 12178 12954 12177 12955 12697 12955 12699 12955 8198 12956 8197 12956 12698 12956 12698 12957 8197 12957 12700 12957 12699 12958 12700 12958 12701 12958 8197 12959 12646 12959 12700 12959 12702 12960 12646 12960 12648 12960 12648 12961 8195 12961 12702 12961 12689 12962 12169 12962 12690 12962 12690 12963 12171 12963 12691 12963 12690 12964 12691 12964 12684 12964 12686 12965 12687 12965 12685 12965 12696 12966 12695 12966 12694 12966 12701 12967 12700 12967 12702 12967 12699 12968 12698 12968 12700 12968 8195 12969 12703 12969 12181 12969 12704 12970 12182 12970 12703 12970 12182 12971 12704 12971 12705 12971 12185 12972 12184 12972 12706 12972 12705 12973 12183 12973 12182 12973 12184 12974 12183 12974 12705 12974 12185 12975 12709 12975 12710 12975 12186 12976 12710 12976 11565 12976 12709 12977 12185 12977 12706 12977 10894 12978 11602 12978 12191 12978 11602 12979 12138 12979 10894 12979 10894 12980 12138 12980 12191 12980 11596 12981 12187 12981 12186 12981 11547 12982 10898 12982 12189 12982 12189 12983 10898 12983 12191 12983 10898 12984 10894 12984 12191 12984 11547 12985 11780 12985 12188 12985 11599 12986 11547 12986 12188 12986 12188 12987 12187 12987 11596 12987 11527 12988 11492 12988 11498 12988 11492 12989 11527 12989 11491 12989 8240 12990 8239 12990 12621 12990 12711 12991 8136 12991 12712 12991 8136 12992 12713 12992 8135 12992 8135 12993 12713 12993 12714 12993 8135 12994 12714 12994 12715 12994 8135 12995 12715 12995 12716 12995 8137 12996 12717 12996 12718 12996 8133 12997 12719 12997 12720 12997 8133 12998 12720 12998 12721 12998 8134 12999 12721 12999 12722 12999 8134 13000 12722 13000 12712 13000 8135 13001 12716 13001 8137 13001 8133 13002 12721 13002 8134 13002 8164 13003 8152 13003 12726 13003 12727 13004 11625 13004 12726 13004 12726 13005 11625 13005 8162 13005 12726 13006 12724 13006 12727 13006 8162 13007 11625 13007 8157 13007 8157 13008 11625 13008 12727 13008 8157 13009 12727 13009 12728 13009 12729 13010 8161 13010 12730 13010 12731 13011 8160 13011 12732 13011 12732 13012 8158 13012 12728 13012 12728 13013 8158 13013 8157 13013 8151 13014 8155 13014 12723 13014 12723 13015 8155 13015 12729 13015 8125 13016 11624 13016 8127 13016 8127 13017 12733 13017 12734 13017 12739 13018 12734 13018 12736 13018 8127 13019 12734 13019 12739 13019 12738 13020 8116 13020 8115 13020 8119 13021 12738 13021 12740 13021 8119 13022 8116 13022 12738 13022 12738 13023 12737 13023 12740 13023 12742 13024 8122 13024 12743 13024 8122 13025 8120 13025 12743 13025 11624 13026 8124 13026 12733 13026 11624 13027 8125 13027 8124 13027 8097 13028 12744 13028 8100 13028 8097 13029 12745 13029 12744 13029 12750 13030 8101 13030 8100 13030 12747 13031 8098 13031 12752 13031 12749 13032 8101 13032 12755 13032 12755 13033 8101 13033 12750 13033 11426 13034 8240 13034 11543 13034 11426 13035 11543 13035 11425 13035 8242 13036 11446 13036 11494 13036 11446 13037 8242 13037 8241 13037 11544 13038 11446 13038 8241 13038 11544 13039 11447 13039 11446 13039 11454 13040 11532 13040 11452 13040 11452 13041 11532 13041 8163 13041 8243 13042 11452 13042 8163 13042 8243 13043 11496 13043 11452 13043 8243 13044 11490 13044 11496 13044 8140 13045 11532 13045 12756 13045 12756 13046 11532 13046 11534 13046 8141 13047 12756 13047 12757 13047 8144 13048 12759 13048 12760 13048 12762 13049 8146 13049 8145 13049 12762 13050 12763 13050 8146 13050 8148 13051 12764 13051 12765 13051 8149 13052 12765 13052 11614 13052 8150 13053 11614 13053 12766 13053 8138 13054 8150 13054 12766 13054 8141 13055 12757 13055 8142 13055 8142 13056 12758 13056 8143 13056 8143 13057 12759 13057 8144 13057 8144 13058 12760 13058 8145 13058 8148 13059 12765 13059 8149 13059 11626 13060 8138 13060 11627 13060 11626 13061 11623 13061 8138 13061 8114 13062 8113 13062 12768 13062 12769 13063 8113 13063 8112 13063 12772 13064 8110 13064 8109 13064 12774 13065 8108 13065 12775 13065 12774 13066 12773 13066 8108 13066 12770 13067 8111 13067 12771 13067 8108 13068 8107 13068 12775 13068 12777 13069 8105 13069 11616 13069 12775 13070 8106 13070 12776 13070 8105 13071 8104 13071 11616 13071 11616 13072 8104 13072 12767 13072 12654 13073 8126 13073 12780 13073 12780 13074 8126 13074 12778 13074 12778 13075 12781 13075 12780 13075 12778 13076 12782 13076 12781 13076 12708 13077 12783 13077 12782 13077 12783 13078 12708 13078 12784 13078 12784 13079 12708 13079 8128 13079 12785 13080 12654 13080 12780 13080 12654 13081 12785 13081 12656 13081 12650 13082 11629 13082 12787 13082 12650 13083 11631 13083 11629 13083 11631 13084 12650 13084 12651 13084 12788 13085 11636 13085 11634 13085 12788 13086 11634 13086 12789 13086 12790 13087 12784 13087 12650 13087 8193 13088 8192 13088 12707 13088 8270 13089 8269 13089 11672 13089 12794 13090 8272 13090 12793 13090 12795 13091 12796 13091 12797 13091 12795 13092 12797 13092 12798 13092 12797 13093 12655 13093 12798 13093 12800 13094 12794 13094 12801 13094 12800 13095 8129 13095 12794 13095 8129 13096 12800 13096 12802 13096 8129 13097 12802 13097 12649 13097 12796 13098 12799 13098 12801 13098 12803 13099 12804 13099 11635 13099 11632 13100 12652 13100 11630 13100 11632 13101 12805 13101 12652 13101 12806 13102 12652 13102 12805 13102 12653 13103 12807 13103 12655 13103 12807 13104 12798 13104 12655 13104 12653 13105 12652 13105 12806 13105 12807 13106 12653 13106 12806 13106 10969 13107 11040 13107 12810 13107 12810 13108 11040 13108 11039 13108 8130 13109 12797 13109 12811 13109 10979 13110 12811 13110 12809 13110 11039 13111 10979 13111 12809 13111 11033 13112 12811 13112 11036 13112 11033 13113 11035 13113 12811 13113 10965 13114 10966 13114 12812 13114 12809 13115 12808 13115 11039 13115 8276 13116 8275 13116 12813 13116 11220 13117 8277 13117 12813 13117 12813 13118 8277 13118 8276 13118 11546 13119 11545 13119 11221 13119 11545 13120 12814 13120 11221 13120 11526 13121 11202 13121 11215 13121 11526 13122 11215 13122 11217 13122 12814 13123 11219 13123 11221 13123 11711 13124 10992 13124 10995 13124 11692 13125 10995 13125 11006 13125 10992 13126 11714 13126 11715 13126 10992 13127 11719 13127 10991 13127 12816 13128 11007 13128 11010 13128 11680 13129 12816 13129 11010 13129 11004 13130 11007 13130 12816 13130 11004 13131 12816 13131 11688 13131 10995 13132 11692 13132 11711 13132 10992 13133 11715 13133 11716 13133 12801 13134 12794 13134 12817 13134 12818 13135 12817 13135 12819 13135 12820 13136 12801 13136 12817 13136 11680 13137 12819 13137 11652 13137 12821 13138 11738 13138 11739 13138 12819 13139 11739 13139 11652 13139 12819 13140 12821 13140 11739 13140 12819 13141 12817 13141 12821 13141 11674 13142 11673 13142 11737 13142 12793 13143 12822 13143 12817 13143 11737 13144 12822 13144 11674 13144 11738 13145 12821 13145 12822 13145 12817 13146 12822 13146 12821 13146 12778 13147 12823 13147 12824 13147 11593 13148 12710 13148 11592 13148 11581 13149 11580 13149 11591 13149 11591 13150 12824 13150 12823 13150 12825 13151 12824 13151 12710 13151 12725 13152 12730 13152 12731 13152 12731 13153 12732 13153 12725 13153 12736 13154 12735 13154 12741 13154 12736 13155 12741 13155 12742 13155 12737 13156 12736 13156 12742 13156 12826 13157 12757 13157 11538 13157 11588 13158 12828 13158 12827 13158 11614 13159 12765 13159 11613 13159 12829 13160 12763 13160 12762 13160 12762 13161 12761 13161 12829 13161 12829 13162 12761 13162 11588 13162 12828 13163 12760 13163 12759 13163 12827 13164 12828 13164 12759 13164 12759 13165 12758 13165 12827 13165 12827 13166 12758 13166 12826 13166 11538 13167 12756 13167 11535 13167 11588 13168 11589 13168 12829 13168 11613 13169 11589 13169 11615 13169 12778 13170 12779 13170 12823 13170 11581 13171 12823 13171 11604 13171 11605 13172 11604 13172 12830 13172 11608 13173 11606 13173 11609 13173 12769 13174 12770 13174 11604 13174 11604 13175 12770 13175 12830 13175 12830 13176 12770 13176 11605 13176 11605 13177 12770 13177 12771 13177 12771 13178 12772 13178 11584 13178 11586 13179 12773 13179 11606 13179 12773 13180 12774 13180 11606 13180 11608 13181 12774 13181 12775 13181 12776 13182 11609 13182 11608 13182 12787 13183 12788 13183 12831 13183 12787 13184 12831 13184 12783 13184 12834 13185 12831 13185 12835 13185 12786 13186 12835 13186 12789 13186 12835 13187 12786 13187 12785 13187 12834 13188 12832 13188 12831 13188 12787 13189 12783 13189 12790 13189 12783 13190 12784 13190 12790 13190 12835 13191 12831 13191 12789 13191 12833 13192 12781 13192 12783 13192 12781 13193 12833 13193 12834 13193 12835 13194 12781 13194 12834 13194 12650 13195 12787 13195 12790 13195 12807 13196 12806 13196 12836 13196 12800 13197 12799 13197 12838 13197 12839 13198 12799 13198 12795 13198 10953 13199 10965 13199 12840 13199 10956 13200 12840 13200 12841 13200 11012 13201 12841 13201 11680 13201 11012 13202 11024 13202 12841 13202 12812 13203 12808 13203 12842 13203 12801 13204 12820 13204 12844 13204 12796 13205 12801 13205 12844 13205 12820 13206 12818 13206 12845 13206 12841 13207 12840 13207 12846 13207 12818 13208 11680 13208 12846 13208 12846 13209 11680 13209 12841 13209 11024 13210 10956 13210 12841 13210 10956 13211 10951 13211 12840 13211 12840 13212 12842 13212 12843 13212 12843 13213 12844 13213 12845 13213 12846 13214 12843 13214 12845 13214 12803 13215 12649 13215 12802 13215 12804 13216 12838 13216 12837 13216 11221 13217 12813 13217 11546 13217 12712 13218 12848 13218 12847 13218 12849 13219 12721 13219 12720 13219 12851 13220 12714 13220 12713 13220 12853 13221 12854 13221 12717 13221 12850 13222 12718 13222 12854 13222 12719 13223 12850 13223 12720 13223 12713 13224 12711 13224 12851 13224 12744 13225 12855 13225 12751 13225 12744 13226 12745 13226 12856 13226 12856 13227 12746 13227 12857 13227 12746 13228 12747 13228 12857 13228 12857 13229 12747 13229 12752 13229 12752 13230 12748 13230 12858 13230 12859 13231 12748 13231 12753 13231 12859 13232 12753 13232 12860 13232 12860 13233 12754 13233 12749 13233 12860 13234 12749 13234 12861 13234 12749 13235 12755 13235 12861 13235 12861 13236 12755 13236 12750 13236 12862 13237 12861 13237 12750 13237 12750 13238 12751 13238 12862 13238 12853 13239 12848 13239 12854 13239 12850 13240 12848 13240 12849 13240 12854 13241 12848 13241 12850 13241 12856 13242 12857 13242 12855 13242 12857 13243 12858 13243 12855 13243 12862 13244 12858 13244 12859 13244 12859 13245 12860 13245 12862 13245 11552 13246 12863 13246 12864 13246 11568 13247 11552 13247 12864 13247 11569 13248 12864 13248 12865 13248 11556 13249 11558 13249 12866 13249 11554 13250 11556 13250 12866 13250 12864 13251 12863 13251 12866 13251 12865 13252 12864 13252 12866 13252 12868 13253 11369 13253 11562 13253 11369 13254 12867 13254 11367 13254 11368 13255 11367 13255 12869 13255 11368 13256 12869 13256 11597 13256 12869 13257 12868 13257 11563 13257 11562 13258 11563 13258 12868 13258 12867 13259 12868 13259 11367 13259 12870 13260 11374 13260 11371 13260 11371 13261 11374 13261 11376 13261 11375 13262 11374 13262 12871 13262 11373 13263 12871 13263 11370 13263 11557 13264 12873 13264 11567 13264 11567 13265 12873 13265 12874 13265 11550 13266 12874 13266 12875 13266 11553 13267 12875 13267 12872 13267 11555 13268 11553 13268 12872 13268 12873 13269 12872 13269 12874 13269 12874 13270 12872 13270 12875 13270 12876 13271 10009 13271 10001 13271 12880 13272 12881 13272 12882 13272 12882 13273 12881 13273 12883 13273 12883 13274 12881 13274 12884 13274 12892 13275 12891 13275 12880 13275 12882 13276 12892 13276 12880 13276 12885 13277 12887 13277 12888 13277 8483 13278 8484 13278 10001 13278 8479 13279 10006 13279 8477 13279 12877 13280 12893 13280 10004 13280 12877 13281 8480 13281 10009 13281 12877 13282 12879 13282 12893 13282 12879 13283 12876 13283 12893 13283 12878 13284 12877 13284 12876 13284 12893 13285 10001 13285 10004 13285 8479 13286 8339 13286 8480 13286 8481 13287 8341 13287 10009 13287 8482 13288 8344 13288 10009 13288 8482 13289 8341 13289 8344 13289 8479 13290 8338 13290 8339 13290 8341 13291 8482 13291 10009 13291 8484 13292 8478 13292 10004 13292 10009 13293 8480 13293 8481 13293 8477 13294 10004 13294 8478 13294 8335 13295 8338 13295 8477 13295 12888 13296 12890 13296 12878 13296 12878 13297 12890 13297 12892 13297 12892 13298 12879 13298 12878 13298 8347 13299 12881 13299 12880 13299 12881 13300 8347 13300 8346 13300 12884 13301 8346 13301 8344 13301 12884 13302 8344 13302 12886 13302 12891 13303 8338 13303 8335 13303 8339 13304 12891 13304 12889 13304 12887 13305 8339 13305 12889 13305 8341 13306 12887 13306 12886 13306 12884 13307 12881 13307 8346 13307 10029 13308 12895 13308 10028 13308 12896 13309 12897 13309 12898 13309 12897 13310 12896 13310 12899 13310 12900 13311 12899 13311 12901 13311 12902 13312 12903 13312 12904 13312 12902 13313 12904 13313 12905 13313 12895 13314 12894 13314 10033 13314 12894 13315 12895 13315 10029 13315 12895 13316 12910 13316 12894 13316 12910 13317 12913 13317 12912 13317 12910 13318 12895 13318 12913 13318 12911 13319 12894 13319 12910 13319 12894 13320 10029 13320 10030 13320 12894 13321 10032 13321 10033 13321 8473 13322 8472 13322 8315 13322 10032 13323 8330 13323 8475 13323 8315 13324 10031 13324 8473 13324 10028 13325 10033 13325 8475 13325 10029 13326 8476 13326 8471 13326 10030 13327 8470 13327 8472 13327 8330 13328 10032 13328 8316 13328 8311 13329 8315 13329 8472 13329 12902 13330 12912 13330 12900 13330 12900 13331 12912 13331 12913 13331 12912 13332 12907 13332 12909 13332 12909 13333 12913 13333 12912 13333 12897 13334 12900 13334 12913 13334 12905 13335 12912 13335 12902 13335 12896 13336 12898 13336 8310 13336 12901 13337 8332 13337 8330 13337 12901 13338 8330 13338 12903 13338 8311 13339 12908 13339 12906 13339 12901 13340 12899 13340 8332 13340 12914 13341 10446 13341 10445 13341 10447 13342 10446 13342 12915 13342 10447 13343 12915 13343 10449 13343 12923 13344 12921 13344 12924 13344 12925 13345 12926 13345 12927 13345 12919 13346 12921 13346 12923 13346 12928 13347 8364 13347 12929 13347 12929 13348 12930 13348 12931 13348 12914 13349 12933 13349 12915 13349 12918 13350 12933 13350 12919 13350 12918 13351 12917 13351 12914 13351 12933 13352 12917 13352 12919 13352 12914 13353 12917 13353 12933 13353 12933 13354 12918 13354 12915 13354 12914 13355 10445 13355 12916 13355 12914 13356 12915 13356 10446 13356 12934 13357 8366 13357 8367 13357 8367 13358 8371 13358 8605 13358 12934 13359 8367 13359 8606 13359 8602 13360 8376 13360 8600 13360 8608 13361 8599 13361 8362 13361 8605 13362 12934 13362 8606 13362 8600 13363 8599 13363 10447 13363 8602 13364 10449 13364 10451 13364 8605 13365 10451 13365 10445 13365 12934 13366 8605 13366 10445 13366 10446 13367 8608 13367 8609 13367 10446 13368 8609 13368 10445 13368 8605 13369 8602 13369 10451 13369 8376 13370 8374 13370 8371 13370 12917 13371 12919 13371 12925 13371 12928 13372 12929 13372 12917 13372 12928 13373 12917 13373 12925 13373 8353 13374 12920 13374 8354 13374 12924 13375 8376 13375 8371 13375 12924 13376 8371 13376 12926 13376 12932 13377 12930 13377 8362 13377 12924 13378 12921 13378 8376 13378 12932 13379 8354 13379 12920 13379 12935 13380 10450 13380 10452 13380 10455 13381 12936 13381 12937 13381 12938 13382 12939 13382 12940 13382 12940 13383 12939 13383 12941 13383 12941 13384 12939 13384 12942 13384 12943 13385 12942 13385 12944 13385 12948 13386 12947 13386 12949 13386 12950 13387 12949 13387 12951 13387 8578 13388 8577 13388 10454 13388 12952 13389 12953 13389 12937 13389 12937 13390 12953 13390 12954 13390 12954 13391 12935 13391 12937 13391 12935 13392 10452 13392 12937 13392 10452 13393 10454 13393 12937 13393 12955 13394 8388 13394 8576 13394 8598 13395 8388 13395 8358 13395 8603 13396 8604 13396 8373 13396 12957 13397 8384 13397 8581 13397 8381 13398 12957 13398 8581 13398 8582 13399 12956 13399 8377 13399 8578 13400 12955 13400 8385 13400 8579 13401 8578 13401 10454 13401 8579 13402 12955 13402 8578 13402 8578 13403 12955 13403 8577 13403 8576 13404 8388 13404 8598 13404 8598 13405 8356 13405 8601 13405 10454 13406 12957 13406 8581 13406 8576 13407 8598 13407 10448 13407 10455 13408 8577 13408 8576 13408 8577 13409 10455 13409 10454 13409 12956 13410 12957 13410 10452 13410 10452 13411 8603 13411 12956 13411 10450 13412 8603 13412 10452 13412 8381 13413 12957 13413 8369 13413 8375 13414 8373 13414 8604 13414 8369 13415 8384 13415 8381 13415 8385 13416 8386 13416 12955 13416 12941 13417 12953 13417 12952 13417 12940 13418 12941 13418 12952 13418 12954 13419 12948 13419 12950 13419 12950 13420 12940 13420 12952 13420 8388 13421 12938 13421 8358 13421 12942 13422 8384 13422 12944 13422 12951 13423 12949 13423 8356 13423 8375 13424 12949 13424 12947 13424 12945 13425 8372 13425 8373 13425 8372 13426 12945 13426 8369 13426 8369 13427 12945 13427 12944 13427 8384 13428 8369 13428 12944 13428 8375 13429 12947 13429 8373 13429 12942 13430 12939 13430 8385 13430 8356 13431 8358 13431 12951 13431 12951 13432 8358 13432 12938 13432 12964 13433 12965 13433 12966 13433 12966 13434 12967 13434 12958 13434 12958 13435 12967 13435 12968 13435 12962 13436 12972 13436 12965 13436 12965 13437 12964 13437 12962 13437 12962 13438 12964 13438 12970 13438 12973 13439 12972 13439 12971 13439 12969 13440 12977 13440 12966 13440 12969 13441 12978 13441 12976 13441 12964 13442 12966 13442 12980 13442 12980 13443 12966 13443 12979 13443 12981 13444 12963 13444 12980 13444 12961 13445 12974 13445 12973 13445 12961 13446 12980 13446 12963 13446 12965 13447 12972 13447 12974 13447 12968 13448 12967 13448 12978 13448 12979 13449 12959 13449 12960 13449 12976 13450 12959 13450 12977 13450 12959 13451 12976 13451 12978 13451 12978 13452 12960 13452 12959 13452 12983 13453 12985 13453 12980 13453 12980 13454 12985 13454 12986 13454 12987 13455 12980 13455 12986 13455 12990 13456 12981 13456 12989 13456 12990 13457 12991 13457 12981 13457 12981 13458 12991 13458 12992 13458 12994 13459 12995 13459 12982 13459 12982 13460 12995 13460 12996 13460 12997 13461 12979 13461 12982 13461 12997 13462 12998 13462 12979 13462 12979 13463 12998 13463 12999 13463 13000 13464 12979 13464 12999 13464 12979 13465 12984 13465 12980 13465 12981 13466 12992 13466 12982 13466 12987 13467 13004 13467 13005 13467 12988 13468 13005 13468 13006 13468 12990 13469 13007 13469 13008 13469 12991 13470 13008 13470 13009 13470 12992 13471 13009 13471 13010 13471 12994 13472 13011 13472 13012 13472 12996 13473 13013 13473 13014 13473 12998 13474 13015 13474 13016 13474 13000 13475 13017 13475 13018 13475 12983 13476 12984 13476 13002 13476 12989 13477 13007 13477 12990 13477 12991 13478 13009 13478 12992 13478 12995 13479 13013 13479 12996 13479 12998 13480 13016 13480 12999 13480 13000 13481 13018 13481 12984 13481 13004 13482 13001 13482 13002 13482 13004 13483 13003 13483 13001 13483 13009 13484 13008 13484 13006 13484 13008 13485 13007 13485 13006 13485 13024 13486 13022 13486 13015 13486 13014 13487 13011 13487 13025 13487 13026 13488 13025 13488 13011 13488 13026 13489 13011 13489 13027 13489 13021 13490 13002 13490 13019 13490 13032 13491 13033 13491 13027 13491 13035 13492 13020 13492 13019 13492 13037 13493 13036 13493 13028 13493 13037 13494 13028 13494 13025 13494 13039 13495 13040 13495 13041 13495 13024 13496 13014 13496 13036 13496 13044 13497 13045 13497 13046 13497 13050 13498 13021 13498 13034 13498 13038 13499 13010 13499 13051 13499 13021 13500 13049 13500 13002 13500 13021 13501 13050 13501 13049 13501 13049 13502 13004 13502 13002 13502 13031 13503 13030 13503 13051 13503 13006 13504 13040 13504 13051 13504 13051 13505 13030 13505 13038 13505 13034 13506 13048 13506 13047 13506 13045 13507 13044 13507 13042 13507 13039 13508 13042 13508 13029 13508 13037 13509 13033 13509 13036 13509 13035 13510 13052 13510 13034 13510 13052 13511 13019 13511 13023 13511 13029 13512 13032 13512 13038 13512 13045 13513 13042 13513 13043 13513 13044 13514 13046 13514 13048 13514 13034 13515 13020 13515 13035 13515 13052 13516 13022 13516 13024 13516 13034 13517 13052 13517 13053 13517 13054 13518 13052 13518 13036 13518 13054 13519 13033 13519 13055 13519 13055 13520 13032 13520 13029 13520 13044 13521 13029 13521 13042 13521 13053 13522 13044 13522 13034 13522 13059 13523 13060 13523 13061 13523 13062 13524 13068 13524 13067 13524 13067 13525 13069 13525 13064 13525 13066 13526 13070 13526 13060 13526 13073 13527 13072 13527 13071 13527 13067 13528 13074 13528 13069 13528 13070 13529 13077 13529 13073 13529 13076 13530 13078 13530 13074 13530 13080 13531 13053 13531 13078 13531 13081 13532 13061 13532 13071 13532 13060 13533 13071 13533 13061 13533 13064 13534 13069 13534 13065 13534 13069 13535 13070 13535 13066 13535 13073 13536 13076 13536 13072 13536 13075 13537 13083 13537 13070 13537 13083 13538 13079 13538 13077 13538 13077 13539 13055 13539 13044 13539 13077 13540 13044 13540 13080 13540 13084 13541 13085 13541 13086 13541 13087 13542 13085 13542 13084 13542 13088 13543 13086 13543 13085 13543 13064 13544 13065 13544 13089 13544 13068 13545 13090 13545 13091 13545 13092 13546 13088 13546 13094 13546 13094 13547 13085 13547 13095 13547 13095 13548 13087 13548 13097 13548 13097 13549 13087 13549 13096 13549 13096 13550 13084 13550 13098 13550 13099 13551 13084 13551 13093 13551 13093 13552 13057 13552 13056 13552 13093 13553 13092 13553 13057 13553 13063 13554 13089 13554 13094 13554 13082 13555 13096 13555 13081 13555 13082 13556 13091 13556 13097 13556 13095 13557 13090 13557 13062 13557 13094 13558 13062 13558 13063 13558 13089 13559 13065 13559 13092 13559 13099 13560 13093 13560 13060 13560 13100 13561 13101 13561 13102 13561 13103 13562 13104 13562 13102 13562 13105 13563 13106 13563 13107 13563 13107 13564 13106 13564 13108 13564 13108 13565 13100 13565 13102 13565 13108 13566 13102 13566 13104 13566 13109 13567 13104 13567 13103 13567 13105 13568 13107 13568 13109 13568 13110 13569 13111 13569 13112 13569 13113 13570 13110 13570 13112 13570 13121 13571 13122 13571 13123 13571 13119 13572 13121 13572 13115 13572 13121 13573 13119 13573 13124 13573 13125 13574 13113 13574 13121 13574 13121 13575 13123 13575 13125 13575 13127 13576 13117 13576 13114 13576 13128 13577 13114 13577 13116 13577 13129 13578 13111 13578 13110 13578 13130 13579 13110 13579 13125 13579 13132 13580 13123 13580 13122 13580 13128 13581 13112 13581 13129 13581 13129 13582 13110 13582 13135 13582 13132 13583 13122 13583 13133 13583 13133 13584 13124 13584 13136 13584 13136 13585 13124 13585 13134 13585 13131 13586 13132 13586 13133 13586 13128 13587 13129 13587 13127 13587 13135 13588 13137 13588 13129 13588 13139 13589 13136 13589 13140 13589 13136 13590 13141 13590 13133 13590 13131 13591 13142 13591 13143 13591 13137 13592 13135 13592 13144 13592 13137 13593 13144 13593 13145 13593 13127 13594 13145 13594 13146 13594 13126 13595 13146 13595 13147 13595 13131 13596 13143 13596 13135 13596 13126 13597 13148 13597 13136 13597 13144 13598 13150 13598 13145 13598 13151 13599 13152 13599 13141 13599 13152 13600 13142 13600 13138 13600 13135 13601 13153 13601 13144 13601 13155 13602 13141 13602 13139 13602 13155 13603 13157 13603 13141 13603 13141 13604 13157 13604 13151 13604 13152 13605 13158 13605 13159 13605 13142 13606 13159 13606 13160 13606 13143 13607 13161 13607 13162 13607 13153 13608 13162 13608 13163 13608 13144 13609 13163 13609 13164 13609 13145 13610 13165 13610 13166 13610 13154 13611 13167 13611 13168 13611 13147 13612 13168 13612 13169 13612 13140 13613 13170 13613 13156 13613 13139 13614 13140 13614 13156 13614 13152 13615 13159 13615 13142 13615 13142 13616 13160 13616 13149 13616 13149 13617 13161 13617 13143 13617 13144 13618 13164 13618 13150 13618 13150 13619 13165 13619 13145 13619 13147 13620 13169 13620 13148 13620 13148 13621 13170 13621 13140 13621 13170 13622 13171 13622 13156 13622 13170 13623 13169 13623 13173 13623 13175 13624 13168 13624 13167 13624 13176 13625 13167 13625 13166 13625 13180 13626 13163 13626 13162 13626 13182 13627 13161 13627 13183 13627 13184 13628 13186 13628 13157 13628 13159 13629 13187 13629 13188 13629 13160 13630 13188 13630 13183 13630 13158 13631 13187 13631 13159 13631 13180 13632 13179 13632 13163 13632 13179 13633 13178 13633 13164 13633 13155 13634 13156 13634 13185 13634 12963 13635 13106 13635 13108 13635 13106 13636 12963 13636 13107 13636 13108 13637 13109 13637 12961 13637 12961 13638 13189 13638 13105 13638 13107 13639 12961 13639 13105 13639 12963 13640 12961 13640 13107 13640 12961 13641 12963 13641 13108 13641 13190 13642 13191 13642 13192 13642 13194 13643 13198 13643 13199 13643 13200 13644 13199 13644 13198 13644 13203 13645 13202 13645 13204 13645 13192 13646 13191 13646 13202 13646 13196 13647 13202 13647 13191 13647 13202 13648 13194 13648 13204 13648 13199 13649 13204 13649 13194 13649 13207 13650 13204 13650 13206 13650 13208 13651 13209 13651 13203 13651 13203 13652 13209 13652 13210 13652 13204 13653 12961 13653 13203 13653 13204 13654 12963 13654 12961 13654 12963 13655 13207 13655 13208 13655 12961 13656 12963 13656 13208 13656 13105 13657 13189 13657 13172 13657 13108 13658 13172 13658 13109 13658 13172 13659 13108 13659 13185 13659 13185 13660 13108 13660 13205 13660 13183 13661 13194 13661 13193 13661 13182 13662 13193 13662 13195 13662 13181 13663 13195 13663 13197 13663 13181 13664 13103 13664 13180 13664 13180 13665 13101 13665 13179 13665 13191 13666 13101 13666 13100 13666 13205 13667 13108 13667 13213 13667 13108 13668 13106 13668 13213 13668 13106 13669 13171 13669 13214 13669 13214 13670 13171 13670 13206 13670 13208 13671 13173 13671 13174 13671 13209 13672 13174 13672 13175 13672 13212 13673 13177 13673 13178 13673 13206 13674 13173 13674 13208 13674 13207 13675 13206 13675 13208 13675 13208 13676 13174 13676 13209 13676 13211 13677 13177 13677 13212 13677 13183 13678 13188 13678 13194 13678 13188 13679 13187 13679 13198 13679 13187 13680 13186 13680 13200 13680 13186 13681 13184 13681 13199 13681 13184 13682 13185 13682 13205 13682 13102 13683 12959 13683 13103 13683 13103 13684 12959 13684 13101 13684 13212 13685 12960 13685 12959 13685 13201 13686 12959 13686 13202 13686 13215 13687 13216 13687 13217 13687 13215 13688 13219 13688 13220 13688 13221 13689 13217 13689 13222 13689 13223 13690 13218 13690 13224 13690 13225 13691 13227 13691 13226 13691 13216 13692 13228 13692 13229 13692 13216 13693 13215 13693 13228 13693 13216 13694 13229 13694 13230 13694 13226 13695 13224 13695 13218 13695 13221 13696 13219 13696 13217 13696 13232 13697 13233 13697 13219 13697 13231 13698 13226 13698 13234 13698 13225 13699 13234 13699 13227 13699 13236 13700 13237 13700 13238 13700 13241 13701 13242 13701 13243 13701 13244 13702 13237 13702 13241 13702 13233 13703 13247 13703 13246 13703 13251 13704 13250 13704 13252 13704 13246 13705 13243 13705 13235 13705 13228 13706 13246 13706 13235 13706 13251 13707 13252 13707 13243 13707 13242 13708 13241 13708 13237 13708 13244 13709 13254 13709 13255 13709 13255 13710 13256 13710 13257 13710 13258 13711 13239 13711 13240 13711 13245 13712 13238 13712 13237 13712 13242 13713 13235 13713 13243 13713 13259 13714 13260 13714 13261 13714 13260 13715 13262 13715 13263 13715 13264 13716 13263 13716 13265 13716 13265 13717 13268 13717 13269 13717 13264 13718 13269 13718 13270 13718 13260 13719 13264 13719 13270 13719 13273 13720 13266 13720 13265 13720 13263 13721 13272 13721 13265 13721 13277 13722 13280 13722 13281 13722 13281 13723 13282 13723 13283 13723 7949 13724 13284 13724 7948 13724 13279 13725 7949 13725 7950 13725 13278 13726 13266 13726 13275 13726 13260 13727 13270 13727 13271 13727 13287 13728 13268 13728 13267 13728 13288 13729 13270 13729 13269 13729 13266 13730 13268 13730 13265 13730 13279 13731 13275 13731 13281 13731 13291 13732 13290 13732 13292 13732 13290 13733 13293 13733 13292 13733 13296 13734 13294 13734 13292 13734 13294 13735 13298 13735 13292 13735 13240 13736 13298 13736 13294 13736 13299 13737 13255 13737 13257 13737 13302 13738 13301 13738 13303 13738 13304 13739 13302 13739 13303 13739 13304 13740 13305 13740 13302 13740 13304 13741 13306 13741 13305 13741 13309 13742 13310 13742 13308 13742 13312 13743 13311 13743 13313 13743 13295 13744 13315 13744 13258 13744 13236 13745 13316 13745 13317 13745 13320 13746 13318 13746 13319 13746 13236 13747 13317 13747 13318 13747 13322 13748 13323 13748 13324 13748 13325 13749 13326 13749 13327 13749 13332 13750 13322 13750 13331 13750 13332 13751 13323 13751 13322 13751 13333 13752 13327 13752 13322 13752 13320 13753 13325 13753 13334 13753 7945 13754 13313 13754 13335 13754 13313 13755 13336 13755 13322 13755 13341 13756 13342 13756 13339 13756 13339 13757 13342 13757 13340 13757 13344 13758 13341 13758 13345 13758 13346 13759 13344 13759 13345 13759 13345 13760 13348 13760 13347 13760 13347 13761 13348 13761 13349 13761 13349 13762 13348 13762 13310 13762 13310 13763 13350 13763 13349 13763 13311 13764 13310 13764 13314 13764 13348 13765 13353 13765 13314 13765 13347 13766 13356 13766 13346 13766 13356 13767 13358 13767 13357 13767 13358 13768 13356 13768 13359 13768 13358 13769 13359 13769 13352 13769 13352 13770 13359 13770 13349 13770 13305 13771 13360 13771 13307 13771 13363 13772 13362 13772 13364 13772 13364 13773 13362 13773 13361 13773 13366 13774 13364 13774 13367 13774 13307 13775 13302 13775 13305 13775 13368 13776 13369 13776 13322 13776 13369 13777 13333 13777 13322 13777 13333 13778 13370 13778 13371 13778 13348 13779 13345 13779 13327 13779 13327 13780 13339 13780 13334 13780 13370 13781 13336 13781 13353 13781 13338 13782 13337 13782 13314 13782 13314 13783 13337 13783 13313 13783 13335 13784 13338 13784 13355 13784 13354 13785 13335 13785 13355 13785 13353 13786 13348 13786 13371 13786 13359 13787 13356 13787 13349 13787 13349 13788 13356 13788 13347 13788 13370 13789 13333 13789 13369 13789 13370 13790 13369 13790 13336 13790 13336 13791 13369 13791 13368 13791 13372 13792 13377 13792 13379 13792 13382 13793 13384 13793 13383 13793 13377 13794 13375 13794 13385 13794 13386 13795 13387 13795 13388 13795 13394 13796 8088 13796 7943 13796 8087 13797 13396 13797 8085 13797 13397 13798 8087 13798 8088 13798 13397 13799 8088 13799 13394 13799 13387 13800 13396 13800 13388 13800 13388 13801 13396 13801 13395 13801 13398 13802 13386 13802 13399 13802 13400 13803 13398 13803 13399 13803 13389 13804 13402 13804 13386 13804 13395 13805 13397 13805 13390 13805 13403 13806 13404 13806 13405 13806 13404 13807 13406 13807 13405 13807 13406 13808 13411 13808 13409 13808 13412 13809 13409 13809 13411 13809 13409 13810 13412 13810 13382 13810 13382 13811 13412 13811 13384 13811 13413 13812 13414 13812 13415 13812 13414 13813 13417 13813 13415 13813 13415 13814 13417 13814 13418 13814 13423 6 13421 6 13424 6 13424 13815 13425 13815 13426 13815 13424 13816 13427 13816 13425 13816 13407 13817 13427 13817 13408 13817 13394 13818 13403 13818 13405 13818 13394 13819 13405 13819 13429 13819 13430 13820 13431 13820 13432 13820 13433 13821 13431 13821 13434 13821 13435 13822 13434 13822 13436 13822 13433 13823 13434 13823 13435 13823 13437 13824 13436 13824 13438 13824 13438 13825 13436 13825 13439 13825 13439 13826 13441 13826 13440 13826 13440 13827 13441 13827 13442 13827 13444 13828 13445 13828 13446 13828 13446 13829 13447 13829 13444 13829 13444 13830 13449 13830 13440 13830 13444 13831 13448 13831 13450 13831 13410 13832 13429 13832 13405 13832 13410 13833 13405 13833 13406 13833 8090 13834 13451 13834 13425 13834 13453 13835 13425 13835 13440 13835 13440 13836 13428 13836 13438 13836 13450 13837 13432 13837 13454 13837 13454 13838 13432 13838 13455 13838 13456 13839 13454 13839 13457 13839 13455 13840 13457 13840 13454 13840 13460 13841 13459 13841 13461 13841 13462 13842 13460 13842 13461 13842 13426 13843 13423 13843 13424 13843 13426 13844 13463 13844 13423 13844 13426 13845 13465 13845 13463 13845 13466 13846 13467 13846 13465 13846 13466 13847 13468 13847 13467 13847 13469 13848 13470 13848 13464 13848 13464 13849 13471 13849 13423 13849 13461 13850 13473 13850 13462 13850 13475 13851 13474 13851 13469 13851 13476 13852 13421 13852 13477 13852 13422 13853 13478 13853 13477 13853 13479 13854 13480 13854 13478 13854 13479 13855 13481 13855 13480 13855 13481 13856 13482 13856 13480 13856 13480 13857 13482 13857 13483 13857 13420 13858 13413 13858 13415 13858 13425 13859 13466 13859 13426 13859 13444 13860 13460 13860 13463 13860 13454 13861 13444 13861 13450 13861 13454 13862 13456 13862 13444 13862 13444 13863 13456 13863 13460 13863 13465 13864 8090 13864 13453 13864 13453 13865 13486 13865 13487 13865 13485 13866 13453 13866 13440 13866 13452 13867 13468 13867 13425 13867 13451 13868 13467 13868 13452 13868 13465 13869 13467 13869 13451 13869 13473 13870 13475 13870 13462 13870 13486 13871 13453 13871 13484 13871 13383 13872 13488 13872 13489 13872 13489 13873 13490 13873 13372 13873 13491 13874 13492 13874 13493 13874 13494 13875 13492 13875 13491 13875 13494 13876 13495 13876 13492 13876 13373 13877 13491 13877 13493 13877 9092 13878 13496 13878 13493 13878 13373 13879 13493 13879 13496 13879 13373 13880 13496 13880 13497 13880 13497 13881 13498 13881 13373 13881 13499 13882 13500 13882 13501 13882 13499 13883 13501 13883 13502 13883 13503 13884 13499 13884 13502 13884 13500 13885 13505 13885 13501 13885 13506 13886 9112 13886 13505 13886 13505 13887 9112 13887 13501 13887 13503 13888 13502 13888 13508 13888 13387 13889 13499 13889 13396 13889 13510 13890 8085 13890 13396 13890 13367 13891 13306 13891 13483 13891 13367 13892 13361 13892 13360 13892 13367 6 13364 6 13361 6 13360 13893 13305 13893 13306 13893 13483 13894 13416 13894 13476 13894 13477 13895 13480 13895 13483 13895 13510 13896 13488 13896 8085 13896 13510 13897 13511 13897 13488 13897 13511 13898 13510 13898 13512 13898 13509 13899 13513 13899 13512 13899 13488 13900 13383 13900 8085 13900 13384 13901 13403 13901 7943 13901 13384 13902 13412 13902 13403 13902 13404 13903 13412 13903 13411 13903 13500 13904 13387 13904 13393 13904 13516 13905 13517 13905 13401 13905 13518 13906 13519 13906 13516 13906 13516 13907 13522 13907 13523 13907 13524 13908 13523 13908 13525 13908 13520 13909 13515 13909 13521 13909 13516 13910 13524 13910 13517 13910 13524 13911 13521 13911 13517 13911 13253 13912 13526 13912 13241 13912 13253 13913 13528 13913 13527 13913 13530 13914 7950 13914 13254 13914 13530 6 13531 6 7950 6 13257 13915 7948 13915 7941 13915 13298 13916 13299 13916 13291 13916 7950 13917 13532 13917 13278 13917 13278 13918 13267 13918 13266 13918 13267 13919 13532 13919 13533 13919 13534 13920 13267 13920 13533 13920 13534 13921 13287 13921 13267 13921 13535 13922 9082 13922 13533 13922 13252 13923 13250 13923 13288 13923 13287 13924 13529 13924 13252 13924 13527 6 9071 6 13533 6 13535 13925 9075 13925 9076 13925 13535 13926 13533 13926 9075 13926 13533 13927 13526 13927 13527 13927 13530 13928 13532 13928 13531 13928 13541 13929 13536 13929 9077 13929 13288 13930 13271 13930 13270 13930 13340 13931 13234 13931 13230 13931 13234 13932 13342 13932 13455 13932 13376 13933 13455 13933 13432 13933 13376 13934 13432 13934 13433 13934 13230 13935 13235 13935 13340 13935 13242 13936 13237 13936 13318 13936 13318 13937 13237 13937 13236 13937 13236 13938 13238 13938 13239 13938 13318 13939 13320 13939 13235 13939 13455 13940 13342 13940 13458 13940 13455 13941 13458 13941 13457 13941 13458 13942 13343 13942 13542 13942 13458 13943 13542 13943 13459 13943 13357 13944 13344 13944 13346 13944 13472 13945 13358 13945 13543 13945 13544 13946 13546 13946 13545 13946 13357 13947 13461 13947 13459 13947 13358 13948 13352 13948 13548 13948 13548 13949 13352 13949 13351 13949 13363 13950 13550 13950 13350 13950 13363 13951 13365 13951 13551 13951 13554 13952 13482 13952 13555 13952 13561 13953 13560 13953 13562 13953 13350 13954 13310 13954 13362 13954 13551 13955 13365 13955 13552 13955 13483 13956 13366 13956 13367 13956 13483 13957 13482 13957 13366 13957 13563 13958 13481 13958 13479 13958 13564 13959 13471 13959 13565 13959 13564 13960 13479 13960 13471 13960 13479 13961 13478 13961 13471 13961 13470 13962 13469 13962 13566 13962 13566 13963 13469 13963 13474 13963 13567 13964 13474 13964 13472 13964 13545 13965 13567 13965 13472 13965 13566 13966 13474 13966 13567 13966 13568 13967 13567 13967 13569 13967 13381 13968 13437 13968 13438 13968 13380 13969 13407 13969 13409 13969 13382 13970 13380 13970 13409 13970 13385 13971 13375 13971 13433 13971 13375 13972 13376 13972 13433 13972 13571 13973 13572 13973 13378 13973 13248 13974 13573 13974 13574 13974 13249 13975 13574 13975 13575 13975 13581 13976 13582 13976 13583 13976 13573 13977 13581 13977 13585 13977 13573 13978 13585 13978 13575 13978 13587 13979 13577 13979 13589 13979 13576 13980 13578 13980 13579 13980 13249 13981 13576 13981 13537 13981 13249 13982 13577 13982 13576 13982 13249 13983 13575 13983 13577 13983 13576 13984 13538 13984 13537 13984 13249 13985 13248 13985 13574 13985 13247 13986 13590 13986 13582 13986 13247 13987 13232 13987 13590 13987 13571 13988 13221 13988 13572 13988 13572 13989 13221 13989 13223 13989 13221 13990 13222 13990 13223 13990 13223 13991 13224 13991 13231 13991 13566 13992 13565 13992 13470 13992 13564 13993 13563 13993 13479 13993 13561 13994 13562 13994 13592 13994 13595 13995 13596 13995 13597 13995 13598 13996 13553 13996 13556 13996 13548 13997 13599 13997 13543 13997 13602 13998 13543 13998 13601 13998 13604 13999 13605 13999 13595 13999 13597 14000 13604 14000 13595 14000 13606 14001 13607 14001 13608 14001 13609 14002 13610 14002 13546 14002 13546 14003 13547 14003 13608 14003 13547 14004 13606 14004 13608 14004 13248 14005 13584 14005 13573 14005 13223 14006 13231 14006 13572 14006 13583 14007 13590 14007 13571 14007 13273 14008 13319 14008 13276 14008 13276 14009 13317 14009 13277 14009 13612 14010 13391 14010 13614 14010 13391 14011 13613 14011 13392 14011 13332 14012 13331 14012 13441 14012 13329 14013 13445 14013 13330 14013 13447 14014 13328 14014 13326 14014 13615 14015 13616 14015 13617 14015 13401 14016 13617 14016 13618 14016 13620 14017 13263 14017 13262 14017 13621 14018 13519 14018 13518 14018 13620 14019 13518 14019 13619 14019 13620 14020 13621 14020 13518 14020 13436 14021 13434 14021 13402 14021 13430 14022 13448 14022 13615 14022 13443 14023 13442 14023 13331 14023 13436 14024 13392 14024 13439 14024 13436 14025 13389 14025 13392 14025 13389 14026 13436 14026 13402 14026 13560 14027 13622 14027 13419 14027 13419 14028 13614 14028 13421 14028 13614 14029 13391 14029 13427 14029 13427 14030 13424 14030 13614 14030 13614 14031 13424 14031 13421 14031 13612 14032 13623 14032 13613 14032 13295 14033 13282 14033 13312 14033 13283 14034 13296 14034 13285 14034 13285 14035 13296 14035 13297 14035 13286 14036 13290 14036 7941 14036 13613 14037 13623 14037 13282 14037 13280 14038 13613 14038 13282 14038 13300 14039 13308 14039 13282 14039 13282 14040 13308 14040 13311 14040 13312 14041 13282 14041 13311 14041 13625 14042 13626 14042 13300 14042 13628 14043 13303 14043 13627 14043 13628 14044 13629 14044 13303 14044 13632 14045 13417 14045 13631 14045 13419 14046 13418 14046 13560 14046 13300 14047 13626 14047 13301 14047 13303 14048 13629 14048 13630 14048 13304 14049 13630 14049 13414 14049 13306 14050 13304 14050 13633 14050 13263 14051 13619 14051 13634 14051 13618 14052 13634 14052 13619 14052 13621 14053 13620 14053 13519 14053 13522 14054 13259 14054 13636 14054 10732 14055 13639 14055 13539 14055 13261 14056 13638 14056 13636 14056 13261 14057 13271 14057 13539 14057 13640 14058 13261 14058 13639 14058 13640 14059 13523 14059 13261 14059 9957 14060 9101 14060 13641 14060 13638 14061 13642 14061 13636 14061 13635 14062 13522 14062 13643 14062 13518 14063 13401 14063 13618 14063 13617 14064 13401 14064 13615 14064 13391 14065 13390 14065 13408 14065 13410 14066 13390 14066 13397 14066 13410 14067 13397 14067 13429 14067 13394 14068 13429 14068 13397 14068 13280 14069 13277 14069 13316 14069 13321 14070 13272 14070 13616 14070 13616 14071 13325 14071 13321 14071 13272 14072 13274 14072 13616 14072 13262 14073 13519 14073 13620 14073 13439 14074 13613 14074 13280 14074 13392 14075 13613 14075 13439 14075 13537 14076 13250 14076 13249 14076 13536 14077 13540 14077 13534 14077 13536 14078 13541 14078 9079 14078 13576 14079 13644 14079 13538 14079 13576 14080 13579 14080 13644 14080 9972 14081 13645 14081 10282 14081 13538 14082 13644 14082 9972 14082 13644 14083 13645 14083 9972 14083 9079 14084 9076 14084 9075 14084 13587 14085 13581 14085 13583 14085 13648 14086 13374 14086 13373 14086 13378 14087 13374 14087 13571 14087 13587 14088 13583 14088 13647 14088 13649 14089 13587 14089 13647 14089 13649 14090 13586 14090 13587 14090 13498 14091 13520 14091 13649 14091 13649 14092 13520 14092 13525 14092 13525 14093 13641 14093 13586 14093 13588 14094 13586 14094 13641 14094 13649 14095 13525 14095 13586 14095 13641 14096 9099 14096 13588 14096 13650 14097 10738 14097 10739 14097 13651 14098 9945 14098 10738 14098 9107 14099 10738 14099 9106 14099 13652 14100 13588 14100 9099 14100 9110 14101 9959 14101 13652 14101 13588 14102 13652 14102 13580 14102 13588 14103 13580 14103 13578 14103 13652 14104 9959 14104 9960 14104 13639 14105 13579 14105 13580 14105 10281 14106 13653 14106 10282 14106 13653 14107 10281 14107 10724 14107 10292 14108 13654 14108 13655 14108 13656 14109 13655 14109 13657 14109 13656 14110 10291 14110 13655 14110 13645 14111 10281 14111 10282 14111 13566 14112 13591 14112 13660 14112 13660 14113 13591 14113 13658 14113 13661 14114 13565 14114 13660 14114 13660 14115 13565 14115 13566 14115 13564 14116 13565 14116 13662 14116 13661 6 13663 6 13662 6 13661 6 13665 6 13664 6 13665 6 13660 6 13658 6 13664 6 13667 6 13663 6 13663 14117 13562 14117 13560 14117 13594 14118 13593 14118 13666 14118 13666 14119 13593 14119 13667 14119 13569 14120 13666 14120 13664 14120 13568 14121 13569 14121 13665 14121 13665 14122 13569 14122 13664 14122 13659 14123 13568 14123 13665 14123 13668 14124 13553 14124 13596 14124 13595 14125 13668 14125 13596 14125 13553 14126 13668 14126 13552 14126 13552 6 13668 6 13669 6 13669 6 13668 6 13670 6 13672 6 13673 6 13670 6 13672 6 13674 6 13673 6 13550 14127 13551 14127 13669 14127 13549 14128 13669 14128 13670 14128 13548 14129 13549 14129 13673 14129 13670 14130 13673 14130 13549 14130 13599 14131 13548 14131 13674 14131 13599 14132 13674 14132 13600 14132 13600 14133 13674 14133 13675 14133 13600 14134 13675 14134 13601 14134 13601 14135 13675 14135 13672 14135 13601 14136 13672 14136 13602 14136 13602 14137 13672 14137 13671 14137 13603 14138 13677 14138 13605 14138 13605 14139 13676 14139 13595 14139 13624 14140 13623 14140 13604 14140 13604 14141 13623 14141 13611 14141 13625 14142 13597 14142 13596 14142 13631 14143 13556 14143 13557 14143 13629 14144 13556 14144 13631 14144 13559 14145 13632 14145 13558 14145 13632 14146 13559 14146 13560 14146 13622 14147 13560 14147 13561 14147 13622 14148 13561 14148 13614 14148 13612 14149 13609 14149 13607 14149 13546 14150 13679 14150 13545 14150 13567 14151 13545 14151 13680 14151 13680 14152 13545 14152 13679 14152 13682 14153 13543 14153 13681 14153 13611 14154 13547 14154 13682 14154 13683 14155 13606 14155 13608 14155 10724 14156 10732 14156 13684 14156 10732 14157 9089 14157 13684 14157 13684 14158 9089 14158 13685 14158 13687 14159 9101 14159 9957 14159 13650 14160 13687 14160 13688 14160 13646 14161 10282 14161 13689 14161 13654 14162 10292 14162 13690 14162 13690 14163 10292 14163 10290 14163 9969 14164 13692 14164 9966 14164 13656 14165 13657 14165 13694 14165 13693 14166 13694 14166 13685 14166 13654 14167 13689 14167 10282 14167 9089 14168 9968 14168 13685 14168 9967 14169 9971 14169 9969 14169 13510 14170 13696 14170 13695 14170 13698 14171 13512 14171 13699 14171 13502 14172 13495 14172 13508 14172 13700 14173 13702 14173 13701 14173 13701 14174 13702 14174 13703 14174 13489 14175 13488 14175 13511 14175 13704 14176 13489 14176 13511 14176 13705 14177 13505 14177 13504 14177 13706 14178 13506 14178 9097 14178 9945 14179 9954 14179 9106 14179 13708 14180 13709 14180 13710 14180 13651 14181 13710 14181 9945 14181 13709 14182 9954 14182 9945 14182 13711 14183 9956 14183 13712 14183 13707 14184 13714 14184 9110 14184 9955 14185 9956 14185 9954 14185 9950 14186 9954 14186 13709 14186 9956 14187 13713 14187 9954 14187 9955 14188 9954 14188 9950 14188 13717 14189 9956 14189 9955 14189 9950 14190 13717 14190 9954 14190 9960 14191 13715 14191 9957 14191 9957 14192 13715 14192 9953 14192 10291 14193 13656 14193 9962 14193 13592 14194 13680 14194 13610 14194 13611 14195 13682 14195 13604 14195 13604 14196 13682 14196 13681 14196 13686 14197 13718 14197 13684 14197 13718 14198 13686 14198 13719 14198 13686 14199 13694 14199 13719 14199 13694 14200 13720 14200 13719 14200 13722 14201 13688 14201 13687 14201 13722 14202 13723 14202 13688 14202 13710 14203 13723 14203 13724 14203 13725 14204 13690 14204 13691 14204 13720 14205 13725 14205 13691 14205 13689 14206 13718 14206 13646 14206 13646 14207 13718 14207 9968 14207 13720 14208 9967 14208 13719 14208 13719 14209 9967 14209 9968 14209 9968 14210 13718 14210 13719 14210 13506 14211 13706 14211 9113 14211 13507 14212 9113 14212 9064 14212 9092 6 13493 6 13501 6 13501 14213 13493 14213 13502 14213 13696 14214 13728 14214 13695 14214 13698 14215 13727 14215 13503 14215 13726 14216 13499 14216 13727 14216 13696 14217 13726 14217 13728 14217 13697 14218 13695 14218 13728 14218 13729 14219 13730 14219 13731 14219 13491 14220 13490 14220 13731 14220 13494 14221 13491 14221 13732 14221 13490 14222 13489 14222 13729 14222 13729 14223 13489 14223 13704 14223 13702 14224 13732 14224 13731 14224 13731 14225 13703 14225 13702 14225 13703 14226 13731 14226 13730 14226 13703 14227 13730 14227 13701 14227 9113 14228 13706 14228 9064 14228 9064 14229 13706 14229 9097 14229 13713 14230 13724 14230 9107 14230 9107 14231 13724 14231 10738 14231 13722 14232 10739 14232 10738 14232 10738 14233 13723 14233 13722 14233 13725 14234 13653 14234 13718 14234 13655 14235 13653 14235 13725 14235 13694 14236 13657 14236 13720 14236 13720 14237 13657 14237 13655 14237 13687 14238 9953 14238 13721 14238 13721 14239 9953 14239 13715 14239 13724 14240 13713 14240 13733 14240 13733 14241 13711 14241 13714 14241 13721 14242 13733 14242 13714 14242 13721 14243 13715 14243 13733 14243 13677 14244 13675 14244 13735 14244 13736 14245 13735 14245 13734 14245 13740 14246 13659 14246 13741 14246 13738 14247 13659 14247 13666 14247 13744 8265 13743 8265 13745 8265 13746 7838 13747 7838 13748 7838 13743 6 13746 6 13745 6 13748 243 13749 243 13745 243 13734 14248 13735 14248 13739 14248 13734 14249 13735 14249 13675 14249 13742 243 13751 243 13743 243 13734 14250 13746 14250 13743 14250 13734 14251 13741 14251 13746 14251 13750 14252 13741 14252 13659 14252 13747 243 13746 243 13752 243 13757 53 13753 53 13758 53 13754 6 13759 6 13756 6 13751 53 13742 53 13763 53 13761 53 13742 53 13747 53 13744 53 13749 53 13742 53 13742 53 13749 53 13747 53 13735 14253 13751 14253 13764 14253 13764 8265 13751 8265 13763 8265 13762 14254 13735 14254 13764 14254 13737 14255 13759 14255 13738 14255 13736 14256 13764 14256 13677 14256 13736 427 13762 427 13764 427 13754 14257 13738 14257 13759 14257 13761 14258 13740 14258 13754 14258 13761 427 13757 427 13763 427 13766 14259 13768 14259 13767 14259 13771 14260 13767 14260 13768 14260 13678 14261 13775 14261 13774 14261 13777 14262 13610 14262 13612 14262 13776 14263 13775 14263 13778 14263 13778 14264 13623 14264 13779 14264 13611 14265 13779 14265 13623 14265 13592 14266 13561 14266 13612 14266 13561 14267 13622 14267 13612 14267 13774 14268 13773 14268 13607 14268 13623 14269 13778 14269 13606 14269 13623 14270 13778 14270 13624 14270 13596 14271 13625 14271 13626 14271 13596 14272 13627 14272 13598 14272 13627 14273 13596 14273 13626 14273 13765 14274 13598 14274 13628 14274 13765 14275 13628 14275 13556 14275 13769 14276 13631 14276 13558 14276 13558 14277 13786 14277 13559 14277 13559 14278 13786 14278 13560 14278 13787 14279 13559 14279 13788 14279 13560 14280 13561 14280 13788 14280 13598 14281 13785 14281 13596 14281 13625 14282 13783 14282 13597 14282 13783 14283 13596 14283 13785 14283 13790 14284 13597 14284 13783 14284 13779 14285 13791 14285 13792 14285 13793 14286 13770 14286 13795 14286 13779 14287 13792 14287 13772 14287 13772 14288 13792 14288 13781 14288 13781 14289 13792 14289 13796 14289 13795 14290 13796 14290 13793 14290 13794 14291 13770 14291 13793 14291 13779 14292 13611 14292 13798 14292 13798 14293 13611 14293 13790 14293 13799 14294 13785 14294 13800 14294 13785 14295 13784 14295 13800 14295 13799 14296 13798 14296 13790 14296 13610 14297 13777 14297 13592 14297 13592 14298 13777 14298 13782 14298 13801 14299 13789 14299 13788 14299 13798 14300 13791 14300 13779 14300 13606 14301 13775 14301 13683 14301 13683 14302 13678 14302 13607 14302 13609 14303 13678 14303 13774 14303 13766 14304 13769 14304 13768 14304 13771 14305 13769 14305 13795 14305 13784 14306 13598 14306 13770 14306 13770 14307 13598 14307 13765 14307 13797 14308 13558 14308 13789 14308 13780 14309 13772 14309 13774 14309 13795 14310 13770 14310 13771 14310 13782 14311 13781 14311 13801 14311 13791 14312 13798 14312 13802 14312 13800 14313 13794 14313 13802 14313 13782 14314 13803 14314 13804 14314 13788 14315 13804 14315 13803 14315 13801 14316 13788 14316 13803 14316 13782 14317 13804 14317 13788 14317 13798 14318 13805 14318 13806 14318 13800 14319 13806 14319 13805 14319 13799 14320 13805 14320 13798 14320 13798 14321 13806 14321 13802 14321 13802 14322 13806 14322 13800 14322 13805 14323 13627 14323 13626 14323 13808 14324 13624 14324 13778 14324 13773 14325 13612 14325 13614 14325 13808 14326 13623 14326 13773 14326 13807 14327 13631 14327 13629 14327 13808 14328 13809 14328 13807 14328 13622 14329 13809 14329 13773 14329 13808 14330 13625 14330 13624 14330 13809 14331 13808 14331 13773 14331 13807 14332 13809 14332 13786 14332 13808 14333 13807 14333 13805 14333 13812 14334 13811 14334 13813 14334 13814 14335 13815 14335 13816 14335 13819 14336 13820 14336 13821 14336 13822 14337 13820 14337 13824 14337 10962 14338 11853 14338 13824 14338 10952 14339 13814 14339 11849 14339 13826 14340 11848 14340 13827 14340 11848 14341 11849 14341 13827 14341 13815 14342 13814 14342 13828 14342 13828 14343 11885 14343 10960 14343 10960 14344 11884 14344 13824 14344 13818 14345 13810 14345 13827 14345 13810 14346 13812 14346 13826 14346 13812 14347 13822 14347 13825 14347 13820 14348 13819 14348 13824 14348 13832 14349 13831 14349 11855 14349 13837 14350 13839 14350 13840 14350 13837 14351 13836 14351 13839 14351 13841 14352 13842 14352 13843 14352 13848 14353 13847 14353 13849 14353 13852 14354 13851 14354 13841 14354 13839 14355 13857 14355 13840 14355 13852 14356 13858 14356 13851 14356 13858 14357 13850 14357 13851 14357 13850 14358 13849 14358 13847 14358 13845 14359 13838 14359 11883 14359 13845 14360 11883 14360 13843 14360 13843 14361 13840 14361 13838 14361 13841 14362 13843 14362 13852 14362 13838 14363 13837 14363 13842 14363 13845 14364 13838 14364 13842 14364 13845 14365 13842 14365 13836 14365 13829 14366 13831 14366 13835 14366 13831 14367 13833 14367 13835 14367 11866 14368 13833 14368 13832 14368 13832 14369 11855 14369 11866 14369 13846 14370 11866 14370 11855 14370 13846 14371 13833 14371 11866 14371 13829 14372 13835 14372 13832 14372 13835 14373 13848 14373 13860 14373 13835 14374 13834 14374 13848 14374 13841 14375 13864 14375 13844 14375 13867 14376 13847 14376 13868 14376 13847 14377 13867 14377 13851 14377 13868 14378 13847 14378 13846 14378 13839 14379 13872 14379 13871 14379 13872 14380 13844 14380 13864 14380 13868 14381 13846 14381 13869 14381 13869 14382 13853 14382 13873 14382 13858 14383 11878 14383 11870 14383 11871 14384 13850 14384 11870 14384 13849 14385 11871 14385 11882 14385 13860 14386 13849 14386 11882 14386 11880 14387 11882 14387 11871 14387 13874 14388 13879 14388 11872 14388 11872 14389 13879 14389 11868 14389 13880 14390 13881 14390 11870 14390 13881 14391 13876 14391 11871 14391 11879 14392 13883 14392 13882 14392 11879 14393 11880 14393 13883 14393 13870 14394 13871 14394 13884 14394 13873 14395 13884 14395 13885 14395 13868 14396 13888 14396 13889 14396 13868 14397 13889 14397 13890 14397 13866 14398 13890 14398 13865 14398 13868 14399 13869 14399 13888 14399 13817 14400 13871 14400 13872 14400 13884 14401 13877 14401 13879 14401 13874 14402 13819 14402 13885 14402 13819 14403 13874 14403 13815 14403 13815 14404 13874 14404 13878 14404 13878 14405 13877 14405 13815 14405 13885 14406 13819 14406 13886 14406 13886 14407 13819 14407 13821 14407 13888 14408 13820 14408 13823 14408 13876 14409 13890 14409 13889 14409 13880 14410 13865 14410 13890 14410 13880 14411 13811 14411 13865 14411 13813 14412 13882 14412 13883 14412 13883 14413 13876 14413 13813 14413 13887 14414 13820 14414 13888 14414 13865 14415 13811 14415 13864 14415 13872 14416 13810 14416 13818 14416 13871 14417 13877 14417 13884 14417 13860 14418 11853 14418 10962 14418 13860 14419 11882 14419 11853 14419 11848 14420 11878 14420 11883 14420 11848 14421 11883 14421 11849 14421 11885 14422 13875 14422 13891 14422 13875 14423 11885 14423 11875 14423 13859 14424 11849 14424 11883 14424 13891 14425 13861 14425 11884 14425 13840 14426 13857 14426 13859 14426 11875 14427 13859 14427 11868 14427 13891 14428 13875 14428 11872 14428 13854 14429 11872 14429 13855 14429 13854 14430 13891 14430 11872 14430 13854 14431 13829 14431 13891 14431 13857 14432 13855 14432 11868 14432 11872 14433 11868 14433 13855 14433 13892 14434 13895 14434 13894 14434 13897 14435 13894 14435 13896 14435 13894 14436 13897 14436 13878 14436 13898 14437 13895 14437 13899 14437 13900 14438 13899 14438 13901 14438 13902 14439 13904 14439 13905 14439 13907 14440 13906 14440 13908 14440 13907 14441 13908 14441 13909 14441 13907 14442 13909 14442 13905 14442 13907 14443 13905 14443 13882 14443 13909 14444 13908 14444 13910 14444 13912 14445 13911 14445 13913 14445 13916 14446 13878 14446 13897 14446 13916 14447 13877 14447 13878 14447 13910 14448 13911 14448 13912 14448 13916 14449 13893 14449 13878 14449 13897 14450 13896 14450 13902 14450 13900 6 13896 6 13898 6 13914 14451 13909 14451 13910 14451 13920 14452 13874 14452 13919 14452 13878 14453 13919 14453 13916 14453 13922 14454 13923 14454 13916 14454 13917 14455 13924 14455 13925 14455 13920 14456 13926 14456 13927 14456 13918 14457 13927 14457 13924 14457 13923 14458 13925 14458 13926 14458 13923 14459 13922 14459 13929 14459 13927 14460 13918 14460 13930 14460 13928 14461 13917 14461 13925 14461 13917 14462 13918 14462 13924 14462 13929 14463 13922 14463 13893 14463 13893 14464 13922 14464 13919 14464 13892 14465 13919 14465 13920 14465 13931 14466 13920 14466 13927 14466 13930 14467 13918 14467 13932 14467 13928 14468 13932 14468 13917 14468 13892 14469 13931 14469 13895 14469 13895 14470 13931 14470 13899 14470 13901 14471 13931 14471 13930 14471 13913 14472 13928 14472 13929 14472 13915 14473 13913 14473 13929 14473 13913 14474 13911 14474 13928 14474 13911 14475 13908 14475 13928 14475 13906 14476 13903 14476 13932 14476 13903 53 13901 53 13930 53 13901 14477 13899 14477 13931 14477 13943 14478 13941 14478 13944 14478 13945 53 13946 53 13940 53 13947 14479 13943 14479 13945 14479 13943 14480 13949 14480 13939 14480 13939 14481 13949 14481 13950 14481 13953 14482 13941 14482 13942 14482 13941 14483 13954 14483 13952 14483 13946 14484 13951 14484 13942 14484 13946 14485 13944 14485 13951 14485 13941 14486 13952 14486 13944 14486 13948 14487 13953 14487 13947 14487 13863 14488 13856 14488 13862 14488 13834 14489 13888 14489 13830 14489 13834 14490 13889 14490 13888 14490 13889 14491 13834 14491 13867 14491 13864 14492 13851 14492 13841 14492 13872 14493 13844 14493 13839 14493 13870 14494 13856 14494 13853 14494 13888 14495 13887 14495 13830 14495 13867 14496 13834 14496 13851 14496 13864 14497 13841 14497 13872 14497 13954 6 13865 6 13864 6 13872 14498 13952 14498 13954 14498 13870 14499 13952 14499 13871 14499 13952 14500 13870 14500 13949 14500 13886 6 13887 6 13949 6 13949 14501 13887 14501 13950 14501 13830 14502 13955 14502 13956 14502 13830 14503 13957 14503 13955 14503 13957 14504 13958 14504 13863 14504 13961 14505 13839 14505 13962 14505 13961 14506 13962 14506 13841 14506 13963 14507 13841 14507 13964 14507 13963 14508 13964 14508 13965 14508 13867 14509 13967 14509 13966 14509 13968 14510 13867 14510 13965 14510 13960 14511 13839 14511 13961 14511 13961 14512 13841 14512 13963 14512 13967 14513 13834 14513 13955 14513 13830 14514 13853 14514 13958 14514 13958 14515 13853 14515 13863 14515 13863 14516 13853 14516 13856 14516 13862 14517 13856 14517 13839 14517 13962 14518 13844 14518 13841 14518 13962 14519 13839 14519 13844 14519 13851 14520 13965 14520 13964 14520 13834 14521 13830 14521 13956 14521 13955 14522 13957 14522 13969 14522 13969 14523 13957 14523 13936 14523 13936 14524 13937 14524 13969 14524 13933 14525 13966 14525 13934 14525 13934 14526 13966 14526 13967 14526 13967 14527 13969 14527 13934 14527 13969 14528 13967 14528 13955 14528 13937 14529 13959 14529 13960 14529 13960 14530 13970 14530 13937 14530 13970 14531 13960 14531 13961 14531 13933 14532 13934 14532 13969 14532 13972 14533 13974 14533 13975 14533 13978 14534 13976 14534 13977 14534 13978 14535 13971 14535 13973 14535 13972 14536 13975 14536 13980 14536 1089 14537 13971 14537 13978 14537 1089 14538 13978 14538 1091 14538 1091 14539 13978 14539 838 14539 13982 14540 1091 14540 838 14540 838 14541 13978 14541 13977 14541 1088 14542 1084 14542 13984 14542 1089 14543 13984 14543 13981 14543 13986 14544 13973 14544 13987 14544 13988 14545 13987 14545 13989 14545 13992 14546 13979 14546 13973 14546 13985 14547 13992 14547 13973 14547 13987 14548 13973 14548 13972 14548 13972 14549 13980 14549 13989 14549 13991 14550 13980 14550 13976 14550 13989 14551 13980 14551 13991 14551 1178 14552 13995 14552 1097 14552 1116 14553 1178 14553 1097 14553 1116 14554 1179 14554 1178 14554 13994 14555 840 14555 839 14555 13995 14556 13994 14556 839 14556 13999 14557 837 14557 838 14557 13999 14558 14000 14558 837 14558 14000 14559 13999 14559 14001 14559 14000 14560 14001 14560 13998 14560 14001 14561 13982 14561 13998 14561 13994 14562 13999 14562 840 14562 840 14563 13999 14563 838 14563 839 14564 838 14564 13977 14564 839 14565 840 14565 838 14565 14002 14566 13981 14566 13984 14566 14002 14567 14003 14567 13981 14567 1085 14568 1177 14568 1062 14568 1176 14569 1085 14569 832 14569 832 14570 14004 14570 1176 14570 14004 14571 833 14571 14005 14571 14004 14572 14005 14572 1177 14572 14005 14573 833 14573 1177 14573 14003 14574 14005 14574 833 14574 14008 14575 14009 14575 14006 14575 14010 14576 14011 14576 14012 14576 14014 14577 14013 14577 14015 14577 14007 14578 14016 14578 14017 14578 14016 14579 14015 14579 14013 14579 14018 14580 14007 14580 14019 14580 14010 14581 14020 14581 14011 14581 14011 14582 14020 14582 1097 14582 14010 14583 13996 14583 14020 14583 14013 14584 14021 14584 14010 14584 14013 14585 14022 14585 14021 14585 14013 14586 14014 14586 14022 14586 14022 14587 14014 14587 14023 14587 14023 14588 14014 14588 14024 14588 14024 14589 14014 14589 13997 14589 13996 14590 14027 14590 14028 14590 13996 14591 14010 14591 14027 14591 14027 14592 14010 14592 14029 14592 14031 14593 14023 14593 14025 14593 14032 14594 14033 14594 14027 14594 14029 14595 14010 14595 14021 14595 14034 14596 14015 14596 1116 14596 14016 14597 14018 14597 14035 14597 14015 14598 14016 14598 14036 14598 13994 14599 14036 14599 14037 14599 14005 14600 14037 14600 1062 14600 833 14601 14005 14601 1062 14601 14036 14602 14035 14602 14037 14602 1116 14603 14015 14603 14036 14603 14037 14604 14035 14604 1062 14604 1116 14605 14036 14605 13994 14605 14008 14606 14007 14606 14038 14606 14017 14607 14011 14607 14038 14607 14030 14608 14040 14608 14041 14608 14030 14609 14041 14609 14023 14609 14043 14610 14044 14610 14045 14610 14046 14611 14047 14611 14048 14611 14049 14612 14050 14612 14045 14612 14048 14613 14049 14613 14046 14613 14048 14614 14047 14614 14051 14614 14043 14615 14039 14615 14022 14615 14043 14616 14022 14616 14044 14616 14021 14617 14040 14617 14029 14617 14053 14618 14021 14618 14039 14618 14009 14619 14051 14619 14045 14619 14009 14620 14054 14620 14048 14620 14055 14621 14056 14621 14057 14621 14058 14622 14060 14622 14059 14622 14050 14623 14048 14623 14054 14623 14061 14624 14050 14624 14054 14624 14006 14625 14045 14625 14019 14625 14062 14626 14057 14626 14060 14626 14059 14627 14063 14627 14056 14627 14019 14628 14045 14628 14050 14628 14042 14629 14041 14629 14049 14629 14042 14630 14044 14630 14022 14630 14052 14631 14040 14631 14053 14631 14043 14632 14052 14632 14039 14632 14039 14633 14052 14633 14053 14633 14064 14634 14061 14634 14065 14634 14064 14635 14066 14635 14050 14635 14025 14636 14024 14636 14071 14636 14025 14637 14064 14637 14070 14637 14033 14638 14072 14638 14071 14638 14055 14639 14068 14639 14073 14639 14029 14640 14032 14640 14027 14640 14029 14641 14074 14641 14032 14641 14065 14642 14061 14642 14054 14642 14072 14643 14067 14643 14069 14643 14072 14644 14032 14644 14067 14644 14064 14645 14071 14645 14066 14645 14074 14646 14065 14646 14073 14646 14066 14647 14072 14647 14069 14647 14074 14648 14073 14648 14032 14648 14032 14649 14073 14649 14068 14649 14075 14650 14076 14650 14077 14650 14078 14651 14079 14651 14028 14651 14028 14652 14080 14652 13996 14652 14076 14653 14075 14653 14026 14653 14080 14654 14076 14654 14026 14654 14024 14655 14075 14655 14081 14655 14075 14656 14024 14656 14026 14656 14087 14657 14063 14657 14059 14657 14087 14658 14079 14658 14063 14658 14083 14659 14085 14659 14087 14659 14082 14660 14090 14660 14089 14660 14090 14661 14060 14661 14089 14661 14083 14662 14059 14662 14060 14662 14063 14663 14091 14663 14057 14663 14063 14664 14079 14664 14091 14664 14089 14665 14060 14665 14057 14665 14082 14666 14081 14666 14090 14666 14078 14667 14091 14667 14079 14667 14082 14668 14088 14668 14086 14668 14086 14669 14088 14669 14092 14669 14087 14670 14085 14670 14080 14670 14058 14671 14093 14671 14019 14671 14019 14672 14093 14672 14018 14672 1062 14673 14018 14673 14093 14673 14056 14674 14009 14674 14008 14674 1085 14675 1062 14675 14056 14675 14056 14676 1062 14676 14058 14676 839 14677 14094 14677 1097 14677 14038 14678 13975 14678 14095 14678 13974 14679 14095 14679 13975 14679 14095 14680 13974 14680 1085 14680 13974 14681 13971 14681 832 14681 1085 14682 13974 14682 832 14682 14011 14683 14094 14683 14038 14683 14011 14684 1097 14684 14094 14684 14094 14685 839 14685 13977 14685 1063 14686 513 14686 14002 14686 14002 14687 14096 14687 14003 14687 14097 14688 14001 14688 13999 14688 14097 14689 511 14689 14001 14689 14001 14690 511 14690 1115 14690 14005 14691 14003 14691 14037 14691 14037 14692 14003 14692 14096 14692 13984 14693 1063 14693 14002 14693 1084 14694 513 14694 1063 14694 1089 6 13985 6 1088 6 1088 14695 13985 14695 13986 14695 14096 14696 13986 14696 13988 14696 13993 14697 14096 14697 13988 14697 13993 14698 14097 14698 14096 14698 13992 6 1089 6 1091 6 1088 6 13986 6 513 6 513 14699 13986 14699 14096 14699 14097 14700 13990 14700 511 14700 1093 6 13992 6 1091 6 511 14701 1094 14701 1115 14701 1094 14702 13983 14702 1115 14702 13982 14703 14001 14703 13983 14703 14098 14704 14099 14704 14100 14704 14099 14705 14101 14705 14102 14705 14103 14706 14102 14706 14104 14706 14105 14707 14100 14707 14106 14707 14105 14708 14098 14708 14100 14708 14099 14709 14102 14709 14107 14709 14108 14710 14098 14710 2937 14710 2937 14711 14098 14711 14105 14711 14109 14712 2939 14712 2687 14712 14109 14713 14110 14713 2941 14713 2939 14714 14109 14714 2941 14714 2936 14715 2933 14715 14111 14715 14100 14716 14112 14716 14106 14716 14112 14717 14100 14717 14113 14717 14117 14718 14116 14718 14118 14718 14113 14719 14114 14719 14115 14719 14119 14720 14116 14720 14117 14720 14117 14721 14118 14721 14120 14721 14120 14722 14106 14722 14112 14722 14099 14723 14116 14723 14114 14723 14118 14724 14107 14724 14103 14724 14103 14725 14120 14725 14118 14725 14116 14726 14107 14726 14118 14726 2690 14727 3029 14727 2965 14727 3028 14728 14122 14728 2945 14728 2965 14729 3029 14729 3028 14729 14121 14730 2690 14730 2689 14730 14122 14731 14121 14731 2689 14731 2689 14732 2945 14732 14122 14732 14126 14733 2688 14733 2687 14733 14127 14734 14128 14734 14125 14734 14109 14735 2687 14735 14125 14735 14125 14736 2688 14736 14127 14736 14121 14737 14126 14737 2690 14737 14129 14738 14108 14738 14111 14738 14129 14739 14130 14739 14108 14739 2683 14740 2912 14740 3026 14740 2934 14741 3025 14741 3026 14741 2682 14742 14131 14742 3025 14742 2682 14743 2683 14743 14131 14743 3027 14744 14132 14744 3026 14744 14131 14745 14132 14745 3027 14745 3025 14746 3027 14746 3026 14746 14130 14747 2683 14747 14108 14747 14130 14748 14132 14748 2683 14748 14135 14749 14136 14749 14133 14749 14134 14750 14143 14750 14144 14750 14142 14751 14140 14751 14143 14751 14143 14752 14140 14752 14144 14752 14145 14753 14134 14753 14146 14753 14137 14754 14147 14754 14138 14754 14138 14755 14147 14755 2945 14755 14147 14756 14123 14756 2945 14756 14140 14757 14148 14757 14137 14757 14140 14758 14149 14758 14148 14758 14140 14759 14141 14759 14149 14759 14149 14760 14141 14760 14150 14760 14150 14761 14141 14761 14151 14761 14151 14762 14141 14762 14124 14762 14151 14763 14124 14763 14152 14763 14157 14764 14150 14764 14158 14764 14155 14765 14137 14765 14148 14765 2965 14766 14124 14766 14161 14766 14161 14767 14124 14767 14141 14767 14143 14768 14145 14768 14162 14768 14132 14769 14164 14769 2912 14769 14163 14770 14162 14770 14164 14770 2690 14771 2965 14771 14121 14771 14163 14772 14143 14772 14162 14772 14135 14773 14134 14773 14165 14773 14165 14774 14134 14774 14144 14774 14144 14775 14139 14775 14138 14775 14166 14776 14148 14776 14149 14776 14167 14777 14156 14777 14155 14777 14169 14778 14149 14778 14150 14778 14173 14779 14174 14779 14175 14779 14176 14780 14177 14780 14172 14780 14175 14781 14176 14781 14173 14781 14176 14782 14175 14782 14177 14782 14167 14783 14173 14783 14168 14783 14175 14784 14174 14784 14178 14784 14178 14785 14174 14785 14179 14785 14178 14786 14179 14786 14170 14786 14178 14787 14170 14787 14172 14787 14170 14788 14166 14788 14149 14788 14148 14789 14167 14789 14155 14789 14180 14790 14148 14790 14166 14790 14136 14791 14178 14791 14172 14791 14136 14792 14181 14792 14175 14792 14136 14793 14182 14793 14181 14793 14182 14794 14183 14794 14184 14794 14185 14795 14187 14795 14186 14795 14185 14796 14146 14796 14187 14796 14187 14797 14146 14797 14177 14797 14188 14798 14175 14798 14181 14798 14133 14799 14172 14799 14146 14799 14182 14800 14184 14800 14189 14800 14146 14801 14172 14801 14177 14801 14174 14802 14167 14802 14179 14802 14166 14803 14179 14803 14180 14803 14188 14804 14193 14804 14177 14804 14193 14805 14195 14805 14177 14805 14196 14806 14197 14806 14189 14806 14187 14807 14195 14807 14189 14807 14195 14808 14198 14808 14189 14808 14192 14809 14150 14809 14151 14809 14192 14810 14193 14810 14158 14810 14159 14811 14199 14811 14160 14811 14160 14812 14191 14812 14151 14812 14182 14813 14200 14813 14181 14813 14182 14814 14197 14814 14200 14814 14155 14815 14159 14815 14153 14815 14201 14816 14155 14816 14157 14816 14194 14817 14188 14817 14181 14817 14199 14818 14196 14818 14198 14818 14193 14819 14191 14819 14195 14819 14201 14820 14194 14820 14200 14820 14159 14821 14200 14821 14197 14821 14205 14822 14206 14822 14154 14822 14154 14823 14207 14823 14123 14823 14203 14824 14202 14824 14152 14824 14152 14825 14123 14825 14207 14825 14207 14826 14203 14826 14152 14826 14208 14827 14209 14827 14151 14827 14202 14828 14204 14828 14208 14828 14151 14829 14202 14829 14208 14829 14154 14830 14213 14830 14205 14830 14213 14831 14153 14831 14151 14831 14214 14832 14206 14832 14190 14832 14210 14833 14214 14833 14186 14833 14215 14834 14209 14834 14216 14834 14217 14835 14210 14835 14187 14835 14218 14836 14219 14836 14184 14836 14190 14837 14206 14837 14218 14837 14216 14838 14187 14838 14184 14838 14204 14839 14203 14839 14211 14839 14213 14840 14218 14840 14205 14840 14209 14841 14215 14841 14213 14841 14214 14842 14212 14842 14207 14842 14210 14843 14217 14843 14204 14843 14204 14844 14217 14844 14208 14844 14185 14845 2912 14845 14220 14845 14146 14846 14220 14846 14145 14846 2912 14847 14145 14847 14220 14847 14183 14848 14135 14848 2934 14848 2934 14849 2912 14849 14183 14849 14183 14850 2912 14850 14185 14850 2689 14851 14221 14851 2945 14851 14165 14852 14222 14852 14135 14852 14222 14853 14101 14853 2934 14853 2934 14854 14101 14854 2682 14854 14138 14855 2945 14855 14221 14855 14165 14856 14221 14856 14102 14856 14224 14857 14126 14857 14164 14857 14224 14858 2365 14858 14128 14858 14128 14859 2365 14859 2964 14859 14164 14860 14130 14860 14223 14860 2933 14861 2913 14861 14111 14861 14111 14862 2913 14862 14129 14862 2941 14863 14117 14863 14120 14863 14112 14864 2937 14864 2939 14864 2936 14865 14113 14865 2367 14865 2367 6 14115 6 14223 6 14224 14866 14117 14866 2365 14866 2365 14867 14117 14867 2941 14867 2941 14868 14120 14868 2939 14868 2964 14869 14110 14869 14128 14869 14109 14870 14128 14870 14110 14870 14230 14871 14229 14871 14231 14871 14232 14872 14230 14872 14231 14872 14226 14873 14229 14873 14234 14873 14234 14874 14229 14874 14230 14874 4790 14875 14225 14875 14232 14875 4790 14876 14232 14876 4792 14876 4792 14877 14232 14877 4523 14877 14236 14878 14237 14878 4794 14878 4523 14879 14232 14879 14231 14879 4789 14880 14238 14880 4790 14880 4789 14881 14239 14881 14238 14881 4789 14882 4786 14882 14239 14882 4790 14883 14238 14883 14235 14883 14240 14884 14227 14884 14241 14884 14245 14885 14244 14885 14246 14885 14247 14886 14246 14886 14233 14886 14247 14887 14233 14887 14227 14887 14240 14888 14247 14888 14227 14888 14241 14889 14242 14889 14243 14889 14243 14890 14244 14890 14248 14890 14248 14891 14244 14891 14245 14891 14226 14892 14234 14892 14244 14892 14244 14893 14234 14893 14246 14893 4525 14894 14249 14894 4881 14894 4881 14895 14250 14895 4798 14895 14249 14896 4525 14896 4524 14896 14250 14897 14249 14897 4524 14897 14250 14898 4881 14898 14249 14898 4524 14899 4798 14899 14250 14899 14254 14900 14255 14900 4522 14900 14255 14901 14254 14901 14256 14901 4524 14902 4523 14902 14231 14902 14258 14903 14238 14903 14239 14903 4878 14904 4787 14904 4517 14904 4517 14905 4518 14905 14259 14905 14257 14906 4518 14906 14235 14906 14235 14907 4517 14907 14225 14907 14265 14908 14266 14908 14267 14908 14270 14909 14268 14909 14271 14909 14271 14910 14268 14910 14272 14910 14262 14911 14273 14911 14271 14911 14273 14912 14262 14912 14274 14912 14274 14913 14262 14913 14261 14913 14275 14914 14251 14914 4798 14914 14278 14915 14269 14915 14252 14915 14278 14916 14252 14916 14280 14916 14251 14917 14265 14917 14281 14917 14281 14918 14265 14918 14283 14918 14285 14919 14277 14919 14279 14919 14285 14920 14283 14920 14284 14920 14251 14921 14280 14921 14252 14921 14283 14922 14265 14922 14289 14922 14270 14923 14290 14923 14269 14923 14290 14924 14270 14924 4818 14924 4818 14925 14252 14925 14290 14925 14249 14926 14292 14926 14293 14926 4518 14927 14260 14927 4765 14927 14273 14928 4765 14928 14291 14928 14292 14929 14291 14929 14293 14929 4525 14930 4818 14930 14249 14930 4818 14931 14270 14931 14292 14931 14293 14932 14291 14932 4765 14932 4818 14933 14292 14933 14249 14933 14292 14934 14271 14934 14291 14934 14294 14935 14262 14935 14272 14935 14272 14936 14266 14936 14294 14936 14272 14937 14267 14937 14266 14937 14295 14938 14296 14938 14276 14938 14295 14939 14276 14939 14299 14939 14302 14940 14306 14940 14307 14940 14305 14941 14306 14941 14303 14941 14306 14942 14305 14942 14308 14942 14305 14943 14304 14943 14309 14943 14300 14944 14296 14944 14295 14944 14300 14945 14295 14945 14301 14945 14289 14946 14296 14946 14311 14946 14264 14947 14309 14947 14302 14947 14264 14948 14305 14948 14309 14948 14264 14949 14314 14949 14313 14949 14313 14950 14314 14950 14315 14950 14307 14951 14306 14951 14308 14951 14308 14952 14305 14952 14312 14952 14317 14953 14320 14953 14314 14953 14299 14954 14298 14954 14306 14954 14306 14955 14298 14955 14303 14955 14299 14956 14301 14956 14295 14956 14310 14957 14297 14957 14311 14957 14300 14958 14310 14958 14296 14958 14296 14959 14310 14959 14311 14959 14323 14960 14321 14960 14307 14960 14318 14961 14325 14961 14313 14961 14324 14962 14318 14962 14326 14962 14279 14963 14278 14963 14322 14963 14323 14964 14327 14964 14328 14964 14279 14965 14328 14965 14327 14965 14328 14966 14279 14966 14323 14966 14313 14967 14329 14967 14312 14967 14283 14968 14286 14968 14281 14968 14331 14969 14283 14969 14285 14969 14285 14970 14327 14970 14331 14970 14331 14971 14330 14971 14329 14971 14323 14972 14308 14972 14330 14972 14312 14973 14330 14973 14308 14973 14324 14974 14286 14974 14325 14974 14321 14975 14287 14975 14326 14975 14331 14976 14329 14976 14286 14976 14332 14977 14333 14977 14334 14977 14335 14978 14336 14978 14282 14978 14336 14979 14337 14979 14282 14979 14337 14980 14333 14980 14280 14980 14338 14981 14339 14981 14278 14981 14339 14982 14288 14982 14278 14982 14332 14983 14278 14983 14280 14983 14340 14984 14281 14984 14288 14984 14341 14985 14320 14985 14317 14985 14342 14986 14341 14986 14317 14986 14344 14987 14345 14987 14346 14987 14346 14988 14347 14988 14342 14988 14342 14989 14317 14989 14346 14989 14348 14990 14349 14990 14315 14990 14320 14991 14336 14991 14348 14991 14349 14992 14346 14992 14315 14992 14344 14993 14339 14993 14345 14993 14347 14994 14345 14994 14338 14994 14333 14995 14343 14995 14342 14995 14342 14996 14347 14996 14334 14996 14340 14997 14348 14997 14335 14997 14339 14998 14344 14998 14340 14998 14316 14999 14350 14999 14274 14999 14274 15000 14350 15000 14273 15000 14314 15001 14263 15001 4787 15001 14294 15002 14352 15002 14263 15002 14263 15003 14352 15003 4787 15003 14228 15004 14225 15004 4517 15004 14266 15005 14351 15005 14294 15005 14294 15006 14351 15006 14229 15006 14258 15007 14353 15007 14257 15007 14354 15008 14254 15008 14293 15008 14354 15009 4200 15009 14256 15009 14256 15010 4200 15010 4817 15010 14293 15011 14257 15011 14353 15011 4786 15012 4766 15012 14239 15012 4786 15013 4202 15013 4766 15013 4789 6 14240 6 14241 6 4202 15014 14241 15014 14243 15014 14248 15015 14353 15015 14243 15015 14248 15016 14354 15016 14353 15016 14354 15017 14248 15017 14245 15017 14247 15018 4790 15018 4792 15018 14354 6 14245 6 4200 6 4794 15019 4795 15019 4200 15019 4200 15020 4795 15020 4817 15020 4795 15021 14237 15021 4817 15021 4817 15022 14237 15022 14256 15022 14236 15023 14256 15023 14237 15023 14355 15024 14358 15024 14356 15024 14360 15025 14359 15025 14361 15025 14362 15026 14360 15026 14361 15026 14362 15027 14363 15027 14360 15027 14362 15028 14355 15028 14364 15028 14364 15029 14355 15029 14357 15029 14365 15030 14355 15030 6651 15030 6651 15031 14362 15031 6653 15031 6382 15032 14362 15032 14361 15032 6650 15033 6646 15033 14369 15033 14370 15034 14357 15034 14371 15034 14371 15035 14357 15035 14356 15035 14372 15036 14373 15036 14374 15036 14376 15037 14363 15037 14370 15037 14375 15038 14360 15038 14363 15038 6740 15039 14379 15039 6659 15039 14379 15040 14378 15040 6383 15040 6383 15041 6659 15041 14379 15041 14383 15042 14384 15042 6381 15042 14384 15043 14385 15043 14382 15043 14378 15044 14383 15044 6384 15044 14387 15045 14386 15045 14368 15045 14387 15046 14368 15046 14369 15046 6647 15047 6738 15047 6739 15047 6738 15048 6647 15048 6376 15048 14388 15049 6739 15049 6738 15049 14389 15050 6377 15050 6739 15050 14386 15051 6377 15051 14365 15051 14386 15052 14389 15052 6377 15052 14394 15053 14396 15053 14397 15053 14391 15054 14400 15054 14401 15054 14399 15055 14397 15055 14400 15055 14391 15056 14402 15056 14400 15056 14402 15057 14391 15057 14403 15057 14403 15058 14391 15058 14390 15058 14394 15059 14404 15059 14395 15059 14394 15060 14380 15060 14404 15060 14404 15061 14380 15061 6659 15061 14397 15062 14398 15062 14405 15062 14405 15063 14398 15063 14406 15063 14406 15064 14407 15064 14408 15064 14407 15065 14381 15065 14409 15065 14380 15066 14394 15066 14412 15066 14415 15067 14406 15067 14416 15067 14412 15068 14418 15068 14411 15068 14416 15069 14414 15069 14415 15069 14405 15070 14419 15070 14394 15070 14414 15071 14394 15071 14419 15071 14399 15072 14420 15072 14398 15072 14420 15073 14399 15073 6677 15073 6677 15074 14381 15074 14420 15074 14378 15075 14422 15075 14423 15075 6377 15076 14389 15076 6624 15076 6677 15077 14399 15077 14422 15077 14422 15078 14400 15078 14421 15078 14392 15079 14391 15079 14424 15079 14401 15080 14395 15080 14424 15080 14401 15081 14396 15081 14395 15081 14425 15082 14426 15082 14405 15082 14425 15083 14405 15083 14429 15083 14429 15084 14405 15084 14406 15084 14436 15085 14437 15085 14432 15085 14436 15086 14435 15086 14437 15086 14427 15087 14434 15087 14433 15087 14438 15088 14434 15088 14439 15088 14438 15089 14430 15089 14432 15089 14430 15090 14426 15090 14425 15090 14419 15091 14427 15091 14414 15091 14419 15092 14426 15092 14440 15092 14393 15093 14438 15093 14432 15093 14393 15094 14435 15094 14438 15094 14393 15095 14443 15095 14442 15095 14442 15096 14443 15096 14444 15096 14445 15097 14446 15097 14443 15097 14390 15098 14432 15098 14403 15098 14446 15099 14450 15099 14443 15099 14443 15100 14450 15100 14444 15100 14429 15101 14428 15101 14436 15101 14434 15102 14427 15102 14439 15102 14451 15103 14411 15103 14452 15103 14452 15104 14453 15104 14451 15104 14448 15105 14454 15105 14437 15105 14455 15106 14454 15106 14448 15106 14457 15107 14458 15107 14449 15107 14457 15108 14449 15108 14459 15108 14456 15109 14459 15109 14449 15109 14408 15110 14407 15110 14451 15110 14452 15111 14418 15111 14453 15111 14453 15112 14418 15112 14461 15112 14414 15113 14417 15113 14412 15113 14416 15114 14460 15114 14463 15114 14455 15115 14448 15115 14462 15115 14457 15116 14417 15116 14458 15116 14451 15117 14453 15117 14456 15117 14460 15118 14455 15118 14463 15118 14463 15119 14455 15119 14462 15119 14456 15120 14461 15120 14459 15120 14463 15121 14462 15121 14417 15121 14470 15122 14411 15122 14410 15122 14410 15123 14407 15123 14468 15123 14468 15124 14407 15124 14409 15124 14469 15125 14410 15125 14468 15125 14472 15126 14473 15126 14474 15126 14473 15127 14472 15127 14446 15127 14465 15128 14472 15128 14466 15128 14473 15129 14446 15129 14447 15129 14450 15130 14478 15130 14444 15130 14450 15131 14465 15131 14478 15131 14475 15132 14470 15132 14476 15132 14474 15133 14473 15133 14468 15133 14471 15134 14478 15134 14464 15134 14470 15135 14475 15135 14471 15135 14471 15136 14475 15136 14479 15136 14472 15137 14474 15137 14466 15137 14473 15138 14476 15138 14468 15138 14445 15139 14480 15139 14403 15139 14403 15140 14480 15140 14402 15140 6383 15141 14481 15141 6659 15141 14424 15142 14359 15142 14482 15142 14424 15143 14482 15143 14392 15143 14358 15144 14482 15144 14359 15144 14482 15145 14358 15145 6647 15145 14392 15146 14482 15146 6647 15146 6647 15147 14358 15147 6376 15147 14481 15148 6383 15148 14361 15148 14424 15149 14481 15149 14359 15149 14484 15150 14383 15150 14423 15150 14484 15151 14385 15151 14383 15151 14423 15152 14386 15152 14483 15152 6646 15153 6625 15153 14369 15153 6650 15154 14370 15154 14371 15154 14483 15155 14371 15155 14372 15155 6655 6 14377 6 14376 6 6062 6 14371 6 14483 6 6655 15156 14376 15156 6653 15156 6655 15157 6656 15157 6060 15157 6656 15158 14367 15158 6676 15158 6676 15159 14367 15159 14385 15159 14366 15160 14385 15160 14367 15160 14485 15161 14486 15161 7913 15161 7913 15162 14486 15162 7910 15162 7907 15163 14487 15163 14488 15163 7901 15164 14488 15164 14485 15164 7913 15165 7903 15165 14485 15165 7910 15166 14487 15166 7907 15166 7905 15167 14488 15167 7901 15167 7913 15168 14489 15168 7903 15168 7913 15169 14490 15169 14489 15169 14490 15170 7913 15170 7910 15170 14491 15171 7905 15171 7901 15171 7905 15172 14491 15172 14492 15172 7905 15173 14492 15173 7907 15173 14493 15174 14494 15174 7910 15174 14494 15175 14490 15175 7910 15175 14486 15176 14488 15176 14487 15176 14493 15177 14492 15177 14497 15177 14497 15178 14498 15178 14494 15178 14494 15179 14493 15179 14497 15179 14491 15180 14489 15180 14495 15180 14498 15181 14497 15181 14496 15181 14499 15182 7747 15182 7749 15182 14499 15183 14500 15183 7747 15183 7732 15184 14501 15184 14502 15184 7747 15185 14500 15185 7745 15185 7735 15186 14501 15186 7733 15186 7749 15187 14505 15187 14504 15187 7749 15188 7747 15188 14505 15188 14508 15189 7728 15189 14504 15189 7731 15190 14508 15190 7732 15190 7733 15191 14509 15191 14507 15191 7735 15192 7733 15192 14507 15192 14507 15193 14506 15193 7740 15193 14506 15194 14505 15194 7747 15194 14499 15195 14503 15195 14500 15195 14500 15196 14502 15196 14501 15196 14508 15197 14510 15197 14509 15197 14506 15198 14513 15198 14505 15198 14506 15199 14507 15199 14512 15199 14506 15200 14512 15200 14513 15200 14511 15201 14510 15201 14505 15201 14505 15202 14513 15202 14511 15202 14511 15203 14513 15203 14512 15203 14514 15204 7759 15204 14515 15204 7759 15205 14514 15205 7774 15205 7771 15206 14516 15206 14517 15206 7759 15207 7760 15207 14515 15207 7773 15208 14516 15208 7771 15208 7771 15209 14517 15209 7767 15209 7767 15210 14517 15210 7763 15210 14520 15211 14521 15211 7760 15211 7759 15212 14520 15212 7760 15212 14520 15213 7759 15213 7774 15213 14522 15214 7774 15214 7773 15214 14522 15215 7773 15215 7771 15215 14524 15216 7762 15216 7760 15216 7762 15217 14525 15217 7763 15217 14522 15218 14520 15218 7774 15218 14514 15219 14515 15219 14519 15219 14516 15220 14518 15220 14517 15220 14524 15221 14526 15221 14525 15221 14522 15222 14528 15222 14520 15222 14527 15223 14528 15223 14522 15223 14520 15224 14528 15224 14521 15224 14522 15225 14523 15225 14527 15225 14527 15226 14526 15226 14528 15226 14524 15227 14528 15227 14526 15227 14529 15228 14530 15228 7730 15228 7729 15229 14530 15229 14531 15229 7778 15230 14532 15230 14533 15230 7768 15231 7765 15231 14529 15231 7729 15232 14531 15232 7734 15232 7734 15233 14532 15233 7780 15233 7780 15234 14532 15234 7778 15234 7775 15235 14533 15235 7765 15235 7768 15236 14535 15236 14534 15236 14535 15237 7730 15237 7729 15237 14536 15238 7729 15238 7734 15238 7776 15239 14538 15239 14539 15239 7780 15240 14539 15240 14537 15240 7776 15241 14539 15241 7778 15241 7778 15242 14539 15242 7780 15242 14536 15243 14535 15243 7729 15243 14535 15244 14543 15244 14534 15244 14538 15245 14534 15245 14540 15245 14541 15246 14540 15246 14543 15246 14542 15247 14544 15247 14543 15247 14542 15248 14541 15248 14544 15248 14545 15249 7781 15249 7785 15249 14545 15250 14546 15250 7781 15250 7781 15251 14546 15251 7782 15251 7852 15252 14546 15252 14547 15252 7848 15253 14547 15253 14548 15253 7849 15254 14548 15254 14549 15254 7791 15255 14549 15255 14545 15255 7785 15256 7789 15256 14545 15256 7852 15257 14547 15257 7850 15257 7850 15258 14547 15258 7848 15258 7849 15259 14549 15259 7793 15259 7785 15260 14550 15260 7789 15260 7785 15261 14551 15261 14550 15261 14552 15262 7782 15262 7852 15262 14552 15263 7852 15263 7850 15263 14553 15264 7850 15264 7848 15264 14550 15265 14554 15265 7791 15265 7791 15266 14554 15266 7793 15266 14553 15267 14552 15267 7850 15267 14546 15268 14545 15268 14549 15268 14546 15269 14549 15269 14547 15269 14554 15270 14550 15270 14555 15270 14554 15271 14556 15271 14553 15271 14551 15272 14557 15272 14555 15272 7876 15273 14559 15273 14560 15273 7866 15274 14560 15274 14561 15274 7860 15275 14562 15275 14558 15275 7882 15276 14559 15276 7879 15276 7879 15277 14559 15277 7876 15277 7876 15278 14560 15278 7866 15278 7866 15279 14561 15279 7864 15279 7864 15280 14561 15280 7862 15280 7860 15281 14563 15281 14564 15281 7860 15282 7886 15282 14563 15282 14567 15283 7858 15283 14564 15283 14567 15284 7862 15284 7858 15284 7876 15285 14568 15285 14566 15285 7864 15286 14568 15286 7866 15286 14566 15287 14565 15287 7879 15287 14565 15288 14563 15288 7882 15288 14559 15289 14562 15289 14561 15289 14569 15290 14570 15290 14568 15290 14565 15291 14572 15291 14563 15291 14563 15292 14572 15292 14569 15292 14567 15293 14564 15293 14569 15293 14570 15294 14569 15294 14572 15294 14568 15295 14570 15295 14571 15295 14573 15296 7861 15296 14574 15296 7861 15297 14573 15297 7863 15297 7865 15298 14573 15298 14575 15298 7869 15299 14575 15299 14576 15299 7899 15300 14576 15300 14577 15300 7861 15301 7896 15301 14574 15301 7865 15302 14575 15302 7867 15302 7867 15303 14575 15303 7869 15303 7869 15304 14576 15304 7900 15304 7899 15305 14574 15305 7896 15305 14578 15306 14579 15306 7896 15306 14580 15307 7865 15307 7867 15307 14579 15308 14582 15308 7899 15308 7900 15309 14582 15309 14581 15309 7899 15310 14582 15310 7900 15310 14580 15311 14578 15311 7865 15311 7899 15312 7896 15312 14579 15312 14575 15313 14577 15313 14576 15313 14573 15314 14577 15314 14575 15314 14582 15315 14583 15315 14584 15315 14583 15316 14585 15316 14584 15316 14586 15317 7812 15317 7813 15317 7812 15318 14586 15318 7918 15318 7915 15319 14588 15319 14589 15319 7818 15320 14590 15320 14587 15320 7918 15321 14588 15321 7916 15321 7916 15322 14588 15322 7915 15322 7920 15323 14590 15323 7818 15323 14591 15324 14592 15324 7816 15324 7813 15325 14591 15325 7816 15325 7813 15326 7812 15326 14591 15326 14591 15327 7812 15327 7918 15327 7920 15328 14592 15328 14595 15328 7919 15329 14595 15329 14594 15329 14594 15330 14593 15330 7916 15330 7818 15331 7816 15331 14592 15331 14586 15332 14587 15332 14590 15332 14586 15333 14590 15333 14588 15333 14598 15334 14599 15334 14593 15334 14591 15335 14596 15335 14592 15335 14593 15336 14594 15336 14598 15336 14601 15337 7815 15337 7881 15337 14601 15338 14602 15338 7815 15338 7817 15339 14602 15339 14603 15339 7822 15340 14603 15340 14604 15340 7826 15341 14604 15341 14605 15341 7831 15342 14605 15342 14601 15342 7881 15343 7831 15343 14601 15343 7819 15344 14603 15344 7822 15344 7881 15345 14607 15345 14606 15345 7881 15346 7815 15346 14607 15346 14608 15347 7817 15347 7819 15347 7826 15348 14609 15348 7824 15348 7824 15349 14609 15349 14610 15349 7819 15350 7822 15350 14608 15350 14608 15351 14607 15351 7817 15351 7828 15352 7831 15352 14606 15352 14602 15353 14605 15353 14604 15353 14602 15354 14604 15354 14603 15354 14609 15355 14611 15355 14610 15355 14608 15356 14610 15356 14612 15356 14609 15357 14606 15357 14613 15357 14612 15358 14611 15358 14613 15358 14614 15359 7921 15359 7820 15359 7820 15360 7821 15360 14614 15360 7922 15361 14618 15361 7821 15361 7820 15362 14620 15362 14619 15362 7820 15363 7921 15363 14620 15363 14621 15364 7921 15364 7902 15364 14621 15365 7902 15365 7904 15365 14622 15366 7904 15366 7906 15366 14623 15367 7821 15367 14619 15367 14623 15368 7922 15368 7821 15368 7906 15369 14624 15369 14622 15369 7922 15370 14624 15370 7906 15370 14621 15371 14620 15371 7921 15371 14623 15372 14625 15372 14624 15372 14624 15373 14625 15373 14622 15373 14620 15374 14626 15374 14619 15374 14621 15375 14622 15375 14626 15375 14623 15376 14619 15376 14626 15376 14625 15377 14626 15377 14622 15377 14626 15378 14627 15378 14623 15378 14623 15379 14627 15379 14625 15379 14628 15380 7877 15380 7868 15380 7842 15381 14630 15381 14631 15381 7872 15382 14631 15382 14632 15382 7880 15383 14630 15383 7832 15383 7832 15384 14630 15384 7842 15384 7842 15385 14631 15385 7923 15385 7868 15386 7877 15386 14633 15386 14633 15387 7877 15387 14634 15387 14634 15388 7877 15388 7878 15388 14634 15389 7880 15389 7832 15389 14636 15390 14637 15390 7870 15390 7870 15391 14637 15391 7872 15391 7923 15392 14637 15392 14635 15392 7832 15393 7842 15393 14635 15393 7923 15394 14635 15394 7842 15394 14636 15395 7868 15395 14633 15395 14629 15396 14632 15396 14631 15396 14635 15397 14637 15397 14639 15397 14637 15398 14638 15398 14639 15398 14639 15399 14641 15399 14640 15399 14639 15400 14638 15400 14641 15400 7892 15401 14642 15401 7890 15401 7898 15402 14644 15402 14645 15402 7894 15403 14645 15403 14646 15403 7889 15404 14643 15404 7859 15404 7859 15405 14644 15405 7898 15405 7898 15406 14645 15406 7897 15406 7894 15407 14646 15407 7892 15407 7892 15408 14647 15408 14648 15408 14647 15409 7892 15409 7890 15409 14649 15410 7890 15410 7889 15410 14649 15411 7889 15411 7859 15411 14650 15412 14649 15412 7859 15412 14651 15413 7894 15413 14648 15413 7894 15414 14651 15414 7897 15414 14649 15415 14647 15415 7890 15415 14642 15416 14646 15416 14645 15416 14642 15417 14645 15417 14643 15417 14651 15418 14653 15418 14652 15418 14653 15419 14654 15419 14652 15419 14652 15420 14655 15420 14650 15420 14649 15421 14656 15421 14647 15421 14647 15422 14657 15422 14653 15422 14648 15423 14647 15423 14653 15423 14654 15424 14653 15424 14657 15424 14652 15425 14654 15425 14655 15425 14655 15426 14656 15426 14650 15426 14658 15427 14659 15427 7805 15427 7796 15428 14662 15428 14663 15428 7802 15429 14663 15429 14658 15429 7924 15430 14659 15430 7787 15430 7787 15431 14660 15431 7786 15431 7802 15432 14664 15432 14665 15432 14664 15433 7805 15433 7924 15433 14666 15434 7924 15434 7787 15434 14667 15435 7786 15435 14668 15435 14665 15436 7796 15436 7798 15436 7796 15437 14669 15437 7792 15437 7786 15438 7790 15438 14668 15438 7792 15439 14669 15439 7790 15439 7798 15440 7802 15440 14665 15440 14659 15441 14663 15441 14662 15441 14660 15442 14662 15442 14661 15442 14659 15443 14662 15443 14660 15443 14669 15444 14665 15444 14670 15444 14670 15445 14671 15445 14668 15445 14668 15446 14672 15446 14667 15446 14665 15447 14664 15447 14670 15447 14668 15448 14671 15448 14672 15448 14671 15449 14673 15449 14672 15449 14671 15450 14670 15450 14673 15450 7801 15451 14675 15451 7931 15451 7926 15452 14676 15452 14677 15452 7926 15453 14677 15453 14678 15453 7926 15454 14678 15454 7803 15454 7803 15455 14679 15455 7800 15455 14680 15456 7801 15456 14682 15456 14682 15457 7931 15457 7930 15457 7926 15458 14684 15458 14683 15458 7803 15459 14684 15459 7926 15459 14683 15460 14682 15460 7930 15460 7803 15461 7800 15461 14681 15461 14676 15462 14678 15462 14677 15462 14675 15463 14678 15463 14676 15463 14681 15464 14685 15464 14684 15464 14685 15465 14686 15465 14684 15465 14683 15466 14684 15466 14687 15466 14687 15467 14682 15467 14683 15467 14687 15468 14688 15468 14682 15468 14680 15469 14682 15469 14688 15469 14684 15470 14686 15470 14687 15470 14686 15471 14688 15471 14687 15471 14689 15472 7845 15472 7795 15472 14689 15473 14690 15473 7845 15473 7847 15474 14690 15474 14691 15474 7932 15475 14692 15475 14693 15475 7797 15476 14693 15476 14694 15476 7795 15477 14694 15477 14689 15477 7845 15478 14690 15478 7847 15478 7929 15479 14692 15479 7932 15479 7797 15480 14694 15480 7794 15480 7795 15481 14695 15481 14696 15481 14699 15482 7797 15482 7794 15482 7799 15483 14699 15483 14700 15483 14697 15484 14695 15484 7847 15484 7794 15485 7795 15485 14696 15485 14689 15486 14694 15486 14690 15486 14690 15487 14694 15487 14693 15487 14691 15488 14693 15488 14692 15488 14690 15489 14693 15489 14691 15489 14700 15490 14703 15490 14698 15490 14695 15491 14697 15491 14704 15491 14703 15492 14704 15492 14697 15492 14696 15493 14695 15493 14701 15493 14699 15494 14696 15494 14701 15494 14702 15495 14701 15495 14704 15495 14700 15496 14702 15496 14703 15496 14704 15497 14703 15497 14702 15497 14705 15498 7755 15498 7756 15498 14705 15499 14706 15499 7755 15499 7753 15500 14706 15500 14707 15500 7751 15501 7750 15501 14708 15501 7757 15502 14709 15502 14705 15502 7756 15503 7757 15503 14705 15503 7755 15504 14706 15504 7753 15504 7753 15505 14707 15505 7750 15505 7751 15506 14708 15506 7770 15506 7769 15507 14709 15507 7772 15507 7772 15508 14709 15508 7757 15508 7756 15509 14710 15509 7757 15509 14710 15510 7755 15510 14711 15510 14711 15511 7755 15511 7753 15511 14713 15512 14712 15512 7750 15512 7772 15513 14715 15513 7769 15513 7770 15514 14715 15514 14713 15514 7769 15515 14715 15515 7770 15515 7772 15516 7757 15516 14714 15516 14705 15517 14709 15517 14706 15517 7750 15518 14707 15518 14708 15518 14706 15519 14709 15519 14707 15519 14714 15520 14716 15520 14715 15520 14713 15521 14715 15521 14717 15521 14718 15522 14711 15522 14712 15522 14718 15523 14719 15523 14711 15523 14711 15524 14719 15524 14714 15524 14710 15525 14711 15525 14714 15525 14719 15526 14716 15526 14714 15526 14720 15527 10668 15527 10667 15527 14720 15528 14721 15528 10668 15528 10668 15529 14721 15529 10669 15529 10669 15530 14721 15530 14722 15530 10669 15531 14722 15531 10659 15531 10659 15532 14722 15532 10660 15532 10670 15533 14724 15533 10661 15533 10661 15534 14724 15534 10663 15534 10662 15535 14725 15535 10664 15535 10665 15536 14726 15536 10666 15536 10653 15537 10669 15537 10659 15537 10670 15538 10661 15538 10658 15538 10658 15539 10653 15539 10659 15539 14720 15540 14726 15540 14721 15540 14721 15541 14726 15541 14722 15541 14722 15542 14725 15542 14723 15542 10655 15543 14728 15543 10657 15543 10657 15544 14728 15544 10658 15544 14728 15545 10652 15545 10658 15545 10652 15546 14727 15546 10650 15546 14727 15547 10652 15547 14728 15547 10149 15548 14730 15548 10143 15548 10148 15549 14730 15549 14731 15549 10145 15550 14734 15550 14729 15550 10144 15551 10145 15551 14729 15551 10148 15552 14731 15552 10142 15552 10142 15553 14731 15553 10147 15553 10146 15554 14733 15554 10140 15554 10140 15555 14733 15555 10139 15555 10138 15556 14734 15556 10145 15556 10144 15557 10149 15557 10154 15557 10152 15558 10151 15558 10139 15558 10147 15559 10141 15559 10150 15559 10146 15560 10151 15560 10141 15560 10150 15561 10155 15561 10142 15561 14731 15562 14733 15562 14732 15562 10788 15563 14736 15563 10150 15563 14735 15564 10787 15564 14738 15564 14735 15565 14736 15565 10788 15565 10155 15566 14737 15566 14738 15566 14736 15567 14735 15567 14737 15567 14735 15568 14738 15568 14737 15568 14739 15569 14740 15569 10521 15569 10521 15570 14740 15570 10513 15570 10512 15571 14740 15571 14741 15571 10514 15572 14741 15572 14742 15572 10518 15573 14743 15573 14744 15573 10520 15574 14744 15574 14739 15574 10523 15575 14741 15575 10514 15575 10514 15576 14742 15576 10516 15576 10507 15577 10521 15577 10506 15577 10510 15578 10512 15578 10523 15578 10504 15579 10518 15579 10519 15579 10517 15580 10509 15580 10515 15580 10515 15581 10511 15581 10516 15581 10510 15582 10506 15582 10512 15582 10519 15583 10520 15583 10504 15583 14741 15584 14743 15584 14742 15584 10508 15585 14746 15585 10511 15585 10509 15586 10508 15586 10511 15586 10511 15587 14746 15587 10510 15587 10507 15588 10503 15588 14745 15588 14745 15589 14746 15589 10508 15589 14747 15590 14745 15590 10503 15590 10580 15591 14749 15591 10572 15591 10571 15592 14749 15592 14750 15592 10577 15593 14753 15593 14748 15593 10572 15594 14749 15594 10571 15594 10581 15595 14750 15595 10573 15595 10582 15596 14751 15596 10574 15596 10576 15597 14753 15597 10578 15597 10578 15598 14753 15598 10577 15598 10563 15599 10566 15599 10577 15599 10579 15600 10580 15600 10563 15600 10568 15601 10571 15601 10581 15601 10582 15602 10567 15602 10570 15602 10575 15603 10567 15603 10574 15603 10574 15604 10567 15604 10582 15604 14748 15605 14753 15605 14749 15605 14750 15606 14752 15606 14751 15606 10567 15607 14755 15607 10569 15607 10565 15608 10568 15608 10563 15608 9582 15609 14756 15609 14754 15609 10564 15610 9582 15610 14754 15610 14755 15611 14756 15611 10569 15611 14756 15612 14755 15612 14754 15612 10826 15613 14758 15613 10825 15613 10823 15614 14759 15614 14760 15614 10820 15615 14761 15615 14762 15615 10817 15616 14763 15616 14757 15616 10827 15617 10817 15617 14757 15617 10825 15618 14759 15618 10824 15618 10822 15619 14761 15619 10821 15619 10821 15620 14761 15620 10820 15620 10820 15621 14762 15621 10819 15621 10827 15622 10782 15622 10817 15622 10780 15623 10826 15623 10825 15623 10780 15624 10825 15624 10824 15624 10786 15625 10823 15625 10822 15625 10761 15626 10786 15626 10822 15626 10816 15627 10817 15627 10783 15627 14759 15628 14763 15628 14762 15628 14758 15629 14763 15629 14759 15629 10784 15630 10762 15630 10785 15630 10784 15631 14764 15631 10762 15631 8918 15632 14765 15632 10781 15632 10781 15633 14766 15633 10783 15633 10783 15634 14766 15634 10784 15634 14766 15635 14764 15635 10784 15635 8918 15636 14764 15636 14765 15636 14765 15637 14766 15637 10781 15637 14767 15638 14768 15638 10867 15638 10867 15639 14768 15639 10866 15639 10866 15640 14768 15640 14769 15640 10863 15641 14769 15641 14770 15641 10864 15642 14770 15642 14771 15642 10873 15643 14771 15643 14772 15643 10871 15644 14772 15644 14773 15644 10869 15645 14773 15645 14767 15645 10866 15646 14769 15646 10865 15646 10865 15647 14769 15647 10863 15647 10863 15648 14770 15648 10864 15648 10873 15649 14772 15649 10872 15649 10871 15650 14773 15650 10870 15650 10870 15651 14773 15651 10869 15651 9943 15652 9938 15652 10869 15652 10868 15653 10867 15653 9943 15653 9942 15654 10865 15654 10863 15654 9941 15655 10863 15655 10864 15655 9939 15656 10870 15656 9938 15656 9939 15657 10871 15657 10870 15657 10871 15658 9939 15658 10872 15658 9942 15659 9943 15659 10866 15659 10870 15660 10869 15660 9938 15660 14767 15661 14773 15661 14768 15661 14769 15662 14773 15662 14772 15662 14774 15663 14775 15663 9938 15663 9942 15664 14777 15664 9943 15664 14777 15665 9942 15665 9941 15665 14777 15666 9941 15666 14776 15666 9943 15667 14777 15667 9938 15667 14775 15668 14774 15668 14776 15668 10875 15669 14779 15669 14780 15669 10879 15670 14780 15670 14781 15670 10880 15671 14781 15671 14782 15671 10881 15672 14782 15672 14783 15672 10877 15673 14783 15673 14778 15673 14784 15674 10876 15674 14785 15674 14785 15675 10876 15675 10875 15675 14788 15676 14789 15676 10881 15676 14788 15677 10877 15677 14784 15677 14778 15678 14783 15678 14779 15678 14779 15679 14783 15679 14782 15679 14780 15680 14782 15680 14781 15680 14788 15681 14790 15681 14789 15681 14791 15682 14785 15682 14786 15682 14791 15683 14792 15683 14785 15683 14790 15684 14788 15684 14792 15684 14789 15685 14790 15685 14791 15685 14793 15686 10091 15686 10090 15686 14793 15687 14794 15687 10091 15687 10091 15688 14794 15688 10092 15688 10093 15689 14795 15689 14796 15689 10086 15690 14797 15690 14798 15690 10089 15691 14799 15691 14800 15691 10092 15692 14795 15692 10093 15692 10087 15693 14799 15693 10088 15693 10088 15694 14799 15694 10089 15694 10089 15695 14800 15695 10090 15695 10102 15696 10088 15696 10089 15696 10087 15697 10102 15697 10101 15697 10087 15698 10101 15698 10086 15698 14794 15699 14799 15699 14795 15699 14795 15700 14798 15700 14796 15700 10102 15701 10103 15701 14801 15701 10101 15702 14802 15702 10104 15702 14803 15703 10099 15703 10104 15703 10105 15704 14803 15704 14801 15704 14802 15705 14803 15705 10104 15705 14803 15706 14804 15706 14801 15706 14801 15707 14804 15707 14802 15707 8011 15708 14807 15708 14808 15708 10417 15709 10414 15709 7997 15709 10437 15710 8011 15710 8013 15710 10416 15711 7997 15711 10412 15711 10416 15712 10433 15712 7999 15712 7999 15713 10433 15713 10434 15713 7999 15714 10434 15714 10429 15714 8013 15715 10429 15715 10435 15715 7999 15716 10429 15716 8013 15716 10424 15717 10422 15717 8011 15717 10433 15718 14810 15718 10434 15718 10429 15719 14810 15719 10435 15719 10421 15720 14813 15720 10419 15720 10421 15721 14812 15721 14813 15721 10419 15722 14813 15722 10417 15722 10414 15723 14811 15723 10412 15723 10414 15724 14813 15724 14811 15724 14814 15725 14812 15725 14810 15725 14815 15726 14816 15726 8026 15726 8026 15727 14816 15727 8036 15727 8032 15728 14816 15728 14817 15728 8029 15729 14817 15729 14818 15729 8025 15730 14818 15730 14815 15730 8036 15731 14816 15731 8032 15731 8032 15732 14817 15732 8029 15732 8026 15733 10613 15733 10614 15733 10612 15734 8026 15734 8036 15734 10605 15735 10604 15735 8032 15735 10617 15736 8025 15736 10616 15736 10617 15737 8028 15737 8025 15737 8029 15738 10608 15738 10607 15738 8032 15739 8029 15739 10606 15739 10604 15740 10603 15740 8032 15740 10602 15741 10612 15741 8036 15741 10616 15742 8025 15742 10615 15742 10609 15743 14819 15743 10608 15743 10609 15744 14820 15744 14819 15744 10609 15745 10617 15745 14820 15745 10607 15746 14819 15746 10606 15746 10606 15747 14819 15747 10605 15747 10602 15748 14821 15748 14822 15748 10602 15749 10603 15749 14821 15749 14821 15750 14823 15750 14822 15750 10614 15751 14822 15751 10615 15751 10615 15752 14820 15752 10616 15752 10617 15753 10616 15753 14820 15753 14823 15754 14820 15754 14822 15754 14819 15755 14820 15755 14823 15755 1645 15756 14824 15756 14825 15756 14827 15757 14829 15757 14828 15757 14835 15758 14836 15758 14837 15758 14842 15759 14845 15759 14843 15759 14847 15760 14849 15760 14848 15760 14856 15761 14857 15761 14855 15761 14857 15762 14856 15762 14858 15762 14857 15763 14853 15763 14855 15763 14856 15764 14860 15764 14861 15764 14865 15765 14864 15765 958 15765 958 15766 14864 15766 14866 15766 14867 15767 958 15767 14866 15767 14865 15768 958 15768 14868 15768 14867 15769 14829 15769 14868 15769 14837 15770 14869 15770 14838 15770 14870 6 14871 6 14836 6 14872 15771 14873 15771 14836 15771 14874 15772 14875 15772 14826 15772 14848 15773 14849 15773 1288 15773 949 15774 14881 15774 14882 15774 959 15775 14883 15775 14869 15775 14885 15776 14886 15776 14840 15776 14840 15777 14886 15777 14887 15777 14887 15778 14879 15778 14840 15778 14891 15779 14846 15779 14848 15779 14879 15780 14887 15780 14880 15780 14893 15781 14897 15781 14895 15781 14899 15782 14900 15782 14901 15782 14903 15783 14901 15783 14902 15783 14900 15784 14904 15784 14902 15784 14894 15785 14914 15785 14911 15785 14914 15786 14894 15786 14916 15786 14898 15787 14909 15787 14894 15787 14916 15788 14894 15788 14909 15788 14908 15789 14910 15789 277 15789 14915 15790 14917 15790 277 15790 14917 15791 14915 15791 14918 15791 14906 15792 14899 15792 14920 15792 1645 15793 14922 15793 14924 15793 14858 15794 14859 15794 14925 15794 14926 15795 14923 15795 14854 15795 14858 15796 14926 15796 14854 15796 14924 15797 14884 15797 14927 15797 14924 15798 14927 15798 14923 15798 14923 15799 14927 15799 14854 15799 14918 15800 14863 15800 14865 15800 14838 15801 14869 15801 14933 15801 14829 15802 14934 15802 14868 15802 14922 15803 14936 15803 14883 15803 14883 15804 14935 15804 14869 15804 14921 15805 14937 15805 14936 15805 14920 15806 14899 15806 14937 15806 14938 15807 14937 15807 14899 15807 14876 15808 14940 15808 14939 15808 14940 15809 14849 15809 14877 15809 14877 15810 14942 15810 14941 15810 14909 15811 14944 15811 14943 15811 14865 15812 14945 15812 14944 15812 14865 15813 14868 15813 14945 15813 14946 15814 14947 15814 14948 15814 14946 15815 14949 15815 14947 15815 14949 15816 14930 15816 14947 15816 14951 15817 14935 15817 14952 15817 14955 15818 14953 15818 14956 15818 14957 15819 14958 15819 14955 15819 14954 15820 14953 15820 14955 15820 14960 15821 14961 15821 14962 15821 14967 15822 14960 15822 14962 15822 14963 15823 14968 15823 14942 15823 14971 15824 14969 15824 14970 15824 14969 15825 14931 15825 14932 15825 14945 15826 14970 15826 14965 15826 14945 15827 14965 15827 14964 15827 14909 15828 14943 15828 14916 15828 14972 15829 14973 15829 14974 15829 14974 15830 14973 15830 14975 15830 14975 15831 14973 15831 14976 15831 14928 15832 14975 15832 14976 15832 14881 15833 14972 15833 14911 15833 952 15834 14977 15834 14859 15834 14891 15835 1288 15835 14889 15835 14968 15836 14941 15836 14942 15836 14940 15837 14941 15837 14969 15837 14949 15838 14940 15838 14969 15838 14942 15839 14962 15839 14963 15839 14942 15840 14943 15840 14962 15840 14939 15841 14940 15841 14950 15841 14950 15842 14954 15842 14939 15842 14950 15843 14940 15843 14949 15843 14943 15844 14944 15844 14967 15844 14954 15845 14955 15845 14937 15845 14936 15846 14937 15846 14958 15846 14934 15847 14971 15847 14945 15847 14958 15848 14935 15848 14936 15848 14947 15849 14931 15849 14971 15849 14934 15850 14947 15850 14971 15850 14951 15851 14933 15851 14935 15851 14979 15852 14980 15852 14950 15852 14981 15853 14948 15853 14951 15853 14858 15854 14956 15854 14857 15854 14984 15855 14853 15855 14983 15855 14853 15856 14857 15856 14983 15856 14854 15857 14956 15857 14858 15857 14952 15858 14957 15858 14959 15858 14957 15859 14984 15859 14959 15859 14959 15860 14984 15860 14981 15860 14981 15861 14984 15861 14983 15861 14980 15862 14983 15862 14982 15862 14981 15863 14983 15863 14980 15863 14985 15864 14986 15864 14968 15864 14968 15865 14987 15865 14985 15865 14968 15866 14961 15866 14987 15866 14966 15867 14965 15867 14988 15867 14989 15868 14965 15868 14970 15868 14988 15869 14965 15869 14989 15869 14975 15870 14990 15870 14991 15870 14972 15871 14960 15871 14928 15871 14988 15872 14991 15872 14990 15872 14990 15873 14960 15873 14966 15873 14966 15874 14960 15874 14964 15874 14985 15875 14991 15875 14988 15875 14911 15876 14972 15876 14992 15876 14972 15877 14928 15877 14992 15877 14899 15878 14977 15878 14938 15878 14993 15879 14994 15879 14995 15879 14995 15880 14994 15880 14996 15880 14995 15881 14997 15881 14999 15881 14861 15882 15000 15882 14862 15882 14995 15883 14999 15883 15001 15883 14862 15884 15000 15884 15003 15884 14973 15885 14996 15885 14976 15885 14906 15886 14904 15886 14899 15886 14900 15887 14899 15887 14904 15887 14903 15888 15005 15888 14824 15888 15006 15889 15007 15889 15005 15889 15005 15890 15007 15890 14825 15890 15006 15891 14906 15891 14922 15891 14897 15892 14898 15892 14894 15892 14915 15893 15008 15893 15009 15893 14892 15894 14915 15894 15009 15894 14910 15895 15011 15895 15010 15895 15010 15896 14915 15896 14910 15896 14902 15897 14905 15897 14903 15897 15006 15898 15005 15898 14903 15898 14896 15899 14893 15899 14892 15899 15013 15900 15012 15900 15003 15900 15017 15901 14844 15901 15015 15901 15015 15902 14843 15902 15013 15902 15015 15903 14844 15903 14843 15903 15016 15904 14999 15904 14997 15904 14886 15905 14845 15905 14887 15905 14845 15906 14842 15906 14881 15906 14972 15907 15017 15907 14973 15907 15003 15908 15012 15908 14862 15908 14862 15909 15012 15909 14856 15909 14856 15910 15012 15910 14859 15910 14978 15911 14851 15911 14889 15911 14995 15912 15020 15912 15019 15912 15021 15913 15024 15913 14832 15913 15019 15914 15020 15914 15021 15914 15021 15915 15020 15915 15022 15915 14995 15916 15001 15916 15020 15916 14871 15917 15025 15917 14872 15917 14833 15918 14874 15918 14866 15918 14993 15919 15018 15919 14994 15919 15004 15920 15018 15920 14976 15920 14838 15921 14829 15921 15026 15921 15026 15922 15027 15922 14835 15922 14827 15923 14831 15923 14829 15923 14829 15924 14831 15924 15026 15924 15028 15925 14839 15925 14877 15925 14847 15926 15031 15926 15030 15926 14850 15927 15033 15927 14851 15927 14830 15928 14833 15928 15034 15928 14832 15929 15034 15929 14833 15929 15035 15930 15024 15930 15025 15930 15025 15931 15027 15931 15035 15931 15036 15932 15032 15932 15037 15932 15037 15933 15032 15933 15028 15933 15030 15934 15033 15934 15038 15934 15038 15935 15033 15935 15039 15935 15038 15936 15040 15936 15030 15936 15030 15937 15040 15937 15028 15937 15039 15938 15033 15938 15036 15938 15038 15939 15039 15939 15040 15939 15040 15940 15039 15940 15036 15940 15041 15941 15026 15941 15042 15941 15042 15942 15026 15942 14831 15942 15026 15943 15041 15943 15035 15943 15035 15944 15041 15944 15043 15944 15044 15945 15042 15945 15034 15945 15034 15946 15042 15946 14831 15946 15044 15947 15035 15947 15043 15947 15042 15948 15044 15948 15041 15948 15041 15949 15044 15949 15043 15949 14847 15950 14890 15950 15031 15950 15029 15951 14886 15951 14885 15951 14836 15952 14835 15952 14870 15952 14826 15953 14875 15953 14827 15953 14833 15954 14875 15954 14874 15954 15012 15955 14850 15955 14852 15955 14925 15956 14901 15956 14919 15956 14919 15957 14923 15957 14926 15957 14926 15958 14925 15958 14919 15958 14833 15959 14863 15959 15018 15959 14839 15960 14841 15960 14877 15960 14927 15961 15023 15961 14854 15961 14972 15962 14881 15962 15017 15962 15017 15963 14881 15963 14842 15963 14859 15964 15012 15964 15045 15964 14852 15965 14851 15965 15045 15965 14867 15966 14868 15966 958 15966 14907 15967 14892 15967 15011 15967 15011 15968 14910 15968 14907 15968 14901 15969 14977 15969 14899 15969 14906 15970 14903 15970 14905 15970 14892 15971 14907 15971 14896 15971 15037 15972 15028 15972 15040 15972 15036 15973 15037 15973 15040 15973 952 15974 14859 15974 14978 15974 3496 15975 15046 15975 15047 15975 15051 15976 15052 15976 15053 15976 15057 15977 15058 15977 15059 15977 15057 15978 15064 15978 15065 15978 15066 15979 15067 15979 15068 15979 15069 15980 15070 15980 15071 15980 15073 15981 15074 15981 15075 15981 15079 15982 15080 15982 15081 15982 15082 15983 15079 15983 15081 15983 15083 15984 15074 15984 15084 15984 15082 15985 15085 15985 15086 15985 15088 15986 15051 15986 15089 15986 15089 15987 15051 15987 15091 15987 15089 15988 15090 15988 2909 15988 15050 15989 15049 15989 15089 15989 15093 15990 15050 15990 15089 15990 15094 15991 15095 15991 15058 15991 15058 15992 15095 15992 15096 15992 15058 15993 15097 15993 15059 15993 15098 15994 15099 15994 15050 15994 15093 15995 15091 15995 15050 15995 15089 15996 15091 15996 15093 15996 15105 15997 15104 15997 2086 15997 15108 15998 15092 15998 15096 15998 15097 15999 15096 15999 15092 15999 15111 16000 15112 16000 15067 16000 15103 16001 15110 16001 15067 16001 15113 16002 15078 16002 15114 16002 15113 16003 15115 16003 15078 16003 15109 16004 15114 16004 15078 16004 15110 16005 15103 16005 15101 16005 15118 16006 15117 16006 15119 16006 15121 16007 15119 16007 15117 16007 15123 16008 15124 16008 2168 16008 15126 16009 2168 16009 15125 16009 15127 16010 15128 16010 15125 16010 15134 16011 15135 16011 15136 16011 15134 16012 15137 16012 15135 16012 15118 16013 15138 16013 15134 16013 15136 16014 15135 16014 3496 16014 15120 16015 15133 16015 15139 16015 15132 16016 15131 16016 3496 16016 15142 16017 15141 16017 15126 16017 15146 16018 15143 16018 15145 16018 15142 16019 15147 16019 15148 16019 15129 16020 15123 16020 15144 16020 15149 16021 15123 16021 15150 16021 15150 16022 15123 16022 15141 16022 15146 16023 15145 16023 2114 16023 15152 16024 2114 16024 15145 16024 15148 16025 15080 16025 15154 16025 15154 16026 15084 16026 15153 16026 15107 16027 15106 16027 15151 16027 15151 16028 15106 16028 15148 16028 15135 16029 15052 16029 15140 16029 15140 16030 15051 16030 3140 16030 15140 16031 15051 16031 15088 16031 15159 16032 15160 16032 15049 16032 15152 16033 15162 16033 15107 16033 15162 16034 15161 16034 15107 16034 15107 16035 15161 16035 15092 16035 15145 16036 15163 16036 15162 16036 15164 16037 15163 16037 15149 16037 15164 16038 15165 16038 15163 16038 15100 16039 15166 16039 15165 16039 15100 16040 15077 16040 15166 16040 15102 16041 15168 16041 15167 16041 15133 16042 15170 16042 15169 16042 15088 16043 15171 16043 15170 16043 15172 16044 15173 16044 15174 16044 15172 16045 15175 16045 15173 16045 15175 16046 15172 16046 15176 16046 15174 16047 15156 16047 15155 16047 15177 16048 15161 16048 15178 16048 15180 16049 15182 16049 15181 16049 15178 16050 15182 16050 15180 16050 15177 16051 15178 16051 15183 16051 15184 16052 15185 16052 15186 16052 15186 16053 15185 16053 15187 16053 15188 16054 15187 16054 15185 16054 15190 16055 15184 16055 15186 16055 15187 16056 15188 16056 15168 16056 15195 16057 15194 16057 15189 16057 15195 16058 15193 16058 15194 16058 15195 16059 15157 16059 15193 16059 15193 16060 15157 16060 15158 16060 15145 16061 15162 16061 15152 16061 15196 16062 15197 16062 15198 16062 15196 16063 15199 16063 15200 16063 15196 16064 15200 16064 15201 16064 15052 16065 15201 16065 15200 16065 15105 16066 2086 16066 15138 16066 15134 16067 15202 16067 15197 16067 15134 16068 15138 16068 15202 16068 15150 16069 15074 16069 15073 16069 15084 16070 15074 16070 15141 16070 2806 16071 15100 16071 15164 16071 15164 16072 15114 16072 15109 16072 15188 16073 15167 16073 15168 16073 15188 16074 15193 16074 15167 16074 15173 16075 15193 16075 15156 16075 15173 16076 15166 16076 15193 16076 15168 16077 15186 16077 15187 16077 15168 16078 15169 16078 15186 16078 15165 16079 15166 16079 15175 16079 15169 16080 15170 16080 15186 16080 15190 16081 15186 16081 15170 16081 15175 16082 15181 16082 15163 16082 15170 16083 15189 16083 15190 16083 15170 16084 15171 16084 15189 16084 15155 16085 15157 16085 15174 16085 15174 16086 15157 16086 15195 16086 15160 16087 15174 16087 15195 16087 15177 16088 15159 16088 15161 16088 15177 16089 15174 16089 15159 16089 15205 16090 15176 16090 15206 16090 15204 16091 15176 16091 15205 16091 15206 16092 15176 16092 15172 16092 15177 16093 15183 16093 15207 16093 15084 16094 15180 16094 15179 16094 15180 16095 15084 16095 15080 16095 15205 16096 15206 16096 15207 16096 15180 16097 15209 16097 15183 16097 15183 16098 15209 16098 15207 16098 15205 16099 15209 16099 15208 16099 15210 16100 15192 16100 15188 16100 15184 16101 15191 16101 15211 16101 15211 16102 15191 16102 15212 16102 15201 16103 15052 16103 15214 16103 15201 16104 15214 16104 15215 16104 15196 16105 15201 16105 15215 16105 15197 16106 15184 16106 15052 16106 15212 16107 15213 16107 15216 16107 15213 16108 15192 16108 15216 16108 15210 16109 15216 16109 15192 16109 15212 16110 15215 16110 15214 16110 15210 16111 15215 16111 15212 16111 15052 16112 15135 16112 15137 16112 15197 16113 15052 16113 15217 16113 15052 16114 15137 16114 15217 16114 15208 16115 15084 16115 15179 16115 15132 16116 15140 16116 15088 16116 15152 16117 15107 16117 15151 16117 15139 16118 15105 16118 15138 16118 15218 16119 15219 16119 15220 16119 15220 16120 15219 16120 15221 16120 15221 16121 15223 16121 15222 16121 15087 16122 15226 16122 15225 16122 15221 16123 15228 16123 15200 16123 15129 16124 15127 16124 15123 16124 15124 16125 15123 16125 15127 16125 2114 16126 15229 16126 15230 16126 15231 16127 15232 16127 15229 16127 15229 16128 15232 16128 15230 16128 15232 16129 15231 16129 15146 16129 3496 16130 15047 16130 15233 16130 15046 16131 15234 16131 15233 16131 15047 16132 15046 16132 15233 16132 15131 16133 15234 16133 15046 16133 15231 16134 15229 16134 15147 16134 15121 16135 15117 16135 15116 16135 15224 16136 15237 16136 15236 16136 15239 16137 15222 16137 15238 16137 15240 16138 15071 16138 15238 16138 15238 16139 15070 16139 15236 16139 15239 16140 15236 16140 15237 16140 15237 16141 15224 16141 15239 16141 15239 16142 15224 16142 15222 16142 15112 16143 15072 16143 15103 16143 15103 16144 15072 16144 15104 16144 15198 16145 15240 16145 15199 16145 15227 16146 15075 16146 15086 16146 15241 16147 15113 16147 15114 16147 15243 16148 15242 16148 15218 16148 15220 16149 15243 16149 15218 16149 15220 16150 15244 16150 15243 16150 15225 16151 15226 16151 15245 16151 15246 16152 15225 16152 15245 16152 15226 16153 15247 16153 15245 16153 15245 16154 15063 16154 15054 16154 15220 16155 15225 16155 15244 16155 15244 16156 15225 16156 15246 16156 15081 16157 15247 16157 15085 16157 15087 16158 15247 16158 15226 16158 15062 16159 15061 16159 15108 16159 15051 16160 15055 16160 15091 16160 15218 16161 15242 16161 15219 16161 15219 16162 15242 16162 15228 16162 15228 16163 15242 16163 15200 16163 15200 16164 15242 16164 15052 16164 15049 16165 15248 16165 15064 16165 15250 16166 15066 16166 15068 16166 15250 16167 15251 16167 15066 16167 15076 16168 15253 16168 15252 16168 15072 16169 15254 16169 15070 16169 15072 16170 15251 16170 15254 16170 15253 16171 15255 16171 15252 16171 15235 16172 15070 16172 15255 16172 15064 16173 15248 16173 15256 16173 15249 16174 15257 16174 15248 16174 15249 16175 15055 16175 15257 16175 15258 16176 15063 16176 15062 16176 15258 16177 15065 16177 15256 16177 15260 16178 15254 16178 15250 16178 15252 16179 15255 16179 15261 16179 15261 16180 15255 16180 15262 16180 15261 16181 15260 16181 15252 16181 15252 16182 15260 16182 15250 16182 15262 16183 15255 16183 15259 16183 15259 16184 15255 16184 15254 16184 15260 16185 15262 16185 15259 16185 15263 16186 15256 16186 15248 16186 15257 16187 15267 16187 15248 16187 15257 16188 15258 16188 15266 16188 15263 16189 15266 16189 15265 16189 15115 16190 15113 16190 15253 16190 15057 16191 15065 16191 15094 16191 15065 16192 15062 16192 15094 16192 15249 16193 15099 16193 15055 16193 15242 16194 15056 16194 15055 16194 15061 16195 15063 16195 15247 16195 15075 16196 15235 16196 15241 16196 15153 16197 15141 16197 15142 16197 15153 16198 15142 16198 15154 16198 15134 16199 15217 16199 15137 16199 15055 16200 15053 16200 15242 16200 15057 16201 15060 16201 15064 16201 15106 16202 15247 16202 15080 16202 15053 16203 15055 16203 15051 16203 2086 16204 15069 16204 15202 16204 15203 16205 15073 16205 15241 16205 15060 16206 15059 16206 15097 16206 2114 16207 15151 16207 15148 16207 15130 16208 15136 16208 15234 16208 15046 16209 3496 16209 15131 16209 15234 16210 3495 16210 15130 16210 15131 16211 3495 16211 15234 16211 15131 16212 15130 16212 3495 16212 2167 16213 15123 16213 2168 16213 15143 16214 15126 16214 15128 16214 15129 16215 2133 16215 15128 16215 2133 16216 15129 16216 15143 16216 15146 16217 2113 16217 15231 16217 15146 16218 15231 16218 15143 16218 15118 16219 15136 16219 3544 16219 3544 16220 15136 16220 15116 16220 15136 16221 15130 16221 15121 16221 15122 16222 15121 16222 3497 16222 15130 16223 3497 16223 15121 16223 15264 16224 15256 16224 15263 16224 15248 16225 15267 16225 15263 16225 15263 16226 15265 16226 15264 16226 15198 16227 15197 16227 15202 16227 15269 16228 15271 16228 15270 16228 15272 16229 15273 16229 15274 16229 15285 16230 4658 16230 15286 16230 4657 16231 15291 16231 15292 16231 15293 16232 15294 16232 15295 16232 15294 16233 15296 16233 15295 16233 15299 16234 15300 16234 15301 16234 15303 16235 15291 16235 15304 16235 15304 16236 15291 16236 15305 16236 15302 16237 15306 16237 15303 16237 15307 16238 15306 16238 15308 16238 15312 16239 15311 16239 4999 16239 15311 16240 15310 16240 15313 16240 15309 16241 15311 16241 15312 16241 4999 16242 15271 16242 15312 16242 4644 16243 15314 16243 15277 16243 4644 16244 15315 16244 15314 16244 15316 16245 15317 16245 15276 16245 15276 16246 15317 16246 15318 16246 15318 16247 15319 16247 15276 16247 15311 16248 15268 16248 15270 16248 15311 16249 15313 16249 15268 16249 15295 16250 15296 16250 15322 16250 15323 16251 15324 16251 15325 16251 15323 16252 15325 16252 15326 16252 15325 16253 15327 16253 15326 16253 15323 16254 15326 16254 15328 16254 15332 16255 15333 16255 15282 16255 15282 16256 15333 16256 15324 16256 15324 16257 15323 16257 15282 16257 15282 16258 15323 16258 15283 16258 15334 16259 15336 16259 15293 16259 15337 16260 15293 16260 15295 16260 15341 16261 15342 16261 15343 16261 15345 16262 15348 16262 15347 16262 15353 16263 15338 16263 15354 16263 15354 16264 15355 16264 15353 16264 15340 16265 15354 16265 15338 16265 15353 16266 15355 16266 15356 16266 15356 16267 15355 16267 15357 16267 15358 16268 15359 16268 15340 16268 15343 16269 15352 16269 15340 16269 15361 16270 15362 16270 15346 16270 15363 16271 15350 16271 15364 16271 15361 16272 15346 16272 15367 16272 15369 16273 15367 16273 15368 16273 15371 16274 15372 16274 15369 16274 15366 16275 15365 16275 15371 16275 15372 16276 15371 16276 15365 16276 15305 16277 15362 16277 15373 16277 15374 16278 15367 16278 15299 16278 15305 16279 15374 16279 15299 16279 15330 16280 15329 16280 15369 16280 15367 16281 15300 16281 15299 16281 15357 16282 15310 16282 15309 16282 15376 16283 15377 16283 15378 16283 15378 16284 15377 16284 15379 16284 15380 16285 15381 16285 15312 16285 15314 16286 15383 16286 15271 16286 15383 16287 15380 16287 15271 16287 15330 16288 15385 16288 15315 16288 15365 16289 15386 16289 15384 16289 15364 16290 15344 16290 15386 16290 15387 16291 15322 16291 15388 16291 15322 16292 15296 16292 15389 16292 15328 16293 15391 16293 15284 16293 15358 16294 15392 16294 15326 16294 15326 16295 15391 16295 15328 16295 15351 16296 15393 16296 15352 16296 15309 16297 15393 16297 15360 16297 15309 16298 15382 16298 15393 16298 15394 16299 15395 16299 15396 16299 15397 16300 15377 16300 15395 16300 15407 16301 15408 16301 15409 16301 15408 16302 15410 16302 15409 16302 15411 16303 15412 16303 15410 16303 15414 16304 15407 16304 15409 16304 15417 16305 15416 16305 15418 16305 15419 16306 15418 16306 15381 16306 15419 16307 15417 16307 15418 16307 15419 16308 15378 16308 15417 16308 15417 16309 15378 16309 15379 16309 15381 16310 15415 16310 15413 16310 15352 16311 15392 16311 15358 16311 15365 16312 15384 16312 15372 16312 15421 16313 15420 16313 15422 16313 15423 16314 15421 16314 15422 16314 15305 16315 15291 16315 15362 16315 15362 16316 15291 16316 15370 16316 15424 16317 15425 16317 15387 16317 15412 16318 15390 16318 15391 16318 15397 16319 15417 16319 15377 16319 15417 16320 15379 16320 15377 16320 15391 16321 15392 16321 15409 16321 15388 16322 15389 16322 15398 16322 15398 16323 15401 16323 15388 16323 15398 16324 15389 16324 15397 16324 15414 16325 15409 16325 15392 16325 15401 16326 15403 16326 15386 16326 15393 16327 15382 16327 15413 16327 15405 16328 15406 16328 15385 16328 15399 16329 15395 16329 15383 16329 15383 16330 15315 16330 15406 16330 15394 16331 15396 16331 15426 16331 15398 16332 15427 16332 15400 16332 15426 16333 15427 16333 15398 16333 15426 16334 15396 16334 15428 16334 15428 16335 15396 16335 15399 16335 15404 16336 15430 16336 15428 16336 15428 16337 15430 16337 15429 16337 15400 16338 15402 16338 15401 16338 15428 16339 15429 16339 15427 16339 15432 16340 15407 16340 15415 16340 15434 16341 15418 16341 15416 16341 15285 16342 15407 16342 15375 16342 15433 16343 15434 16343 15437 16343 15434 16344 15416 16344 15437 16344 15408 16345 15436 16345 15411 16345 15411 16346 15436 16346 15431 16346 15435 16347 15407 16347 15432 16347 15375 16348 15355 16348 15438 16348 15354 16349 15285 16349 15439 16349 15372 16350 15330 16350 15369 16350 15442 16351 15441 16351 15443 16351 15443 16352 15445 16352 15444 16352 15442 16353 15444 16353 15446 16353 15308 16354 15446 16354 15307 16354 15308 16355 15447 16355 15446 16355 15308 16356 15448 16356 15447 16356 15307 16357 15446 16357 15450 16357 15443 16358 15441 16358 15451 16358 15420 16359 15451 16359 15422 16359 15345 16360 15344 16360 15348 16360 15346 16361 15452 16361 15368 16361 15371 16362 15368 16362 15453 16362 15452 16363 15455 16363 15453 16363 15455 16364 15371 16364 15453 16364 15357 16365 15456 16365 15356 16365 15353 16366 15356 16366 15457 16366 15343 16367 15458 16367 15456 16367 15342 16368 15338 16368 15343 16368 15459 16369 15460 16369 15461 16369 15444 16370 15445 16370 15463 16370 15463 16371 15289 16371 15288 16371 15333 16372 15290 16372 15324 16372 15290 16373 15287 16373 15325 16373 15324 16374 15290 16374 15325 16374 15285 16375 15465 16375 15420 16375 15451 16376 15465 16376 15443 16376 15443 16377 15465 16377 15445 16377 15467 16378 15274 16378 15440 16378 15470 16379 15447 16379 15469 16379 15471 16380 15280 16380 15469 16380 15448 16381 15471 16381 15469 16381 15467 16382 15468 16382 15469 16382 15469 16383 15468 16383 15470 16383 15468 16384 15449 16384 15470 16384 15314 16385 15271 16385 15472 16385 15302 16386 15471 16386 15306 16386 15306 16387 15471 16387 15308 16387 15279 16388 15278 16388 15331 16388 15273 16389 15320 16389 15313 16389 15440 16390 15274 16390 15441 16390 15472 16391 15473 16391 15275 16391 15271 16392 15474 16392 15472 16392 15284 16393 15296 16393 15476 16393 15476 16394 15477 16394 15281 16394 15294 16395 15298 16395 15296 16395 15290 16396 15477 16396 15478 16396 15478 16397 15477 16397 15476 16397 15472 16398 15480 16398 15473 16398 15472 16399 15474 16399 15480 16399 15475 16400 15481 16400 15474 16400 15475 16401 15273 16401 15481 16401 15272 16402 15280 16402 15481 16402 15481 16403 15280 16403 15482 16403 15482 16404 15280 16404 15279 16404 15279 16405 15473 16405 15482 16405 15482 16406 15473 16406 15480 16406 15483 16407 15478 16407 15484 16407 15298 16408 15479 16408 15485 16408 15485 16409 15479 16409 15486 16409 15485 16410 15484 16410 15298 16410 15488 16411 15480 16411 15474 16411 15480 16412 15487 16412 15482 16412 15481 16413 15488 16413 15474 16413 15336 16414 15334 16414 15297 16414 15297 16415 15334 16415 15466 16415 15282 16416 15281 16416 15332 16416 15290 16417 15333 16417 15477 16417 15316 16418 15279 16418 15317 16418 15475 16419 15321 16419 15273 16419 15273 16420 15310 16420 15274 16420 15460 16421 15459 16421 15466 16421 15362 16422 15361 16422 15373 16422 15354 16423 15439 16423 15438 16423 15300 16424 15278 16424 15471 16424 15466 16425 15292 16425 15460 16425 15287 16426 15465 16426 15286 16426 15472 16427 15277 16427 15314 16427 15275 16428 15277 16428 15472 16428 15375 16429 15274 16429 15310 16429 15286 16430 15465 16430 15285 16430 15325 16431 15287 16431 15327 16431 15327 16432 15286 16432 4658 16432 15425 16433 15424 16433 15292 16433 15292 16434 15424 16434 4657 16434 4644 16435 15277 16435 15319 16435 15340 16436 15359 16436 15354 16436 15356 16437 15353 16437 5390 16437 15343 16438 15353 16438 15458 16438 15346 16439 15362 16439 15344 16439 15350 16440 15344 16440 3971 16440 3971 16441 15344 16441 15364 16441 15364 16442 15350 16442 3971 16442 15363 16443 3972 16443 3973 16443 5798 16444 15491 16444 15492 16444 15494 16445 15497 16445 15498 16445 6501 16446 15503 16446 15504 16446 15512 16447 15515 16447 15513 16447 15516 16448 15517 16448 6485 16448 15518 16449 15519 16449 6485 16449 15525 16450 15524 16450 15528 16450 15528 16451 15524 16451 15529 16451 15531 16452 15532 16452 6621 16452 15533 16453 6621 16453 15534 16453 6621 16454 15532 16454 15535 16454 6623 16455 15536 16455 15508 16455 15537 6 15538 6 15506 6 15506 16456 15538 16456 15539 16456 15541 16457 15493 16457 15535 16457 15534 16458 15493 16458 15495 16458 15534 16459 15535 16459 15493 16459 6519 16460 15547 16460 15548 16460 6519 16461 15548 16461 15549 16461 15503 16462 15550 16462 15551 16462 15553 16463 6485 16463 15543 16463 6623 16464 15539 16464 15552 16464 15554 16465 15555 16465 15510 16465 15510 16466 15555 16466 15556 16466 15510 16467 15546 16467 6431 16467 15553 16468 15516 16468 6485 16468 15546 16469 15556 16469 15547 16469 15560 16470 15561 16470 15562 16470 15562 16471 15561 16471 15563 16471 15568 16472 15571 16472 15569 16472 15574 16473 15576 16473 15566 16473 15577 16474 15578 16474 15560 16474 15577 16475 15579 16475 15578 16475 15560 16476 15578 16476 5798 16476 5798 16477 15578 16477 5800 16477 15563 16478 15580 16478 7298 16478 15580 16479 15563 16479 15581 16479 15491 16480 15582 16480 15575 16480 15583 16481 15567 16481 15570 16481 15586 16482 15587 16482 15585 16482 15585 16483 15587 16483 15588 16483 15585 16484 15589 16484 15570 16484 15570 16485 15589 16485 15584 16485 15573 16486 15567 16486 15586 16486 15583 16487 5859 16487 15567 16487 15590 16488 15567 16488 5859 16488 15592 16489 15588 16489 15587 16489 15527 16490 15583 16490 15593 16490 15594 16491 5850 16491 15522 16491 15593 16492 15594 16492 15522 16492 15591 16493 15503 16493 6501 16493 15591 16494 6501 16494 5850 16494 5800 16495 15532 16495 15531 16495 15508 16496 15536 16496 15600 16496 15602 16497 15603 16497 15550 16497 15550 16498 15603 16498 15536 16498 15586 16499 15604 16499 15587 16499 15605 16500 15604 16500 15586 16500 6518 16501 15544 16501 15606 16501 6518 16502 15606 16502 15605 16502 15544 16503 15519 16503 15607 16503 15607 16504 15519 16504 15511 16504 15608 16505 15607 16505 15511 16505 6519 16506 15609 16506 15545 16506 15545 16507 15609 16507 15608 16507 15549 16508 15609 16508 6519 16508 15575 16509 15611 16509 15576 16509 15531 16510 15533 16510 15611 16510 15612 16511 15606 16511 15615 16511 15614 16512 15618 16512 15619 16512 15623 16513 15624 16513 15621 16513 15628 16514 15627 16514 15626 16514 15630 16515 15632 16515 15625 16515 15631 16516 15625 16516 15627 16516 15629 16517 15633 16517 15634 16517 15634 16518 15633 16518 15635 16518 15636 16519 15635 16519 15630 16519 15636 16520 15634 16520 15635 16520 15636 16521 15598 16521 15634 16521 15634 16522 15598 16522 15599 16522 15639 16523 15638 16523 15640 16523 15595 16524 15640 16524 15641 16524 15548 16525 15637 16525 15577 16525 15577 16526 15580 16526 15548 16526 15590 16527 15643 16527 15605 16527 15583 16528 15643 16528 15590 16528 15543 16529 6518 16529 15605 16529 15543 16530 15643 16530 15558 16530 15629 16531 15608 16531 15628 16531 15629 16532 15634 16532 15608 16532 15607 16533 15608 16533 15634 16533 15634 16534 15599 16534 15597 16534 15631 16535 15627 16535 15610 16535 15617 16536 15621 16536 15604 16536 15602 16537 15604 16537 15621 16537 15624 16538 15618 16538 15603 16538 15613 16539 15598 16539 15636 16539 15601 16540 15613 16540 15636 16540 15601 16541 15600 16541 15613 16541 15618 16542 15536 16542 15603 16542 15618 16543 15613 16543 15600 16543 15600 16544 15536 16544 15618 16544 15612 16545 15614 16545 15644 16545 15644 16546 15614 16546 15645 16546 15648 16547 15619 16547 15623 16547 15526 16548 15527 16548 15649 16548 15523 16549 15650 16549 15648 16549 15523 16550 15648 16550 15522 16550 15522 16551 15622 16551 15527 16551 15646 16552 15644 16552 15647 16552 15648 16553 15650 16553 15647 16553 15649 16554 15622 16554 15620 16554 15647 16555 15650 16555 15646 16555 15646 16556 15649 16556 15620 16556 15629 16557 15651 16557 15652 16557 15652 16558 15633 16558 15629 16558 15654 16559 15635 16559 15655 16559 15655 16560 15635 16560 15633 16560 15595 16561 15625 16561 15656 16561 15595 16562 15656 16562 15640 16562 15639 16563 15626 16563 15637 16563 15626 16564 15625 16564 15637 16564 15654 16565 15655 16565 15658 16565 15655 16566 15633 16566 15658 16566 15652 16567 15651 16567 15657 16567 15595 16568 15578 16568 15579 16568 15577 16569 15637 16569 15659 16569 15595 16570 15579 16570 15659 16570 15582 16571 5800 16571 15531 16571 15543 16572 15558 16572 15553 16572 15666 16573 15667 16573 15668 16573 15529 16574 15666 16574 15530 16574 15529 16575 15667 16575 15666 16575 15530 16576 15666 16576 15670 16576 15661 16577 15671 16577 15663 16577 15672 16578 15671 16578 15641 16578 15568 16579 15567 16579 15571 16579 15675 16580 15676 16580 15673 16580 15676 16581 15675 16581 15588 16581 15675 16582 15585 16582 15588 16582 15588 16583 5849 16583 15676 16583 15566 16584 15563 16584 15565 16584 15560 16585 5798 16585 15677 16585 15574 16586 15679 16586 15491 16586 15492 16587 15491 16587 15678 16587 15569 16588 15572 16588 15570 16588 15675 16589 15589 16589 15585 16589 15564 16590 15561 16590 15560 16590 15560 16591 15679 16591 15574 16591 15680 16592 15681 16592 15682 16592 15666 16593 15682 16593 15670 16593 15685 16594 15664 16594 15684 16594 15684 16595 15514 16595 15513 16595 15683 16596 15666 16596 15685 16596 15685 16597 15666 16597 15664 16597 15555 16598 15515 16598 15556 16598 15556 16599 15515 16599 15547 16599 15515 16600 15512 16600 15687 16600 15547 16601 15515 16601 15687 16601 15638 16602 15686 16602 15672 16602 15663 16603 15686 16603 15665 16603 15670 16604 15681 16604 15530 16604 15525 16605 15681 16605 15527 16605 15693 16606 15667 16606 15692 16606 15499 16607 15501 16607 15690 16607 15692 16608 15499 16608 15690 16608 15692 16609 15691 16609 15693 16609 15662 16610 15668 16610 15691 16610 15691 16611 15668 16611 15693 16611 15508 16612 15496 16612 15696 16612 15538 16613 15697 16613 15539 16613 15552 16614 15697 16614 15551 16614 15660 16615 15689 16615 15661 16615 15671 16616 15689 16616 15641 16616 15696 16617 15698 16617 15505 16617 15511 16618 15519 16618 15699 16618 15515 16619 15701 16619 15513 16619 15515 16620 15700 16620 15701 16620 15520 16621 15688 16621 15702 16621 15680 16622 15702 16622 15688 16622 15680 16623 15513 16623 15702 16623 15702 16624 15513 16624 15701 16624 15696 16625 15498 16625 15703 16625 15499 16626 15704 16626 15500 16626 15704 16627 15695 16627 15705 16627 15705 16628 15695 16628 15697 16628 15697 16629 15698 16629 15705 16629 15706 16630 15701 16630 15707 16630 15521 16631 15702 16631 15708 16631 15521 16632 15707 16632 15699 16632 15710 16633 15703 16633 15711 16633 15711 16634 15703 16634 15498 16634 15703 16635 15710 16635 15705 16635 15705 16636 15710 16636 15712 16636 15713 16637 15711 16637 15704 16637 15704 16638 15711 16638 15498 16638 15713 16639 15705 16639 15712 16639 15711 16640 15713 16640 15710 16640 15516 16641 15559 16641 15517 16641 15517 16642 15559 16642 15520 16642 15509 16643 15700 16643 15554 16643 15515 16644 15555 16644 15700 16644 15698 16645 15697 16645 15537 16645 15537 16646 15697 16646 15538 16646 15493 16647 15542 16647 15494 16647 15494 16648 15542 16648 15497 16648 15497 16649 15542 16649 15500 16649 15518 16650 15517 16650 15520 16650 15689 16651 15501 16651 15502 16651 15681 16652 15680 16652 15688 16652 15593 16653 15583 16653 15584 16653 15577 16654 15659 16654 15579 16654 15505 16655 15508 16655 15696 16655 15551 16656 15697 16656 15503 16656 15697 16657 15504 16657 15503 16657 6848 16658 15502 16658 15532 16658 15548 16659 15686 16659 15637 16659 15527 16660 15681 16660 15643 16660 15681 16661 15688 16661 15643 16661 6519 16662 15545 16662 15546 16662 15693 16663 15668 16663 15667 16663 15545 16664 6431 16664 15546 16664 15590 16665 5859 16665 15583 16665 15580 16666 15577 16666 7298 16666 15491 16667 7254 16667 15574 16667 15572 16668 15585 16668 15570 16668 15572 16669 15573 16669 15585 16669 5849 16670 5858 16670 15589 16670 15560 16671 15574 16671 15564 16671 15641 16672 15642 16672 15595 16672 15626 16673 15651 16673 15629 16673 10711 16674 15720 16674 10721 16674 10711 16675 15722 16675 10712 16675 10740 16676 15719 16676 15723 16676 10687 16677 15724 16677 15721 16677 15722 16678 15724 16678 15727 16678 15723 16679 10713 16679 15725 16679 10725 16680 15731 16680 10726 16680 10726 16681 15731 16681 15733 16681 10715 16682 15734 16682 15735 16682 10726 16683 15736 16683 10727 16683 10716 16684 15737 16684 10719 16684 15734 16685 15739 16685 15735 16685 15735 16686 15739 16686 15737 16686 10727 16687 15741 16687 10728 16687 15739 16688 10685 16688 15737 16688 10728 16689 15720 16689 10742 16689 15740 16690 10685 16690 15714 16690 10742 16691 15720 16691 15717 16691 15740 16692 10719 16692 15737 16692 10719 16693 15733 16693 10716 16693 15736 16694 10719 16694 10722 16694 10722 16695 15714 16695 15715 16695 15741 16696 10722 16696 10721 16696 10711 16697 10721 16697 15716 16697 15718 16698 10711 16698 10712 16698 10713 16699 10712 16699 15728 16699 15725 16700 10713 16700 10715 16700 10716 16701 10715 16701 15735 16701 15730 16702 10715 16702 10716 16702 15726 16703 15725 16703 15730 16703 10726 16704 10727 16704 10728 16704 10726 16705 10742 16705 10725 16705 15726 16706 10741 16706 10740 16706 10685 16707 15727 16707 10684 16707 10684 16708 15727 16708 15724 16708 10687 16709 10684 16709 15724 16709 15747 6 15750 6 15751 6 15753 6 15752 6 15754 6 15755 16710 15743 16710 15745 16710 15760 16711 15761 16711 15758 16711 15762 16712 15758 16712 15761 16712 15764 16713 15763 16713 15765 16713 15766 16714 15765 16714 15744 16714 15766 6 15744 6 15767 6 15768 16715 15767 16715 15769 16715 15757 16716 15770 16716 15769 16716 15757 16717 15756 16717 15770 16717 15771 6 15765 6 15766 6 15767 16718 15744 16718 15743 16718 15755 6 15753 6 15754 6 15766 16719 15767 16719 15772 16719 15762 16720 15774 16720 15773 16720 15774 16721 15762 16721 15761 16721 15749 16722 15773 16722 15774 16722 15770 16723 15775 16723 15768 16723 15771 16724 15778 16724 15779 16724 15764 16725 15779 16725 15780 16725 15774 16726 15782 16726 15783 16726 15749 16727 15784 16727 15785 16727 15752 16728 15785 16728 15786 16728 15756 16729 15787 16729 15775 16729 15770 16730 15756 16730 15775 16730 15772 16731 15777 16731 15766 16731 15766 16732 15778 16732 15771 16732 15760 16733 15781 16733 15761 16733 15761 16734 15782 16734 15774 16734 15774 16735 15783 16735 15749 16735 15749 16736 15785 16736 15750 16736 15750 16737 15785 16737 15752 16737 15752 16738 15786 16738 15754 16738 15779 53 15791 53 15792 53 15780 53 15792 53 15793 53 15781 53 15794 53 15782 53 15776 53 15790 53 15777 53 15778 16739 15791 16739 15779 16739 15779 53 15792 53 15780 53 15780 53 15793 53 15781 53 15783 16740 15795 16740 15796 16740 15784 16741 15796 16741 15797 16741 15785 53 15797 53 15798 53 15787 53 15800 53 15788 53 15775 53 15787 53 15788 53 15784 53 15797 53 15785 53 15785 53 15798 53 15786 53 15786 53 15799 53 15787 53 15790 16742 15803 16742 15804 16742 15793 16743 15806 16743 15807 16743 15795 16744 15808 16744 15809 16744 15796 16745 15809 16745 15810 16745 15797 16746 15810 16746 15811 16746 15790 16747 15804 16747 15791 16747 15791 16748 15805 16748 15792 16748 15792 16749 15806 16749 15793 16749 15793 16750 15807 16750 15794 16750 15795 16751 15809 16751 15796 16751 15797 16752 15811 16752 15798 16752 15814 16753 15815 16753 15816 16753 15818 16754 15815 16754 15819 16754 15817 16755 15815 16755 15818 16755 15818 16756 15819 16756 15820 16756 15814 16757 15819 16757 15815 16757 15824 16758 15825 16758 15826 16758 15827 16759 15825 16759 15828 16759 15829 16760 15830 16760 15831 16760 15832 16761 15831 16761 15833 16761 15840 16762 15839 16762 15841 16762 15842 16763 15841 16763 15843 16763 15844 16764 15845 16764 15846 16764 15844 16765 15846 16765 15847 16765 15850 16766 15849 16766 15851 16766 15824 16767 15852 16767 15854 16767 15826 16768 15825 16768 15827 16768 15827 16769 15828 16769 15830 16769 15829 16770 15831 16770 15832 16770 15832 16771 15833 16771 15834 16771 15834 16772 15835 16772 15836 16772 15836 16773 15837 16773 15838 16773 15840 16774 15841 16774 15842 16774 15844 16775 15847 16775 15848 16775 15855 16776 15824 16776 15856 16776 15828 16777 15857 16777 15858 16777 15830 16778 15858 16778 15859 16778 15831 16779 15859 16779 15860 16779 15831 16780 15860 16780 15861 16780 15825 16781 15857 16781 15828 16781 15828 16782 15858 16782 15830 16782 15862 16783 15863 16783 15835 16783 15837 16784 15864 16784 15865 16784 15839 16785 15866 16785 15867 16785 15843 16786 15869 16786 15845 16786 15835 16787 15863 16787 15837 16787 15869 16788 15870 16788 15845 16788 15845 16789 15870 16789 15846 16789 15846 16790 15870 16790 15871 16790 15847 16791 15871 16791 15872 16791 15851 16792 15873 16792 4940 16792 15863 16793 15874 16793 15875 16793 15863 16794 15862 16794 15874 16794 15817 16795 15877 16795 15876 16795 15865 53 15878 53 15818 53 15865 53 15864 53 15878 53 15878 53 15864 53 15875 53 15875 16796 15864 16796 15863 16796 15822 16797 4993 16797 15855 16797 4993 16798 15816 16798 4929 16798 15859 16799 15817 16799 15860 16799 15859 16800 15883 16800 15817 16800 15859 16801 15858 16801 15883 16801 15883 16802 15858 16802 15884 16802 15884 16803 15858 16803 4930 16803 15872 16804 15880 16804 15873 16804 15823 53 15871 53 15870 53 15886 53 15823 53 15870 53 15886 53 15887 53 15820 53 4983 16805 15867 16805 15866 16805 4902 16806 15888 16806 15868 16806 15869 16807 15888 16807 15886 16807 15855 16808 4993 16808 15857 16808 4930 16809 15857 16809 4993 16809 15853 16810 15813 16810 15850 16810 15850 6 15813 6 15812 6 15844 6 15812 6 15811 6 15840 6 15809 6 15808 6 15838 16811 15808 16811 15836 16811 15826 16812 15801 16812 15824 16812 15803 6 15826 6 15827 6 15804 16813 15827 16813 15830 16813 15805 6 15829 6 15832 6 15807 6 15834 6 15836 6 15808 16814 15807 16814 15836 16814 15805 6 15832 6 15806 6 15840 6 15842 6 15809 6 15842 16815 15845 16815 15810 16815 15845 16816 15844 16816 15811 16816 15746 16817 15758 16817 15887 16817 15887 16818 15758 16818 4983 16818 4983 16819 15758 16819 15762 16819 15886 16820 15773 16820 15748 16820 4983 16821 15762 16821 4902 16821 4930 16822 15769 16822 15884 16822 4993 16823 15743 16823 15757 16823 15884 16824 15767 16824 15883 16824 4993 16825 15769 16825 4930 16825 15755 16826 15881 16826 15753 16826 15755 16827 15882 16827 15881 16827 15879 16828 15745 16828 15747 16828 15881 16829 15751 16829 15753 16829 15880 16830 15751 16830 15881 16830 15744 16831 15874 16831 15876 16831 15875 16832 15765 16832 15763 16832 15876 16833 15742 16833 15744 16833 15874 16834 15765 16834 15875 16834 15878 16835 15742 16835 15877 16835 15877 16836 15742 16836 15876 16836 15889 6 15890 6 15891 6 15889 16837 15892 16837 15890 16837 15896 6 15894 6 15895 6 15894 6 15896 6 15898 6 15898 6 15896 6 15899 6 15901 16838 15900 16838 15902 16838 15903 6 15901 6 15902 6 15903 16839 15890 16839 15901 16839 15901 6 15890 6 15892 6 15893 16840 15889 16840 15904 16840 15906 16841 15904 16841 15905 16841 15907 6 15908 6 15909 6 15911 6 15910 6 15912 6 15913 16842 15912 16842 15891 16842 15916 16843 15917 16843 15918 16843 15903 16844 15902 16844 15919 16844 15906 6 15910 6 15920 6 15920 16845 15910 16845 15911 16845 15911 16846 15912 16846 15913 16846 15921 16847 15898 16847 15900 16847 15913 16848 15914 16848 15915 16848 15897 6 15895 6 15909 6 15919 16849 15924 16849 15918 16849 15913 16850 15925 16850 15926 16850 15911 16851 15926 16851 15927 16851 15920 16852 15927 16852 15928 16852 15906 16853 15928 16853 15929 16853 15906 16854 15929 16854 15930 16854 15922 16855 15930 16855 15931 16855 15897 16856 15931 16856 15932 16856 15900 16857 15933 16857 15934 16857 15902 16858 15934 16858 15923 16858 15919 16859 15902 16859 15923 16859 15918 16860 15924 16860 15915 16860 15915 16861 15925 16861 15913 16861 15913 16862 15926 16862 15911 16862 15911 16863 15927 16863 15920 16863 15908 16864 15930 16864 15922 16864 15922 16865 15931 16865 15897 16865 15897 16866 15932 16866 15896 16866 15899 16867 15933 16867 15900 16867 15927 53 15938 53 15939 53 15924 16868 15937 16868 15925 16868 15927 53 15939 53 15928 53 15928 16869 15940 16869 15929 16869 15933 53 15945 53 15946 53 15934 53 15946 53 15936 53 15923 16870 15934 16870 15936 16870 15930 53 15942 53 15931 53 15933 16871 15946 16871 15934 16871 15947 16872 15948 16872 15935 16872 15937 16873 15949 16873 15950 16873 15940 16874 15952 16874 15953 16874 15942 16875 15954 16875 15955 16875 15944 16876 15955 16876 15956 16876 15944 16877 15956 16877 15957 16877 15945 16878 15957 16878 15958 16878 15936 16879 15959 16879 15947 16879 15935 16880 15936 16880 15947 16880 15935 16881 15948 16881 15937 16881 15937 16882 15950 16882 15938 16882 15939 16883 15952 16883 15940 16883 15942 16884 15955 16884 15943 16884 15945 16885 15958 16885 15946 16885 15946 16886 15959 16886 15936 16886 15962 16887 15961 16887 15963 16887 15964 16888 15961 16888 15965 16888 15966 16889 15965 16889 15967 16889 15968 16890 15967 16890 15960 16890 15962 16891 15968 16891 15960 16891 15963 16892 15961 16892 15964 16892 15969 16893 15967 16893 15968 16893 15979 16894 15978 16894 15980 16894 15983 16895 15982 16895 15984 16895 15998 16896 15997 16896 15999 16896 16000 16897 16001 16897 15972 16897 15971 16898 16000 16898 15972 16898 15977 16899 15978 16899 15979 16899 15985 16900 15987 16900 15988 16900 15988 16901 15989 16901 15991 16901 15993 16902 15995 16902 15996 16902 15996 16903 15997 16903 15998 16903 15998 16904 15999 16904 16001 16904 16002 16905 15970 16905 16003 16905 16002 16906 16004 16906 15970 16906 15973 16907 16004 16907 16005 16907 15976 16908 16006 16908 16007 16908 15975 16909 16006 16909 15976 16909 15976 16910 16007 16910 15978 16910 15978 16911 16009 16911 15980 16911 16010 16912 16011 16912 15982 16912 15982 16913 16011 16913 15984 16913 15984 16914 16011 16914 16012 16914 15987 16915 16013 16915 16014 16915 15992 16916 15991 16916 16017 16916 15984 16917 16012 16917 15986 16917 15987 16918 16014 16918 15989 16918 15989 16919 16016 16919 15991 16919 15995 16920 1198 16920 16019 16920 15972 16921 16021 16921 16003 16921 15994 16922 1198 16922 15995 16922 16001 16923 16021 16923 15972 16923 16011 16924 16022 16924 16023 16924 16022 53 16010 53 16024 53 16024 53 16010 53 16009 53 16024 53 16009 53 16008 53 15963 16925 16025 16925 16024 16925 16025 16926 15964 16926 16026 16926 16023 16927 16012 16927 16011 16927 16027 16928 16019 16928 1198 16928 16020 16929 16028 16929 16029 16929 16029 16930 16021 16930 16020 16930 15968 53 16003 53 16030 53 15968 16931 16002 16931 16003 16931 15968 16932 16031 16932 16002 16932 15968 53 15962 53 16031 53 16032 16933 15962 16933 15963 16933 16007 16934 16032 16934 15963 16934 16007 16935 16006 16935 16032 16935 16032 16936 16006 16936 16033 16936 15968 53 16034 53 15969 53 16035 16937 15969 16937 16018 16937 16035 16938 15966 16938 15969 16938 16037 16939 15964 16939 15966 16939 16037 16940 16014 16940 15964 16940 16015 16941 16037 16941 16038 16941 16038 16942 16016 16942 16015 16942 16038 53 16039 53 16016 53 16036 53 16018 53 16017 53 16041 16943 16004 16943 16040 16943 16016 53 16039 53 16017 53 15959 6 16000 6 15947 6 15959 16944 16001 16944 16000 16944 16001 16945 15959 16945 15998 16945 15996 6 15958 6 15957 6 15990 6 15956 6 15955 6 15971 6 15948 6 15947 6 15971 16946 15973 16946 15948 16946 15950 6 15977 6 15979 6 15951 6 15979 6 15981 6 15952 6 15981 6 15983 6 15953 16947 15983 16947 15986 16947 15954 16948 15953 16948 15986 16948 15949 16949 15977 16949 15950 16949 15950 16950 15979 16950 15951 16950 15951 6 15981 6 15952 6 15985 16951 15988 16951 15954 16951 15988 16952 15991 16952 15955 16952 15991 16953 15990 16953 15955 16953 15993 16954 15996 16954 15957 16954 15996 6 15998 6 15958 6 16038 16955 15907 16955 15909 16955 16036 16956 15909 16956 15895 16956 16035 16957 15895 16957 15893 16957 16037 16958 15907 16958 16038 16958 16038 16959 15909 16959 16039 16959 15916 16960 16041 16960 15917 16960 15916 16961 16033 16961 16041 16961 16032 16962 15916 16962 15914 16962 16031 16963 15890 16963 15903 16963 16033 16964 15916 16964 16032 16964 16040 16965 15917 16965 16041 16965 15901 16966 16030 16966 15921 16966 16034 16967 15901 16967 15892 16967 16027 16968 15892 16968 15894 16968 16028 16969 15894 16969 15898 16969 16030 16970 16029 16970 15921 16970 16034 16971 15892 16971 16027 16971 16027 16972 15894 16972 16028 16972 15891 16973 15912 16973 16024 16973 16026 16974 15910 16974 15905 16974 16022 16975 15910 16975 16023 16975 16023 16976 15910 16976 16026 16976 16042 6 16043 6 16044 6 16042 16977 16045 16977 16043 16977 16045 16978 16042 16978 16046 16978 16047 16979 16046 16979 16048 16979 16047 6 16049 6 16051 6 16051 16980 16049 16980 16052 16980 16056 16981 16055 16981 16057 16981 16058 16982 16056 16982 16045 16982 16046 16983 16042 16983 16059 16983 16060 16984 16061 16984 16046 16984 16060 16985 16062 16985 16061 16985 16065 16986 16064 16986 16066 16986 16067 16987 16044 16987 16068 16987 16070 16988 16057 16988 16071 16988 16071 16989 16057 16989 16072 16989 16065 16990 16066 16990 16067 16990 16068 6 16044 6 16043 6 16054 6 16051 6 16053 6 16067 16991 16068 16991 16069 16991 16069 6 16070 6 16071 6 16048 16992 16073 16992 16050 16992 16074 16993 16061 16993 16062 16993 16050 6 16073 6 16074 6 16071 16994 16075 16994 16076 16994 16067 16995 16076 16995 16077 16995 16063 16996 16078 16996 16079 16996 16052 16997 16083 16997 16084 16997 16053 16998 16084 16998 16085 16998 16072 16999 16055 16999 16075 16999 16071 17000 16076 17000 16069 17000 16069 17001 16076 17001 16067 17001 16063 17002 16079 17002 16060 17002 16060 17003 16080 17003 16062 17003 16062 17004 16081 17004 16074 17004 16074 17005 16082 17005 16050 17005 16050 17006 16083 17006 16049 17006 16052 17007 16084 17007 16053 17007 16087 53 16088 53 16075 53 16077 17008 16089 17008 16090 17008 16078 53 16090 53 16091 53 16079 53 16091 53 16092 53 16075 17009 16088 17009 16076 17009 16078 17010 16091 17010 16079 17010 16079 53 16092 53 16080 53 16082 53 16093 53 16094 53 16083 53 16095 53 16096 53 16081 53 16093 53 16082 53 16099 17011 16087 17011 16100 17011 16099 17012 16088 17012 16087 17012 16088 17013 16099 17013 16101 17013 16089 17014 16102 17014 16103 17014 16095 17015 16107 17015 16108 17015 16096 17016 16108 17016 16109 17016 16097 17017 16109 17017 16110 17017 16098 17018 16110 17018 16100 17018 16088 17019 16101 17019 16089 17019 16091 17020 16104 17020 16092 17020 16093 17021 16106 17021 16094 17021 16095 17022 16108 17022 16096 17022 16096 17023 16109 17023 16097 17023 16097 17024 16110 17024 16098 17024 16115 17025 16112 17025 16116 17025 16119 17026 16118 17026 16111 17026 16115 17027 16116 17027 16117 17027 16117 17028 16118 17028 16120 17028 16120 17029 16118 17029 16119 17029 16111 53 16118 53 16116 53 16111 53 16116 53 16112 53 16121 17030 16124 17030 16122 17030 16122 17031 16124 17031 16125 17031 16126 17032 16125 17032 16127 17032 16131 17033 16130 17033 16132 17033 16135 17034 16134 17034 16136 17034 16139 17035 16138 17035 16140 17035 16141 17036 16142 17036 16143 17036 16147 17037 16146 17037 16148 17037 16122 17038 16151 17038 16123 17038 16126 17039 16127 17039 16129 17039 16128 17040 16130 17040 16131 17040 16133 17041 16134 17041 16135 17041 16139 17042 16140 17042 16142 17042 16152 17043 3039 17043 16124 17043 16124 17044 3039 17044 16125 17044 16127 17045 16154 17045 16155 17045 16130 17046 16157 17046 16158 17046 16125 17047 16154 17047 16127 17047 16127 17048 16155 17048 16129 17048 16130 17049 16158 17049 16132 17049 16159 17050 16160 17050 16134 17050 16136 17051 16161 17051 16162 17051 16138 17052 16163 17052 16164 17052 16140 17053 16164 17053 16165 17053 16142 17054 16166 17054 16167 17054 16143 17055 16142 17055 16167 17055 16136 17056 16162 17056 16138 17056 16167 17057 16168 17057 16143 17057 16143 17058 16168 17058 16145 17058 16148 17059 16170 17059 16171 17059 16150 17060 16171 17060 16172 17060 16123 17061 16153 17061 16121 17061 16145 17062 16169 17062 16146 17062 16146 17063 16170 17063 16148 17063 16148 17064 16171 17064 16150 17064 16150 17065 16172 17065 16123 17065 16160 17066 16173 17066 16174 17066 16162 17067 16115 17067 16163 17067 16162 17068 16177 17068 16115 17068 16178 17069 16179 17069 16170 17069 16171 17070 16179 17070 16180 17070 16180 17071 16172 17071 16171 17071 16119 17072 16153 17072 16181 17072 16119 17073 3048 17073 16152 17073 16182 17074 16113 17074 16114 17074 16156 17075 16114 17075 16157 17075 16156 17076 16183 17076 16182 17076 16184 17077 16183 17077 16155 17077 16170 17078 16179 17078 16171 17078 16181 17079 16185 17079 16119 17079 16178 17080 16169 17080 16120 17080 16120 53 16169 53 16168 53 16186 17081 16168 17081 16187 17081 16186 17082 16120 17082 16168 17082 3073 17083 16166 17083 16165 17083 3073 17084 16188 17084 16166 17084 16167 17085 16188 17085 16187 17085 16187 53 16168 53 16167 53 3048 17086 3047 17086 16152 17086 16166 17087 16188 17087 16167 17087 16164 17088 3073 17088 16165 17088 16100 6 16149 6 16151 6 16149 6 16100 6 16110 6 16141 6 16108 6 16107 6 16139 17089 16106 17089 16105 17089 16137 6 16105 6 16135 6 16122 17090 16125 17090 16099 17090 16101 17091 16125 17091 16126 17091 16104 17092 16133 17092 16135 17092 16101 6 16126 6 16102 6 16102 17093 16128 17093 16103 17093 16103 17094 16131 17094 16104 17094 16104 6 16135 6 16105 6 16139 17095 16142 17095 16106 17095 16144 17096 16147 17096 16109 17096 3071 17097 16046 17097 16061 17097 16187 17098 16073 17098 16048 17098 16188 17099 16073 17099 16187 17099 16187 17100 16048 17100 16186 17100 16070 17101 3046 17101 16057 17101 16070 17102 16184 17102 3046 17102 16183 17103 16070 17103 16068 17103 16182 17104 16043 17104 3048 17104 3048 17105 16056 17105 3047 17105 16058 17106 16181 17106 16054 17106 16185 17107 16058 17107 16045 17107 16178 17108 16045 17108 16047 17108 16180 17109 16051 17109 16054 17109 16181 17110 16058 17110 16185 17110 16178 17111 16047 17111 16179 17111 16044 17112 16173 17112 16175 17112 16174 17113 16066 17113 16064 17113 16174 17114 16064 17114 16059 17114 16175 17115 16042 17115 16044 17115 16174 17116 16059 17116 16177 17116 16177 17117 16042 17117 16176 17117 16176 17118 16042 17118 16175 17118 16190 17119 16189 17119 16191 17119 16189 17120 16192 17120 16191 17120 16196 17121 12833 17121 16197 17121 16198 17122 16197 17122 12834 17122 16198 17123 12834 17123 12832 17123 16203 17124 16204 17124 16205 17124 16205 17125 16204 17125 16206 17125 16209 17126 16203 17126 16210 17126 16210 17127 16203 17127 16205 17127 16206 17128 16218 17128 16205 17128 16214 17129 16208 17129 16210 17129 16216 17130 16213 17130 16205 17130 16214 17131 16210 17131 16213 17131 16214 17132 16193 17132 16219 17132 16218 17133 16219 17133 16220 17133 16201 17134 16218 17134 16220 17134 16217 17135 16201 17135 16221 17135 16221 17136 16202 17136 16201 17136 16222 17137 16193 17137 16212 17137 16212 17138 16193 17138 16214 17138 12832 17139 16224 17139 16223 17139 12832 17140 16196 17140 16224 17140 16225 17141 16199 17141 16226 17141 16226 17142 16228 17142 16220 17142 16220 17143 16228 17143 16221 17143 16201 17144 16220 17144 16221 17144 16219 17145 16224 17145 16225 17145 16218 17146 16214 17146 16219 17146 16229 17147 16230 17147 16231 17147 16234 17148 16229 17148 16231 17148 13091 17149 16235 17149 13090 17149 13091 17150 16236 17150 16235 17150 13091 17151 13097 17151 16236 17151 16237 17152 13097 17152 13096 17152 16241 17153 13093 17153 13056 17153 16248 17154 16247 17154 16249 17154 16250 17155 16249 17155 16251 17155 16237 17156 13096 17156 16238 17156 16239 17157 13099 17157 16240 17157 16240 17158 13093 17158 16241 17158 16244 17159 16245 17159 16246 17159 13062 17160 16250 17160 13090 17160 13062 17161 16253 17161 16250 17161 16255 17162 13064 17162 13089 17162 16259 17163 13058 17163 13060 17163 16254 17164 13064 17164 16255 17164 16258 17165 13058 17165 16259 17165 16260 17166 13059 17166 16261 17166 16261 17167 13061 17167 16262 17167 16263 17168 13082 17168 16235 17168 16235 17169 13091 17169 16252 17169 13063 17170 16249 17170 13064 17170 13065 17171 16245 17171 16243 17171 13057 17172 16243 17172 13056 17172 13058 17173 13056 17173 13093 17173 13081 17174 13096 17174 13097 17174 13064 17175 16247 17175 13089 17175 13089 17176 16245 17176 13065 17176 16265 17177 16254 17177 16255 17177 16266 17178 16256 17178 16257 17178 16263 17179 16269 17179 16262 17179 16261 17180 16269 17180 16270 17180 16259 17181 16270 17181 16267 17181 16262 17182 16269 17182 16261 17182 16267 17183 16266 17183 16257 17183 16235 17184 16252 17184 16268 17184 16268 17185 16252 17185 16264 17185 16227 17186 16271 17186 16269 17186 16272 17187 16273 17187 16274 17187 16264 17188 16273 17188 16227 17188 16274 17189 16264 17189 16265 17189 16265 17190 16266 17190 16274 17190 16272 17191 16266 17191 16267 17191 16274 17192 16266 17192 16272 17192 16271 17193 16267 17193 16270 17193 16227 17194 16268 17194 16264 17194 16235 17195 16240 17195 16252 17195 16235 17196 16239 17196 16240 17196 16239 17197 16236 17197 16238 17197 16240 17198 16241 17198 16252 17198 16250 17199 16241 17199 16242 17199 16246 17200 16248 17200 16244 17200 16250 17201 16242 17201 16248 17201 16228 17202 16227 17202 16275 17202 16224 17203 16276 17203 16223 17203 16219 17204 16225 17204 16277 17204 16191 17205 16220 17205 16189 17205 16278 17206 16226 17206 16191 17206 16191 17207 16189 17207 16278 17207 16278 17208 16189 17208 16277 17208 16279 17209 16276 17209 16222 17209 16203 17210 16217 17210 16204 17210 16203 17211 16209 17211 16215 17211 16204 17212 16217 17212 16212 17212 16233 17213 16222 17213 16212 17213 16229 17214 16233 17214 16217 17214 16217 17215 16221 17215 16229 17215 16229 17216 16221 17216 16280 17216 16279 17217 16194 17217 16195 17217 16194 17218 16233 17218 16234 17218 16233 17219 16194 17219 16279 17219 16279 17220 16195 17220 16276 17220 16197 17221 16276 17221 16234 17221 16197 17222 12833 17222 16276 17222 12834 17223 16276 17223 12833 17223 12834 17224 16272 17224 16276 17224 16275 17225 16273 17225 16200 17225 16200 17226 16273 17226 16231 17226 16202 17227 16229 17227 16280 17227 16231 17228 16273 17228 16197 17228 223 17229 222 17229 224 17229 225 17230 226 17230 227 17230 227 17231 226 17231 228 17231 227 17232 229 17232 230 17232 228 17233 226 17233 229 17233 221 17234 223 17234 232 17234 237 17235 223 17235 238 17235 237 17236 233 17236 223 17236 239 17237 240 17237 241 17237 240 17238 245 17238 242 17238 242 17239 245 17239 246 17239 240 17240 239 17240 245 17240 240 17241 242 17241 241 17241 249 17242 252 17242 253 17242 254 17243 252 17243 255 17243 256 17244 255 17244 251 17244 248 17245 257 17245 251 17245 261 17246 253 17246 254 17246 250 17247 249 17247 262 17247 271 17248 270 17248 272 17248 272 17249 274 17249 273 17249 263 17250 265 17250 275 17250 276 17251 275 17251 277 17251 276 17252 263 17252 275 17252 279 17253 278 17253 276 17253 291 17254 266 17254 292 17254 291 17255 267 17255 266 17255 291 17256 293 17256 267 17256 294 17257 269 17257 295 17257 294 17258 296 17258 266 17258 269 17259 270 17259 271 17259 298 17260 271 17260 299 17260 295 17261 269 17261 297 17261 300 17262 301 17262 292 17262 293 17263 289 17263 267 17263 286 17264 288 17264 302 17264 287 17265 286 17265 303 17265 281 17266 285 17266 304 17266 281 17267 304 17267 282 17267 283 17268 305 17268 275 17268 275 17269 305 17269 277 17269 263 17270 260 17270 259 17270 258 17271 309 17271 307 17271 307 17272 309 17272 310 17272 311 17273 312 17273 307 17273 312 17274 311 17274 313 17274 309 17275 279 17275 315 17275 312 17276 316 17276 307 17276 324 17277 323 17277 284 17277 324 17278 284 17278 280 17278 319 17279 325 17279 307 17279 328 53 327 53 329 53 329 17280 327 17280 330 17280 331 17281 330 17281 303 17281 326 17282 325 17282 332 17282 285 17283 287 17283 333 17283 326 17284 332 17284 333 17284 334 17285 328 17285 335 17285 336 17286 335 17286 337 17286 338 17287 337 17287 290 17287 339 53 340 53 334 53 343 17288 342 17288 293 17288 336 17289 337 17289 338 17289 338 17290 290 17290 289 17290 350 17291 301 17291 351 17291 351 17292 301 17292 300 17292 349 17293 296 17293 294 17293 334 17294 352 17294 353 17294 353 17295 352 17295 357 17295 358 17296 357 17296 359 17296 359 17297 357 17297 360 17297 355 17298 298 17298 299 17298 361 17299 364 17299 362 17299 365 17300 367 17300 366 17300 367 17301 365 17301 368 17301 366 17302 367 17302 369 17302 370 17303 372 17303 376 17303 376 17304 372 17304 373 17304 372 17305 371 17305 377 17305 377 17306 373 17306 372 17306 381 17307 382 17307 383 17307 383 17308 382 17308 384 17308 385 17309 387 17309 388 17309 385 17310 388 17310 386 17310 389 17311 391 17311 390 17311 392 17312 394 17312 395 17312 392 17313 395 17313 393 17313 394 17314 384 17314 395 17314 393 17315 396 17315 391 17315 391 17316 396 17316 397 17316 393 17317 395 17317 396 17317 396 17318 395 17318 398 17318 395 17319 382 17319 398 17319 384 17320 392 17320 391 17320 391 17321 389 17321 383 17321 383 17322 389 17322 385 17322 401 17323 402 17323 403 17323 402 17324 401 17324 404 17324 405 17325 406 17325 401 17325 401 17326 406 17326 404 17326 405 17327 408 17327 406 17327 407 17328 409 17328 410 17328 402 17329 406 17329 408 17329 415 17330 416 17330 417 17330 415 17331 412 17331 414 17331 417 17332 412 17332 415 17332 419 17333 413 17333 420 17333 412 17334 420 17334 413 17334 420 17335 418 17335 416 17335 423 17336 422 17336 416 17336 424 17337 416 17337 415 17337 417 17338 420 17338 412 17338 430 17339 429 17339 427 17339 430 17340 427 17340 434 17340 435 17341 434 17341 436 17341 438 17342 427 17342 426 17342 439 17343 438 17343 426 17343 439 17344 426 17344 428 17344 428 17345 429 17345 433 17345 440 17346 441 17346 442 17346 443 17347 445 17347 442 17347 442 17348 445 17348 440 17348 446 17349 413 17349 447 17349 448 17350 447 17350 419 17350 422 17351 448 17351 420 17351 419 17352 420 17352 448 17352 369 17353 367 17353 449 17353 450 17354 451 17354 449 17354 454 17355 432 17355 431 17355 430 17356 455 17356 431 17356 455 17357 430 17357 434 17357 453 17358 433 17358 432 17358 453 17359 456 17359 433 17359 457 17360 449 17360 451 17360 452 17361 450 17361 459 17361 462 17362 461 17362 259 17362 259 17363 461 17363 441 17363 463 17364 464 17364 465 17364 466 17365 464 17365 463 17365 467 17366 464 17366 466 17366 471 17367 472 17367 473 17367 477 17368 478 17368 479 17368 495 17369 496 17369 497 17369 495 17370 497 17370 498 17370 500 17371 502 17371 503 17371 500 17372 504 17372 501 17372 501 17373 504 17373 505 17373 505 17374 504 17374 506 17374 505 17375 506 17375 507 17375 506 17376 508 17376 460 17376 508 17377 509 17377 460 17377 460 17378 509 17378 510 17378 502 17379 512 17379 503 17379 502 17380 513 17380 512 17380 514 17381 512 17381 515 17381 514 17382 516 17382 512 17382 517 53 502 53 518 53 518 17383 502 17383 519 17383 519 17384 502 17384 501 17384 501 17385 505 17385 520 17385 520 17386 505 17386 521 17386 511 53 523 53 507 53 524 17387 525 17387 526 17387 529 17388 527 17388 530 17388 531 17389 532 17389 533 17389 532 17390 534 17390 533 17390 532 17391 536 17391 534 17391 534 17392 536 17392 538 17392 539 53 538 53 540 53 534 17393 538 17393 543 17393 542 53 540 53 544 53 544 53 540 53 545 53 546 17394 545 17394 547 17394 548 17395 547 17395 549 17395 550 53 549 53 551 53 550 53 548 53 549 53 544 17396 545 17396 546 17396 552 53 547 53 548 53 551 53 549 53 553 53 555 17397 549 17397 537 17397 531 17398 557 17398 556 17398 562 17399 560 17399 563 17399 560 17400 563 17400 566 17400 568 17401 569 17401 564 17401 571 53 569 53 568 53 573 17402 568 17402 575 17402 557 17403 575 17403 556 17403 557 53 573 53 575 53 576 17404 577 17404 579 17404 581 17405 558 17405 582 17405 582 17406 584 17406 581 17406 558 17407 556 17407 582 17407 551 17408 585 17408 586 17408 551 17409 553 17409 585 17409 554 17410 584 17410 553 17410 580 17411 567 17411 583 17411 580 17412 564 17412 567 17412 584 17413 567 17413 560 17413 586 17414 566 17414 563 17414 588 17415 563 17415 589 17415 591 17416 592 17416 593 17416 595 17417 592 17417 591 17417 592 17418 595 17418 596 17418 579 17419 596 17419 597 17419 597 17420 598 17420 579 17420 598 17421 597 17421 595 17421 595 17422 591 17422 598 17422 598 17423 591 17423 594 17423 599 17424 593 17424 592 17424 577 17425 557 17425 600 17425 599 17426 577 17426 600 17426 601 17427 600 17427 531 17427 574 17428 602 17428 603 17428 378 17429 604 17429 605 17429 378 17430 605 17430 375 17430 607 17431 375 17431 605 17431 609 17432 610 17432 611 17432 611 17433 612 17433 609 17433 611 17434 613 17434 612 17434 614 17435 611 17435 610 17435 614 17436 610 17436 615 17436 616 17437 620 17437 619 17437 621 17438 620 17438 622 17438 623 17439 621 17439 622 17439 624 17440 625 17440 626 17440 629 17441 632 17441 631 17441 632 17442 633 17442 634 17442 634 17443 633 17443 635 17443 638 17444 642 17444 640 17444 640 17445 642 17445 643 17445 640 17446 643 17446 644 17446 645 17447 646 17447 642 17447 647 17448 648 17448 422 17448 422 17449 649 17449 246 17449 643 17450 650 17450 644 17450 641 17451 651 17451 652 17451 654 17452 639 17452 638 17452 635 17453 633 17453 656 17453 656 17454 657 17454 659 17454 634 17455 635 17455 636 17455 632 17456 661 17456 660 17456 664 17457 631 17457 665 17457 626 17458 668 17458 669 17458 619 17459 670 17459 671 17459 410 17460 673 17460 610 17460 674 17461 675 17461 606 17461 371 17462 674 17462 604 17462 676 17463 379 17463 380 17463 676 17464 607 17464 608 17464 677 17465 674 17465 370 17465 674 17466 677 17466 675 17466 379 17467 677 17467 370 17467 376 17468 375 17468 380 17468 380 17469 375 17469 607 17469 609 17470 407 17470 610 17470 672 17471 678 17471 409 17471 617 17472 411 17472 403 17472 403 17473 609 17473 617 17473 673 17474 410 17474 678 17474 678 17475 410 17475 409 17475 610 17476 407 17476 410 17476 615 17477 610 17477 673 17477 673 17478 678 17478 682 17478 682 17479 678 17479 683 17479 678 17480 672 17480 686 17480 686 17481 687 17481 688 17481 690 17482 689 17482 691 17482 691 17483 689 17483 623 17483 692 17484 691 17484 695 17484 696 17485 695 17485 697 17485 700 17486 699 17486 701 17486 702 17487 703 17487 704 17487 705 17488 704 17488 706 17488 705 17489 706 17489 707 17489 705 17490 707 17490 708 17490 697 17491 695 17491 709 17491 710 17492 709 17492 711 17492 712 17493 711 17493 713 17493 712 17494 713 17494 714 17494 697 17495 709 17495 710 17495 665 17496 713 17496 664 17496 718 17497 720 17497 719 17497 718 17498 721 17498 720 17498 722 17499 721 17499 723 17499 723 17500 721 17500 726 17500 727 17501 726 17501 658 17501 730 17502 727 17502 729 17502 658 17503 726 17503 659 17503 728 17504 658 17504 731 17504 735 17505 734 17505 736 17505 735 17506 736 17506 737 17506 735 17507 737 17507 738 17507 739 17508 735 17508 738 17508 741 17509 742 17509 736 17509 741 17510 743 17510 742 17510 741 17511 246 17511 649 17511 743 17512 744 17512 745 17512 742 17513 743 17513 746 17513 747 17514 742 17514 746 17514 749 17515 748 17515 746 17515 750 17516 748 17516 749 17516 754 17517 753 17517 755 17517 752 17518 757 17518 438 17518 753 17519 256 17519 758 17519 755 17520 753 17520 759 17520 760 17521 759 17521 761 17521 762 17522 763 17522 761 17522 762 17523 764 17523 763 17523 765 17524 766 17524 762 17524 769 17525 759 17525 760 17525 761 17526 770 17526 771 17526 764 17527 762 17527 772 17527 772 17528 773 17528 774 17528 772 17529 774 17529 775 17529 774 17530 773 17530 776 17530 777 17531 778 17531 779 17531 776 17532 777 17532 780 17532 781 17533 780 17533 782 17533 720 17534 782 17534 719 17534 787 17535 786 17535 788 17535 792 17536 791 17536 793 17536 703 17537 701 17537 793 17537 794 17538 791 17538 792 17538 797 17539 798 17539 795 17539 717 17540 797 17540 710 17540 706 17541 801 17541 802 17541 707 17542 706 17542 803 17542 805 17543 806 17543 804 17543 808 17544 676 17544 608 17544 803 17545 804 17545 807 17545 810 17546 676 17546 808 17546 811 17547 803 17547 812 17547 807 17548 812 17548 803 17548 688 17549 813 17549 814 17549 688 17550 683 17550 686 17550 685 17551 684 17551 815 17551 685 17552 815 17552 808 17552 810 17553 807 17553 676 17553 698 17554 696 17554 697 17554 702 17555 700 17555 701 17555 794 17556 786 17556 791 17556 725 17557 724 17557 817 17557 818 17558 769 17558 819 17558 760 17559 819 17559 769 17559 820 17560 821 17560 740 17560 734 17561 740 17561 733 17561 730 17562 729 17562 822 17562 822 17563 823 17563 730 17563 823 17564 822 17564 763 17564 763 17565 764 17565 823 17565 742 17566 737 17566 736 17566 754 17567 751 17567 753 17567 821 17568 818 17568 819 17568 727 17569 723 17569 726 17569 785 17570 780 17570 784 17570 679 17571 680 17571 608 17571 825 17572 826 17572 827 17572 828 17573 831 17573 832 17573 833 17574 828 17574 832 17574 831 17575 828 17575 834 17575 834 17576 830 17576 835 17576 831 17577 834 17577 835 17577 838 17578 825 17578 837 17578 838 17579 836 17579 825 17579 838 17580 827 17580 839 17580 841 17581 600 17581 842 17581 842 17582 600 17582 601 17582 845 17583 844 17583 846 17583 851 17584 852 17584 853 17584 853 17585 852 17585 854 17585 859 17586 860 17586 861 17586 863 17587 864 17587 865 17587 871 17588 872 17588 873 17588 875 17589 876 17589 877 17589 877 17590 876 17590 878 17590 885 17591 884 17591 886 17591 889 17592 888 17592 890 17592 893 17593 894 17593 895 17593 895 17594 894 17594 896 17594 899 17595 898 17595 900 17595 901 17596 902 17596 903 17596 903 17597 902 17597 904 17597 905 17598 906 17598 907 17598 909 17599 910 17599 911 17599 915 17600 914 17600 916 17600 917 17601 918 17601 919 17601 921 17602 922 17602 923 17602 923 17603 922 17603 924 17603 925 17604 926 17604 927 17604 931 17605 930 17605 932 17605 933 17606 934 17606 935 17606 935 17607 934 17607 936 17607 940 17608 941 17608 942 17608 944 17609 945 17609 946 17609 946 17610 514 17610 947 17610 944 17611 946 17611 949 17611 949 17612 946 17612 947 17612 944 17613 949 17613 945 17613 945 17614 950 17614 238 17614 941 17615 940 17615 951 17615 951 17616 940 17616 952 17616 953 17617 952 17617 225 17617 888 53 226 53 225 53 888 53 954 53 226 53 226 17618 954 17618 231 17618 221 53 232 53 222 53 222 17619 232 17619 955 17619 222 17620 955 17620 224 17620 956 17621 235 17621 234 17621 887 17622 957 17622 888 17622 887 840 959 840 957 840 938 17623 958 17623 939 17623 959 17624 890 17624 961 17624 935 17625 939 17625 962 17625 964 17626 935 17626 962 17626 884 17627 965 17627 963 17627 933 53 964 53 934 53 934 17628 964 17628 966 17628 883 17629 967 17629 965 17629 967 17630 886 17630 969 17630 931 17631 936 17631 970 17631 970 842 936 842 968 842 881 53 975 53 879 53 930 810 974 810 932 810 932 17632 974 17632 976 17632 975 17633 882 17633 977 17633 978 17634 932 17634 976 17634 977 807 876 807 979 807 925 17635 927 17635 980 17635 875 817 981 817 876 817 925 53 980 53 926 53 877 53 983 53 875 53 983 17636 878 17636 985 17636 923 17637 928 17637 986 17637 921 17638 923 17638 988 17638 988 17639 923 17639 986 17639 871 17640 989 17640 872 17640 921 53 988 53 922 53 873 53 991 53 871 53 871 53 991 53 989 53 991 17641 874 17641 993 17641 994 17642 924 17642 992 17642 917 17643 919 17643 996 17643 868 17644 997 17644 995 17644 918 879 996 879 998 879 869 53 999 53 867 53 918 17645 998 17645 920 17645 920 17646 998 17646 1000 17646 999 17647 870 17647 1001 17647 915 17625 920 17625 1002 17625 870 17648 864 17648 1001 17648 1001 17649 864 17649 1003 17649 913 17650 915 17650 1004 17650 913 17651 1004 17651 914 17651 914 17652 1006 17652 916 17652 916 17653 1006 17653 1008 17653 865 17654 866 17654 1007 17654 909 17655 911 17655 1012 17655 910 6350 1012 6350 1014 6350 861 53 1015 53 859 53 912 17656 1014 17656 1016 17656 1015 17657 862 17657 1017 17657 1018 17658 912 17658 1016 17658 862 17659 856 17659 1017 17659 1017 17660 856 17660 1019 17660 905 17661 907 17661 1020 17661 1020 17662 907 17662 1018 17662 855 17663 1021 17663 856 17663 905 53 1020 53 906 53 857 53 1023 53 855 53 906 17664 1022 17664 908 17664 857 17665 858 17665 1023 17665 903 858 908 858 1026 858 1026 17666 908 17666 1024 17666 858 17667 852 17667 1025 17667 1028 17668 903 17668 1026 17668 851 17655 1029 17655 852 17655 853 53 1031 53 851 53 851 53 1031 53 1029 53 904 17669 1030 17669 1032 17669 853 17670 854 17670 1031 17670 1034 17671 904 17671 1032 17671 1033 17672 848 17672 1035 17672 897 864 899 864 1036 864 847 853 1037 853 848 853 847 2683 1039 2683 1037 2683 900 17673 1038 17673 1040 17673 1039 17674 850 17674 1041 17674 1041 17675 844 17675 1043 17675 893 17676 1044 17676 894 17676 894 17677 1044 17677 1046 17677 892 53 1048 53 603 53 603 17678 1048 17678 574 17678 845 17679 846 17679 1047 17679 1048 17680 891 17680 1053 17680 841 17681 1049 17681 1054 17681 846 17682 841 17682 1052 17682 1052 17683 841 17683 1054 17683 593 53 1055 53 594 53 593 17684 1056 17684 1055 17684 594 17685 1057 17685 1058 17685 509 17686 1056 17686 942 17686 942 17687 1056 17687 940 17687 940 17688 1056 17688 888 17688 884 17689 1056 17689 886 17689 886 17690 1056 17690 880 17690 880 17691 1056 17691 882 17691 882 17692 1056 17692 876 17692 878 17693 1056 17693 593 17693 872 17694 878 17694 593 17694 593 17695 599 17695 844 17695 850 17696 593 17696 844 17696 852 17697 593 17697 854 17697 852 17698 858 17698 593 17698 862 17699 593 17699 856 17699 593 17700 860 17700 866 17700 864 17701 593 17701 866 17701 864 17702 870 17702 593 17702 593 17703 870 17703 868 17703 874 17704 593 17704 868 17704 516 17705 514 17705 1058 17705 1058 17706 514 17706 946 17706 238 17707 235 17707 1058 17707 935 17708 936 17708 1058 17708 932 17709 1058 17709 931 17709 932 17710 927 17710 1058 17710 1058 17711 927 17711 928 17711 924 17712 919 17712 594 17712 594 17713 919 17713 920 17713 915 17714 594 17714 920 17714 915 17715 916 17715 594 17715 594 17716 916 17716 911 17716 912 17717 907 17717 594 17717 594 17718 907 17718 908 17718 594 17719 904 17719 899 17719 900 17720 594 17720 899 17720 594 17721 895 17721 598 17721 1058 17722 928 17722 594 17722 895 17723 896 17723 598 17723 1059 17724 509 17724 1060 17724 515 17725 1061 17725 514 17725 458 17726 510 17726 449 17726 510 17727 1059 17727 449 17727 1062 17728 1064 17728 1063 17728 1063 17729 1064 17729 1065 17729 443 17730 1064 17730 1066 17730 443 17731 1066 17731 444 17731 444 17732 1067 17732 1068 17732 1069 17733 1070 17733 1071 17733 1071 17734 1070 17734 1072 17734 1073 17735 1072 17735 479 17735 1071 17736 1072 17736 1074 17736 472 17737 1076 17737 1075 17737 1076 17738 472 17738 475 17738 470 17739 1080 17739 1079 17739 1082 17740 1081 17740 1083 17740 1082 17741 1083 17741 1084 17741 1089 17742 1087 17742 1088 17742 1090 17743 1091 17743 1092 17743 1094 17744 1095 17744 1092 17744 1094 17745 1097 17745 1096 17745 1094 17746 836 17746 1097 17746 838 17747 839 17747 836 17747 1104 17748 1103 17748 484 17748 1105 17749 1106 17749 1104 17749 1105 17750 1107 17750 1106 17750 1107 17751 491 17751 1108 17751 1110 17752 1109 17752 488 17752 1110 17753 496 17753 1111 17753 1112 17754 1111 17754 496 17754 494 17755 1113 17755 1112 17755 1112 17756 1113 17756 451 17756 451 17757 1113 17757 1114 17757 511 17758 457 17758 1115 17758 1098 17759 1099 17759 1100 17759 1115 17760 1116 17760 826 17760 840 17761 826 17761 1116 17761 457 17762 451 17762 1114 17762 451 17763 452 17763 1112 17763 1111 17764 459 17764 1110 17764 1117 17765 1069 17765 1071 17765 444 17766 1068 17766 1117 17766 1118 17767 1122 17767 1121 17767 1123 17768 1122 17768 1124 17768 1127 17769 1126 17769 1128 17769 1129 17770 1128 17770 1130 17770 1131 17771 1130 17771 1132 17771 1133 17772 1132 17772 1134 17772 1135 17773 1134 17773 1136 17773 1137 17774 1136 17774 1138 17774 1143 17775 1142 17775 1144 17775 1147 17776 1146 17776 1148 17776 1149 17777 1148 17777 1150 17777 1155 17778 1154 17778 1156 17778 1157 17779 1156 17779 1158 17779 1159 17780 1158 17780 1160 17780 508 17781 1160 17781 1161 17781 1056 17782 1161 17782 1162 17782 1055 17783 1162 17783 1057 17783 1055 17784 1056 17784 1162 17784 1123 17785 1124 17785 1125 17785 1147 17786 1148 17786 1149 17786 1151 17787 1152 17787 1153 17787 506 17788 1159 17788 508 17788 508 17789 1161 17789 1056 17789 503 17790 516 17790 1165 17790 1167 17791 1166 17791 1168 17791 1169 17792 1168 17792 1170 17792 1173 17793 1172 17793 1174 17793 1175 17794 1174 17794 1120 17794 1119 17795 1175 17795 1120 17795 1167 17796 1168 17796 1169 17796 1171 17797 1172 17797 1173 17797 516 17798 1058 17798 1164 17798 1179 17799 1116 17799 1097 17799 1178 17800 1179 17800 1097 17800 829 17801 835 17801 830 17801 466 17802 474 17802 467 17802 1181 17803 466 17803 1183 17803 1182 17804 1184 17804 1185 17804 1184 17805 1186 17805 1185 17805 1194 17806 1193 17806 1189 17806 1191 17807 1183 17807 1188 17807 1191 17808 1188 17808 1189 17808 1180 17809 477 17809 473 17809 1185 17810 1195 17810 1196 17810 473 17811 477 17811 1197 17811 1198 17812 1186 17812 1199 17812 1199 17813 1186 17813 1184 17813 1199 17814 1184 17814 1191 17814 1191 17815 1184 17815 1183 17815 1203 17816 1202 17816 1204 17816 1205 17817 1206 17817 1207 17817 1208 17818 1205 17818 1207 17818 1209 17819 1210 17819 1205 17819 1210 17820 1211 17820 490 17820 1208 17821 1217 17821 1205 17821 1224 17822 1222 17822 1221 17822 1222 17823 1204 17823 1223 17823 1223 17824 1204 17824 1219 17824 1223 17825 1207 17825 1220 17825 1220 17826 1206 17826 1221 17826 1208 17827 1223 17827 1217 17827 1217 17828 1223 17828 499 17828 1223 17829 1219 17829 499 17829 485 17830 1222 17830 1224 17830 485 17831 1224 17831 1218 17831 1218 17832 1224 17832 1225 17832 1226 17833 1227 17833 1228 17833 1228 17834 1227 17834 1229 17834 1231 17835 1230 17835 1232 17835 1233 17836 1232 17836 1226 17836 1229 17837 1230 17837 1231 17837 479 17838 1072 17838 477 17838 477 17839 1072 17839 1197 17839 1197 17840 1072 17840 1196 17840 1070 17841 1234 17841 1182 17841 472 17842 471 17842 476 17842 475 17843 472 17843 476 17843 472 17844 1180 17844 473 17844 475 17845 474 17845 1235 17845 1235 17846 1181 17846 1180 17846 1105 17847 484 17847 1215 17847 484 17848 1236 17848 485 17848 481 17849 1203 17849 1236 17849 490 17850 488 17850 491 17850 486 17851 488 17851 490 17851 491 17852 1201 17852 489 17852 487 17853 486 17853 1202 17853 487 17854 1202 17854 1201 17854 1209 17855 496 17855 1211 17855 467 17856 1078 17856 468 17856 470 17857 1078 17857 1237 17857 1078 17858 467 17858 1237 17858 486 17859 1211 17859 495 17859 490 17860 1211 17860 486 17860 489 17861 480 17861 1212 17861 1116 17862 1238 17862 1097 17862 1116 17863 493 17863 1239 17863 1116 17864 1114 17864 493 17864 1239 17865 493 17865 497 17865 497 17866 1236 17866 1239 17866 497 17867 487 17867 1236 17867 487 17868 497 17868 496 17868 487 17869 496 17869 1110 17869 482 17870 1201 17870 491 17870 1240 17871 484 17871 1103 17871 1096 17872 1097 17872 1241 17872 1241 17873 1097 17873 1238 17873 476 17874 467 17874 474 17874 1085 17875 1244 17875 1243 17875 1085 17876 465 17876 1244 17876 1244 17877 465 17877 464 17877 464 17878 1235 17878 1234 17878 475 17879 464 17879 468 17879 1234 17880 1180 17880 478 17880 1244 17881 1234 17881 1245 17881 1070 17882 1245 17882 1234 17882 1245 17883 1070 17883 1069 17883 1064 17884 1062 17884 1246 17884 1245 17885 1247 17885 1244 17885 1066 17886 1250 17886 1251 17886 1245 17887 1251 17887 1247 17887 1243 17888 1249 17888 1246 17888 1246 17889 1250 17889 1066 17889 1066 17890 1251 17890 1067 17890 1067 17891 1251 17891 1245 17891 1247 17892 1253 17892 1248 17892 1249 17893 1254 17893 1255 17893 1251 17894 1256 17894 1252 17894 1247 17895 1251 17895 1252 17895 1250 17896 1256 17896 1251 17896 1240 17897 1259 17897 1260 17897 1239 17898 1261 17898 1258 17898 1241 17899 1238 17899 1258 17899 1101 17900 1259 17900 1240 17900 1240 17901 1260 17901 1239 17901 1262 17902 1257 17902 1263 17902 1261 17903 1265 17903 1266 17903 1261 17904 1266 17904 1258 17904 1194 17905 1189 17905 1187 17905 1189 17906 1188 17906 1187 17906 1194 17907 1242 17907 1193 17907 1267 17908 1237 17908 476 17908 1197 17909 1196 17909 1195 17909 1200 17910 1197 17910 1195 17910 1214 17911 1216 17911 1225 17911 1225 17912 1216 17912 1218 17912 500 17913 1268 17913 504 17913 500 17914 1269 17914 1268 17914 500 17915 1270 17915 1269 17915 1200 17916 1271 17916 500 17916 1200 17917 1272 17917 1271 17917 1273 17918 1198 17918 1199 17918 1273 17919 1191 17919 1274 17919 1274 17920 1191 17920 1275 17920 1269 17921 1270 17921 1274 17921 1272 17922 1198 17922 1273 17922 1276 17923 1275 17923 1190 17923 1190 17924 1192 17924 1276 17924 1279 17925 1137 17925 1280 17925 1230 17926 1137 17926 1232 17926 1281 17927 1137 17927 1225 17927 1281 17928 1225 17928 1224 17928 1278 17929 1279 17929 1283 17929 1279 17930 1278 17930 1232 17930 1281 17931 1224 17931 1282 17931 1285 17932 1221 17932 504 17932 1286 17933 1285 17933 504 17933 1268 17934 1286 17934 504 17934 1256 17935 1272 17935 1252 17935 1272 17936 1256 17936 1271 17936 1274 17937 1254 17937 1253 17937 1273 17938 1253 17938 1252 17938 1272 17939 1273 17939 1252 17939 1271 17940 1255 17940 1270 17940 1274 17941 1253 17941 1273 17941 1263 17942 1266 17942 1283 17942 1281 17943 1265 17943 1264 17943 1279 17944 1264 17944 1262 17944 1279 17945 1262 17945 1263 17945 1283 17946 1266 17946 1282 17946 1281 17947 1264 17947 1280 17947 1280 17948 1264 17948 1279 17948 1084 17949 829 17949 1063 17949 513 17950 517 17950 1063 17950 1084 17951 517 17951 1088 17951 511 17952 1115 17952 523 17952 523 17953 1115 17953 1094 17953 826 17954 836 17954 1094 17954 509 17955 942 17955 1060 17955 361 17956 1041 17956 1043 17956 1035 17957 1041 17957 361 17957 1033 17958 361 17958 1027 17958 363 17959 993 17959 361 17959 363 17960 971 17960 977 17960 363 17961 969 17961 971 17961 363 17962 954 17962 961 17962 363 17963 952 17963 953 17963 363 17964 1287 17964 952 17964 363 17965 1060 17965 1287 17965 993 17966 995 17966 361 17966 1003 17967 361 17967 1001 17967 361 17968 1011 17968 1017 17968 1053 17969 1290 17969 1048 17969 461 17970 948 17970 1061 17970 1024 17971 1022 17971 1018 17971 1014 17972 1010 17972 1016 17972 1008 17973 1006 17973 1002 17973 996 17974 994 17974 998 17974 992 17975 990 17975 986 17975 980 17976 978 17976 982 17976 976 17977 974 17977 970 17977 964 17978 962 17978 966 17978 237 17979 950 17979 947 17979 947 17980 950 17980 949 17980 1046 17981 1042 17981 1051 17981 1054 17982 1049 17982 1289 17982 1060 17983 369 17983 1059 17983 1060 17984 366 17984 369 17984 1027 17985 1031 17985 1033 17985 1025 17986 1019 17986 1023 17986 1023 17987 1019 17987 1021 17987 1013 17988 1015 17988 1011 17988 1011 17989 1015 17989 1017 17989 1007 17990 1003 17990 1005 17990 991 17991 987 17991 989 17991 981 17992 983 17992 979 17992 979 17993 983 17993 985 17993 965 17994 967 17994 963 17994 961 17995 954 17995 959 17995 230 17996 229 17996 953 17996 1045 17997 1047 17997 1043 17997 515 17998 512 17998 442 17998 1061 17999 515 17999 442 17999 943 18000 951 18000 1288 18000 454 18001 1292 18001 1291 18001 1292 18002 454 18002 455 18002 435 18003 1292 18003 455 18003 435 18004 1296 18004 1292 18004 1299 18005 1297 18005 1295 18005 1298 18006 1297 18006 1299 18006 436 18007 1301 18007 1295 18007 1302 18008 1305 18008 1303 18008 1306 18009 1307 18009 1308 18009 1306 18010 744 18010 1307 18010 1309 18011 1307 18011 1310 18011 1301 18012 1302 18012 1304 18012 446 18013 447 18013 646 18013 246 18014 245 18014 422 18014 446 18015 1311 18015 414 18015 1315 18016 1313 18016 1317 18016 1314 18017 1316 18017 1320 18017 1320 18018 1316 18018 1322 18018 1316 18019 1315 18019 1323 18019 1316 18020 1323 18020 1322 18020 1323 18021 1315 18021 1318 18021 1323 18022 1318 18022 1325 18022 1323 18023 1325 18023 1324 18023 1324 18024 1325 18024 1326 18024 1326 18025 1325 18025 1318 18025 1318 18026 1327 18026 1326 18026 1317 18027 1328 18027 1319 18027 1319 18028 1328 18028 1327 18028 1327 18029 1328 18029 1329 18029 1328 18030 1330 18030 1329 18030 1329 18031 1330 18031 1331 18031 1330 18032 1317 18032 1312 18032 1330 18033 1312 18033 1331 18033 1331 18034 1312 18034 1321 18034 1333 18035 1332 18035 1335 18035 1336 18036 1335 18036 1337 18036 1338 18037 1332 18037 1339 18037 1340 18038 1338 18038 1339 18038 1332 18039 1334 18039 1339 18039 1339 18040 1334 18040 1341 18040 1339 18041 1341 18041 1342 18041 1335 18042 1338 18042 1337 18042 1337 18043 1338 18043 1343 18043 1342 18044 1340 18044 1339 18044 1342 18045 1341 18045 1345 18045 1345 18046 1341 18046 1346 18046 1341 18047 1347 18047 1346 18047 1348 18048 1334 18048 1349 18048 1351 18049 1353 18049 1357 18049 1357 18050 1353 18050 1358 18050 1353 18051 1354 18051 1358 18051 1360 18052 1354 18052 1356 18052 1356 18053 1354 18053 1350 18053 1354 18054 1360 18054 1359 18054 1359 18055 1360 18055 1361 18055 1355 18056 1364 18056 1356 18056 1356 18057 1364 18057 1362 18057 1364 18058 1355 18058 1366 18058 1366 18059 1355 18059 1352 18059 1366 18060 1352 18060 1367 18060 1367 18061 1352 18061 1368 18061 1351 18062 1357 18062 1352 18062 1373 18063 1369 18063 1372 18063 1376 18064 1373 18064 1372 18064 1373 18065 1376 18065 1377 18065 1378 18066 1369 18066 1379 18066 1380 18067 1374 18067 1373 18067 1377 18068 1381 18068 1373 18068 1377 18069 1382 18069 1381 18069 1381 18070 1382 18070 1383 18070 1384 18071 1375 18071 1385 18071 1375 18072 1388 18072 1386 18072 1375 18073 1371 18073 1387 18073 1371 18074 1370 18074 1387 18074 1389 18075 1390 18075 1391 18075 1393 18076 1389 18076 1392 18076 1391 18077 1395 18077 1392 18077 1396 18078 1392 18078 1395 18078 1393 18079 1396 18079 1397 18079 1390 18080 1389 18080 1398 18080 1398 18081 1389 18081 1399 18081 1399 18082 1394 18082 1400 18082 1393 18083 1401 18083 1400 18083 1397 18084 1402 18084 1401 18084 1401 18085 1402 18085 1403 18085 1402 18086 1404 18086 1403 18086 1405 18087 1395 18087 1406 18087 1395 18088 1408 18088 1406 18088 1395 18089 1391 18089 1407 18089 1391 18090 1390 18090 1407 18090 1407 18091 1390 18091 1408 18091 1413 18092 1409 18092 1412 18092 1411 18093 1415 18093 1412 18093 1416 18094 1412 18094 1415 18094 1416 18095 1413 18095 1412 18095 1418 18096 1409 18096 1419 18096 1419 18097 1414 18097 1420 18097 1413 18098 1421 18098 1420 18098 1416 18099 1422 18099 1417 18099 1423 18100 1424 18100 1425 18100 1424 18101 1416 18101 1415 18101 1424 18102 1415 18102 1425 18102 1427 18103 1428 18103 1415 18103 1415 18104 1411 18104 1427 18104 1427 18105 1410 18105 1428 18105 1432 18106 1429 18106 1431 18106 1429 18107 1433 18107 1434 18107 1431 18108 1435 18108 1432 18108 1433 18109 1436 18109 1437 18109 1430 18110 1429 18110 1438 18110 1440 18111 1434 18111 1433 18111 1433 18112 1441 18112 1440 18112 1436 18113 1442 18113 1437 18113 1437 18114 1442 18114 1441 18114 1441 18115 1442 18115 1443 18115 1442 18116 1436 18116 1444 18116 1442 18117 1444 18117 1443 18117 1443 18118 1444 18118 1445 18118 1444 18119 1435 18119 1445 18119 1435 18120 1431 18120 1447 18120 1449 18121 1450 18121 1451 18121 1452 18122 1449 18122 1451 18122 1453 18123 1449 18123 1452 18123 1451 18124 1455 18124 1452 18124 1456 18125 1452 18125 1455 18125 1456 18126 1453 18126 1452 18126 1458 18127 1449 18127 1459 18127 1449 18128 1454 18128 1459 18128 1459 18129 1454 18129 1460 18129 1456 18130 1462 18130 1457 18130 1457 18131 1462 18131 1461 18131 1461 18132 1462 18132 1463 18132 1462 18133 1456 18133 1464 18133 1463 18134 1464 18134 1465 18134 1464 18135 1455 18135 1465 18135 1467 18136 1468 18136 1455 18136 1467 18137 1450 18137 1468 18137 1469 18138 1473 18138 1474 18138 1473 18139 1476 18139 1477 18139 1470 18140 1469 18140 1478 18140 1469 18141 1474 18141 1479 18141 1473 18142 1481 18142 1480 18142 1477 18143 1482 18143 1481 18143 1483 18144 1484 18144 1485 18144 1484 18145 1476 18145 1475 18145 1475 18146 1471 18146 1487 18146 1471 18147 1470 18147 1487 18147 1493 18148 1489 18148 1492 18148 1493 18149 1496 18149 1497 18149 1499 18150 1494 18150 1500 18150 1500 18151 1494 18151 1493 18151 1502 18152 1504 18152 1503 18152 1507 18153 1508 18153 1495 18153 1495 18154 1508 18154 1506 18154 1491 18155 1490 18155 1507 18155 1508 18156 1490 18156 1498 18156 1514 18157 1509 18157 1511 18157 1514 18158 1515 18158 1509 18158 1516 18159 1512 18159 747 18159 747 18160 1513 18160 1517 18160 1513 18161 1518 18161 1517 18161 1520 18162 1522 18162 1521 18162 1521 18163 1522 18163 1523 18163 1522 18164 1514 18164 1524 18164 1510 18165 1516 18165 1511 18165 1511 18166 1516 18166 1526 18166 1528 18167 1527 18167 1306 18167 1306 18168 1527 18168 745 18168 1530 18169 1534 18169 1532 18169 745 18170 1527 18170 1531 18170 1535 18171 745 18171 1531 18171 1532 18172 1536 18172 1531 18172 1531 18173 1536 18173 1535 18173 1534 18174 1537 18174 1532 18174 1532 18175 1537 18175 1536 18175 1536 18176 1537 18176 1538 18176 1537 18177 1539 18177 1538 18177 1538 18178 1539 18178 1540 18178 1539 18179 1534 18179 1533 18179 757 18180 1539 18180 1533 18180 1541 18181 1302 18181 1533 18181 1533 18182 1302 18182 757 18182 1529 18183 1528 18183 1541 18183 438 18184 439 18184 752 18184 438 18185 1301 18185 437 18185 437 18186 1301 18186 436 18186 1543 18187 606 18187 675 18187 675 18188 677 18188 1543 18188 1543 18189 677 18189 1544 18189 1546 18190 1545 18190 806 18190 1546 18191 806 18191 805 18191 1551 18192 802 18192 801 18192 1554 18193 1553 18193 1552 18193 1554 18194 1555 18194 1553 18194 1553 18195 1555 18195 1556 18195 1558 18196 1557 18196 790 18196 1558 18197 790 18197 789 18197 1558 18198 1561 18198 1556 18198 1556 18199 1561 18199 1562 18199 1565 18200 1566 18200 1563 18200 1568 18201 771 18201 1567 18201 1562 18202 1561 18202 778 18202 1571 18203 767 18203 1572 18203 1574 18204 758 18204 256 18204 1573 18205 1293 18205 1291 18205 261 18206 752 18206 1294 18206 1542 18207 1575 18207 606 18207 606 18208 1575 18208 605 18208 605 18209 1575 18209 679 18209 744 18210 649 18210 423 18210 741 18211 649 18211 744 18211 744 18212 424 18212 425 18212 425 18213 415 18213 1310 18213 1310 18214 415 18214 414 18214 1311 18215 1310 18215 414 18215 1306 18216 1305 18216 1576 18216 1305 18217 1302 18217 1576 18217 1535 18218 1536 18218 746 18218 746 18219 1536 18219 1538 18219 1538 18220 1540 18220 749 18220 443 18221 442 18221 1065 18221 444 18222 1117 18222 445 18222 1579 18223 1580 18223 1577 18223 1579 18224 1581 18224 1580 18224 1580 18225 1581 18225 1582 18225 1583 18226 1581 18226 1584 18226 1589 18227 1588 18227 1590 18227 1591 18228 1590 18228 1592 18228 1301 18229 1304 18229 1594 18229 1307 18230 1309 18230 1593 18230 1309 18231 1591 18231 1592 18231 1597 18232 1589 18232 1590 18232 1599 18233 1600 18233 1588 18233 1602 18234 1583 18234 1584 18234 1583 18235 1603 18235 1581 18235 1603 18236 1582 18236 1581 18236 1100 18237 1604 18237 1098 18237 1090 18238 1607 18238 1608 18238 1082 18239 1609 18239 1610 18239 1077 18240 1611 18240 1612 18240 1613 18241 1596 18241 1591 18241 1614 18242 1613 18242 1591 18242 1090 18243 1609 18243 1087 18243 1087 18244 1609 18244 1082 18244 1082 18245 1610 18245 1080 18245 1080 18246 1611 18246 1079 18246 1079 18247 1611 18247 1077 18247 1077 18248 1612 18248 1076 18248 1589 18249 1076 18249 1615 18249 1598 18250 1615 18250 1616 18250 1618 18251 1600 18251 1599 18251 1600 18252 1618 18252 1619 18252 1621 18253 1601 18253 1620 18253 1621 18254 1585 18254 1601 18254 1585 18255 1621 18255 1602 18255 1622 18256 1603 18256 1583 18256 1624 18257 1625 18257 1582 18257 1582 18258 1625 18258 1580 18258 1106 18259 1577 18259 1626 18259 1600 18260 1619 18260 1587 18260 1603 18261 1624 18261 1582 18261 1580 18262 1626 18262 1577 18262 1626 18263 1605 18263 1104 18263 1605 18264 1102 18264 1104 18264 1075 18265 1596 18265 1073 18265 1298 18266 1300 18266 1578 18266 1174 18267 1592 18267 1590 18267 1174 18268 1172 18268 1592 18268 1592 18269 1172 18269 1170 18269 1308 18270 1164 18270 1163 18270 1303 18271 1162 18271 1304 18271 1592 18272 1170 18272 1593 18272 1308 18273 1163 18273 1303 18273 1162 18274 1161 18274 1304 18274 1594 18275 1158 18275 1156 18275 1595 18276 1156 18276 1154 18276 1595 18277 1154 18277 1152 18277 1579 18278 1150 18278 1148 18278 1579 18279 1148 18279 1146 18279 1581 18280 1146 18280 1144 18280 1581 18281 1144 18281 1142 18281 1584 6 1140 6 1138 6 1586 18282 1136 18282 1134 18282 1579 18283 1146 18283 1581 18283 1581 18284 1140 18284 1584 18284 1134 18285 1132 18285 1586 18285 1586 18286 1132 18286 1130 18286 1588 18287 1128 18287 1126 18287 1588 18288 1124 18288 1122 18288 1590 18289 1118 18289 1120 18289 1586 18290 1130 18290 1588 18290 1588 18291 1122 18291 1590 18291 450 18292 449 18292 367 18292 450 18293 367 18293 1292 18293 1296 18294 459 18294 1292 18294 459 18295 1296 18295 1298 18295 1107 18296 1298 18296 1627 18296 1578 18297 1107 18297 1627 18297 367 18298 368 18298 1292 18298 1563 18299 1629 18299 1630 18299 1556 18300 1630 18300 1631 18300 1553 18301 1631 18301 1632 18301 1547 18302 1632 18302 1633 18302 1543 18303 1633 18303 1634 18303 1542 18304 1634 18304 1635 18304 1553 18305 1632 18305 1547 18305 450 18306 1292 18306 459 18306 459 18307 1107 18307 1109 18307 1073 18308 1117 18308 1071 18308 1071 18309 1074 18309 1073 18309 1073 18310 1613 18310 1614 18310 1614 18311 1591 18311 1637 18311 265 18312 642 18312 638 18312 275 18313 638 18313 633 18313 281 18314 633 18314 629 18314 270 18315 616 18315 612 18315 275 18316 633 18316 281 18316 286 18317 625 18317 267 18317 1638 18318 1311 18318 446 18318 1636 18319 446 18319 645 18319 1636 18320 1638 18320 446 18320 1638 18321 1310 18321 1311 18321 1638 18322 1636 18322 1637 18322 1635 18323 1634 18323 1640 18323 1629 18324 1644 18324 1645 18324 1646 18325 1629 18325 1645 18325 1650 18326 1630 18326 1649 18326 1650 18327 1651 18327 1630 18327 1630 18328 1651 18328 1652 18328 1629 18329 1648 18329 1630 18329 1631 18330 1655 18330 1657 18330 1659 18331 1631 18331 1658 18331 1659 18332 1660 18332 1631 18332 1632 18333 1661 18333 1662 18333 1663 18334 1633 18334 1632 18334 1665 18335 1664 18335 1663 18335 1664 18336 1666 18336 1633 18336 1634 18337 1666 18337 1640 18337 1635 18338 1640 18338 1668 18338 1668 18339 1669 18339 1635 18339 1635 18340 1669 18340 1670 18340 1657 18341 1672 18341 1673 18341 1657 18342 1674 18342 1672 18342 1654 18343 1676 18343 1677 18343 1678 18344 1650 18344 1680 18344 1649 18345 1648 18345 1683 18345 1683 18346 1648 18346 1684 18346 1647 18347 1685 18347 1686 18347 1685 18348 765 18348 1686 18348 1685 18349 1646 18349 1687 18349 771 18350 1646 18350 1688 18350 1645 18351 1644 18351 1689 18351 1689 18352 1644 18352 1690 18352 1643 18353 1691 18353 1656 18353 1643 18354 1641 18354 1691 18354 364 53 1695 53 1694 53 364 18355 1696 18355 1695 18355 364 18356 1698 18356 1697 18356 364 18357 1699 18357 1698 18357 364 18358 1700 18358 1699 18358 364 18359 1701 18359 1700 18359 364 18360 1704 18360 1703 18360 364 18361 1705 18361 1704 18361 364 18362 1706 18362 1705 18362 1709 18363 1708 18363 1667 18363 1701 18364 1710 18364 1711 18364 1711 18365 1665 18365 1663 18365 1712 18366 1700 18366 1713 18366 1714 18367 1713 18367 1662 18367 1697 18368 1698 18368 1715 18368 1697 18369 1715 18369 1716 18369 1659 18370 1715 18370 1660 18370 1716 18371 1715 18371 1659 18371 1717 18372 1696 18372 1718 18372 1657 18373 1673 18373 1658 18373 1695 18374 1696 18374 1717 18374 362 18375 1694 18375 1719 18375 1720 18376 362 18376 1719 18376 1721 53 1720 53 1722 53 1722 18377 1720 18377 1723 18377 1675 18378 1719 18378 1694 18378 1721 18379 1725 18379 362 18379 362 18380 1725 18380 1726 18380 1728 18381 1727 18381 1729 18381 1650 18382 1649 18382 1730 18382 1726 18383 1682 18383 1730 18383 1728 18384 1729 18384 1686 18384 1734 18385 1733 18385 1735 18385 1735 18386 1656 18386 1734 18386 1656 18387 1735 18387 1644 18387 1645 18388 1688 18388 1646 18388 1737 18389 1688 18389 1645 18389 1738 18390 636 18390 304 18390 304 18391 636 18391 322 18391 1741 18392 303 18392 1742 18392 302 18393 288 18393 1743 18393 289 18394 293 18394 1746 18394 1746 18395 293 18395 1747 18395 1748 18396 668 18396 343 18396 291 18397 292 18397 1748 18397 1749 18398 292 18398 301 18398 301 18399 627 18399 1749 18399 300 18400 296 18400 1750 18400 1750 18401 296 18401 622 18401 1751 18402 1752 18402 349 18402 446 18403 646 18403 645 18403 1756 18404 1755 18404 1757 18404 1758 18405 1757 18405 1759 18405 1760 18406 1759 18406 1761 18406 530 18407 1761 18407 529 18407 1756 18408 1757 18408 1758 18408 1760 18409 1761 18409 530 18409 530 18410 355 18410 1760 18410 299 18411 1760 18411 355 18411 299 18412 273 18412 1758 18412 1758 18413 273 18413 1756 18413 274 18414 1756 18414 273 18414 272 18415 612 18415 274 18415 274 18416 612 18416 1762 18416 1763 18417 274 18417 1762 18417 1763 18418 1754 18418 274 18418 1754 18419 1763 18419 1755 18419 1765 18420 539 18420 541 18420 1766 18421 541 18421 542 18421 1767 18422 542 18422 544 18422 1768 18423 1767 18423 544 18423 1765 18424 541 18424 1766 18424 1768 18425 1671 18425 1767 18425 1765 18426 1669 18426 1706 18426 1706 18427 1764 18427 1765 18427 1766 18428 1669 18428 1765 18428 535 18429 543 18429 1764 18429 1050 18430 1764 18430 1289 18430 535 18431 531 18431 533 18431 1769 18432 559 18432 561 18432 565 18433 1769 18433 561 18433 1770 53 528 53 1771 53 528 18434 529 18434 1771 18434 1771 18435 529 18435 1761 18435 1759 53 1757 53 1772 53 1776 53 1775 53 1777 53 1778 53 589 53 590 53 559 18436 1778 18436 590 18436 559 18437 1779 18437 1778 18437 1779 18438 1769 18438 572 18438 1772 18439 1755 18439 1774 18439 1776 18440 1777 18440 1778 18440 572 18441 524 18441 1780 18441 334 18442 355 18442 1290 18442 1781 18443 334 18443 1290 18443 355 18444 530 18444 1290 18444 574 18445 527 18445 526 18445 525 18446 574 18446 526 18446 1290 18447 530 18447 527 18447 334 18448 1781 18448 307 18448 1040 18449 1034 18449 1781 18449 1042 18450 1781 18450 1051 18450 1034 18451 1032 18451 1781 18451 1024 18452 1018 18452 1781 18452 1016 18453 1010 18453 1781 18453 1008 18454 1002 18454 1781 18454 1002 18455 1000 18455 1781 18455 1781 18456 992 18456 462 18456 984 18457 978 18457 462 18457 976 18458 970 18458 462 18458 970 18459 968 18459 462 18459 233 18460 237 18460 462 18460 947 18461 948 18461 462 18461 1051 18462 1781 18462 1053 18462 1053 18463 1781 18463 1290 18463 1042 18464 1040 18464 1781 18464 1034 18465 1038 18465 1036 18465 1302 18466 1541 18466 1576 18466 1604 18467 1784 18467 1785 18467 1608 18468 1787 18468 1788 18468 1788 18469 1789 18469 1609 18469 1791 18470 1610 18470 1790 18470 1791 18471 1611 18471 1610 18471 1604 18472 1785 18472 1606 18472 1607 18473 1787 18473 1608 18473 1797 18474 1616 18474 1796 18474 1616 18475 1798 18475 1617 18475 1616 18476 1797 18476 1798 18476 1796 18477 1616 18477 1615 18477 1076 18478 1795 18478 1796 18478 1799 18479 1617 18479 1798 18479 1800 18480 1801 18480 1619 18480 1801 18481 1802 18481 1620 18481 1621 18482 1620 18482 1803 18482 1804 18483 1805 18483 1806 18483 1810 18484 1808 18484 1805 18484 1805 18485 1811 18485 1810 18485 1809 18486 1808 18486 1810 18486 1811 18487 1805 18487 1804 18487 1812 18488 1811 18488 1804 18488 1814 18489 1808 18489 1807 18489 1806 18490 1805 18490 1814 18490 1813 18491 1804 18491 1806 18491 1817 18492 1818 18492 1819 18492 1820 18493 1821 18493 1818 18493 1822 18494 1817 18494 1816 18494 1823 18495 1816 18495 1824 18495 1825 18496 1824 18496 1815 18496 1826 18497 1821 18497 1820 18497 1826 18498 1818 18498 1821 18498 1827 18499 1828 18499 1829 18499 1827 18500 1829 18500 1830 18500 1835 18501 1833 18501 1834 18501 1836 18502 1837 18502 1828 18502 1827 18503 1836 18503 1828 18503 1836 18504 1838 18504 1837 18504 1837 18505 1838 18505 1828 18505 1828 18506 1830 18506 1829 18506 1782 18507 1839 18507 1783 18507 1783 18508 1839 18508 1840 18508 1841 18509 1842 18509 1785 18509 1843 18510 1786 18510 1833 18510 1786 18511 1843 18511 1787 18511 1843 18512 1810 18512 1787 18512 1810 18513 1843 18513 1835 18513 1836 18514 1810 18514 1835 18514 1810 18515 1836 18515 1844 18515 1810 18516 1844 18516 1809 18516 1783 18517 1840 18517 1784 18517 1845 18518 1827 18518 1842 18518 1836 18519 1845 18519 1844 18519 1827 18520 1845 18520 1836 18520 1844 18521 1803 18521 1809 18521 1809 18522 1803 18522 1807 18522 1803 18523 1802 18523 1807 18523 1813 18524 1825 18524 1819 18524 1788 18525 1812 18525 1789 18525 1810 18526 1811 18526 1787 18526 1802 18527 1801 18527 1825 18527 1823 18528 1846 18528 1799 18528 1792 18529 1799 18529 1798 18529 1798 18530 1793 18530 1792 18530 1798 18531 1797 18531 1793 18531 1794 18532 1797 18532 1796 18532 1612 18533 1796 18533 1795 18533 1612 18534 1794 18534 1796 18534 1801 18535 1800 18535 1846 18535 1823 18536 1799 18536 1791 18536 1820 18537 1823 18537 1791 18537 1791 18538 1790 18538 1820 18538 1826 18539 1820 18539 1790 18539 1786 18540 1785 18540 1832 18540 1813 18541 1806 18541 1807 18541 1835 18542 1843 18542 1833 18542 1839 18543 1624 18543 1840 18543 1840 18544 1624 18544 1841 18544 1842 18545 1623 18545 1845 18545 1842 18546 1622 18546 1623 18546 1845 18547 1623 18547 1602 18547 1844 18548 1602 18548 1621 18548 1844 18549 1621 18549 1803 18549 1542 18550 1849 18550 1575 18550 1851 18551 1853 18551 1854 18551 1857 6 1855 6 1856 6 1857 18552 1858 18552 1855 18552 1856 18553 1859 18553 1860 18553 1860 18554 1859 18554 1861 18554 1865 18555 1864 18555 1866 18555 1866 18556 1867 18556 1865 18556 1866 6 1868 6 1867 6 1870 18557 1869 18557 1871 18557 1860 6 1861 6 1862 6 1864 6 1863 6 1872 6 1873 18558 1872 18558 1874 18558 1877 18559 1876 18559 1878 18559 1575 6 1877 6 1878 6 1575 6 1880 6 1879 6 1575 18560 1849 18560 1880 18560 1882 18561 1884 18561 1885 18561 1886 18562 1882 18562 1885 18562 1886 18563 1887 18563 1882 18563 1886 18564 1889 18564 1888 18564 1890 6 614 6 1878 6 1890 6 1888 6 614 6 1870 18565 1867 18565 1869 18565 1865 6 1862 6 1864 6 1875 6 1873 6 1874 6 1869 18566 1868 18566 1847 18566 1881 6 1872 6 1863 6 1847 18567 1891 18567 1869 18567 1889 18568 1886 18568 613 18568 613 18569 1886 18569 1762 18569 1763 18570 1886 18570 1885 18570 1871 18571 1892 18571 1893 18571 1869 18572 1891 18572 1871 18572 1854 18573 1855 18573 588 18573 588 18574 1855 18574 587 18574 1895 18575 1851 18575 588 18575 1895 18576 1896 18576 1852 18576 1894 18577 1852 18577 1896 18577 1851 18578 1854 18578 588 18578 1893 18579 548 18579 587 18579 1893 18580 552 18580 548 18580 544 18581 1871 18581 1891 18581 548 18582 550 18582 587 18582 1768 18583 1891 18583 1671 18583 1768 18584 544 18584 1891 18584 1671 18585 1848 18585 1542 18585 1763 18586 1894 18586 1755 18586 1895 18587 1775 18587 1896 18587 1896 18588 1773 18588 1894 18588 536 18589 1897 18589 538 18589 538 18590 1897 18590 1899 18590 540 18591 1899 18591 1900 18591 547 18592 1901 18592 1902 18592 549 18593 1902 18593 1903 18593 538 18594 1899 18594 540 18594 540 18595 1901 18595 545 18595 545 18596 1901 18596 547 18596 547 18597 1902 18597 549 18597 1897 18598 1904 18598 1899 18598 1902 18599 1908 18599 1909 18599 1902 18600 1909 18600 1910 18600 1903 18601 1910 18601 1905 18601 1898 18602 1905 18602 1897 18602 1900 18603 1907 18603 1901 18603 1901 53 1908 53 1902 53 1902 18604 1910 18604 1903 18604 1911 18605 1771 18605 1772 18605 1911 18606 1912 18606 1771 18606 1771 18607 1912 18607 1913 18607 1780 18608 1914 18608 1915 18608 1779 18609 1915 18609 1916 18609 1771 18610 1913 18610 1770 18610 1770 18611 1914 18611 1780 18611 1780 18612 1915 18612 1779 18612 1779 18613 1916 18613 1778 18613 1776 18614 1918 18614 1774 18614 1919 18615 1911 18615 1920 18615 1919 18616 1912 18616 1911 18616 1913 18617 1919 18617 1921 18617 1915 18618 1922 18618 1923 18618 1916 18619 1923 18619 1924 18619 1918 18620 1925 18620 1920 18620 1913 18621 1921 18621 1914 18621 1914 18622 1922 18622 1915 18622 1915 53 1923 53 1916 53 1916 18623 1924 18623 1917 18623 1917 18624 1925 18624 1918 18624 1926 18625 1927 18625 1882 18625 1878 18626 1930 18626 1931 18626 1888 18627 1931 18627 1932 18627 1887 18628 1932 18628 1926 18628 1883 18629 1928 18629 1872 18629 1872 18630 1928 18630 1874 18630 1878 18631 1931 18631 1890 18631 1890 18632 1931 18632 1888 18632 1929 18633 1927 18633 1930 18633 1928 18634 1927 18634 1929 18634 1933 18635 1934 18635 1864 18635 1866 18636 1934 18636 1935 18636 1868 18637 1935 18637 1936 18637 1877 18638 1939 18638 1940 18638 1875 18639 1940 18639 1933 18639 1873 18640 1875 18640 1933 18640 1866 18641 1935 18641 1868 18641 1868 18642 1936 18642 1880 18642 1880 18643 1938 18643 1879 18643 1877 18644 1940 18644 1875 18644 1936 18645 1935 18645 1937 18645 1940 18646 1939 18646 1934 18646 1933 18647 1940 18647 1934 18647 1941 18648 1942 18648 1856 18648 1856 18649 1942 18649 1857 18649 1858 18650 1942 18650 1943 18650 1870 18651 1944 18651 1945 18651 1865 18652 1945 18652 1946 18652 1862 18653 1946 18653 1947 18653 1857 18654 1942 18654 1858 18654 1858 18655 1943 18655 1870 18655 1865 18656 1946 18656 1862 18656 1862 18657 1947 18657 1860 18657 1944 18658 1950 18658 1951 18658 1946 18659 1953 18659 1954 18659 1947 18660 1954 18660 1948 18660 1942 18661 1949 18661 1943 18661 1943 18662 1950 18662 1944 18662 1944 18663 1951 18663 1945 18663 1945 18664 1953 18664 1946 18664 1955 18665 1851 18665 1850 18665 1955 18666 1956 18666 1851 18666 1859 18667 1957 18667 1958 18667 1861 18668 1958 18668 1959 18668 1881 18669 1959 18669 1960 18669 1881 18670 1960 18670 1961 18670 1884 18671 1961 18671 1962 18671 1850 18672 1962 18672 1955 18672 1853 18673 1957 18673 1859 18673 1859 18674 1958 18674 1861 18674 1863 18675 1959 18675 1881 18675 1958 18676 1965 18676 1966 18676 1959 18677 1966 18677 1967 18677 1959 18678 1967 18678 1968 18678 1962 18679 1969 18679 1963 18679 1959 18680 1968 18680 1960 18680 1932 18681 1930 18681 1970 18681 1930 18682 1927 18682 1970 18682 1927 18683 1932 18683 1970 18683 1939 18684 1971 18684 1934 18684 1939 18685 1937 18685 1971 18685 1920 18686 1972 18686 1963 18686 1920 18687 1925 18687 1972 18687 1975 18688 1967 18688 1966 18688 1976 18689 1965 18689 1964 18689 1925 18690 1924 18690 1976 18690 1965 18691 1976 18691 1924 18691 1965 18692 1924 18692 1966 18692 1966 18693 1923 18693 1975 18693 1974 18694 1921 18694 1919 18694 1963 18695 1973 18695 1920 18695 1975 18696 1922 18696 1967 18696 1968 18697 1921 18697 1974 18697 1969 18698 1919 18698 1973 18698 1905 18699 1977 18699 1948 18699 1949 18700 1948 18700 1977 18700 1978 18701 1948 18701 1954 18701 1981 18702 1950 18702 1949 18702 1910 18703 1981 18703 1949 18703 1910 18704 1909 18704 1981 18704 1909 18705 1908 18705 1951 18705 1950 18706 1909 18706 1951 18706 1951 18707 1908 18707 1980 18707 1908 18708 1907 18708 1980 18708 1952 18709 1907 18709 1906 18709 1979 18710 1906 18710 1904 18710 1978 18711 1904 18711 1905 18711 1948 18712 1978 18712 1905 18712 1980 18713 1907 18713 1952 18713 1953 18714 1906 18714 1979 18714 1979 18715 1904 18715 1954 18715 1954 18716 1904 18716 1978 18716 771 18717 1688 18717 1736 18717 1982 18718 771 18718 1736 18718 1982 18719 1728 18719 1983 18719 1984 18720 279 18720 309 18720 1986 18721 284 18721 323 18721 1987 18722 1986 18722 323 18722 1987 18723 323 18723 316 18723 1989 18724 790 18724 1675 18724 1989 18725 1675 18725 1694 18725 1694 18726 1695 18726 1989 18726 800 18727 1715 18727 1698 18727 1992 18728 800 18728 1698 18728 1698 18729 1699 18729 1992 18729 1992 18730 1699 18730 1993 18730 1993 18731 1699 18731 1712 18731 1550 18732 1665 18732 802 18732 802 18733 1665 18733 1710 18733 1994 18734 802 18734 1702 18734 1702 18735 1703 18735 1994 18735 805 18736 1995 18736 1703 18736 1745 18737 290 18737 337 18737 1745 18738 337 18738 335 18738 335 18739 328 18739 1745 18739 1745 18740 328 18740 1996 18740 1996 18741 328 18741 329 18741 296 18742 348 18742 622 18742 622 18743 348 18743 1997 18743 670 18744 360 18744 2000 18744 352 18745 347 18745 2000 18745 2000 18746 347 18746 2001 18746 2002 18747 301 18747 350 18747 2002 18748 350 18748 344 18748 344 18749 340 18749 2002 18749 2003 18750 340 18750 341 18750 2004 18751 353 18751 358 18751 2006 18752 2005 18752 359 18752 293 18753 342 18753 1747 18753 2009 18754 319 18754 2010 18754 636 18755 320 18755 322 18755 1724 18756 1677 18756 789 18756 1659 18757 2011 18757 2012 18757 1662 18758 2014 18758 1663 18758 2014 18759 1713 18759 2016 18759 1668 18760 1640 18760 1544 18760 2017 18761 1640 18761 1667 18761 1667 18762 1708 18762 2017 18762 2017 18763 1708 18763 2018 18763 386 18764 388 18764 2019 18764 2019 18765 388 18765 2020 18765 388 18766 390 18766 2020 18766 2020 18767 390 18767 2021 18767 1333 18768 1336 18768 1334 18768 276 18769 2023 18769 2024 18769 2025 18770 321 18770 318 18770 2026 18771 321 18771 2025 18771 318 18772 317 18772 2025 18772 2027 18773 317 18773 324 18773 659 18774 2028 18774 324 18774 2027 18775 324 18775 2028 18775 2030 18776 1679 18776 778 18776 2031 18777 1729 18777 1727 18777 1727 18778 1726 18778 2031 18778 2031 18779 1726 18779 2032 18779 770 18780 2034 18780 1737 18780 1645 18781 1689 18781 1737 18781 1737 18782 1689 18782 770 18782 2035 18783 1734 18783 767 18783 767 18784 1734 18784 1656 18784 250 18785 262 18785 248 18785 1293 18786 262 18786 261 18786 753 18787 254 18787 255 18787 752 18788 261 18788 254 18788 1573 18789 262 18789 1293 18789 262 18790 1573 18790 257 18790 257 18791 1573 18791 1574 18791 1692 18792 1574 18792 1573 18792 1573 18793 1572 18793 1692 18793 1691 18794 1692 18794 1572 18794 1691 18795 1572 18795 767 18795 758 18796 2035 18796 759 18796 1693 18797 1734 18797 758 18797 758 18798 1734 18798 2035 18798 2034 18799 770 18799 761 18799 768 18800 1571 18800 1690 18800 1689 18801 1690 18801 1571 18801 1689 18802 1571 18802 1567 18802 1567 18803 771 18803 1689 18803 1733 18804 1732 18804 2036 18804 761 18805 771 18805 1982 18805 1982 18806 762 18806 761 18806 1567 18807 1566 18807 1568 18807 1570 18808 1568 18808 1566 18808 765 18809 1685 18809 1570 18809 765 18810 1728 18810 1686 18810 2032 18811 2033 18811 773 18811 766 18812 1566 18812 1684 18812 1684 18813 1565 18813 1683 18813 1684 18814 1566 18814 1565 18814 1565 18815 1569 18815 1683 18815 773 18816 762 18816 2031 18816 766 18817 2031 18817 762 18817 1681 18818 2037 18818 773 18818 2037 18819 2030 18819 777 18819 773 18820 1569 18820 1681 18820 1569 18821 1564 18821 1680 18821 1569 18822 1680 18822 1681 18822 2037 18823 1682 18823 1725 18823 741 18824 736 18824 2038 18824 2038 18825 736 18825 650 18825 247 18826 643 18826 245 18826 741 18827 243 18827 242 18827 741 18828 242 18828 246 18828 1984 18829 1985 18829 736 18829 640 18830 2040 18830 651 18830 644 18831 2040 18831 640 18831 644 18832 2041 18832 2040 18832 644 18833 2039 18833 2041 18833 2039 18834 258 18834 314 18834 734 18835 731 18835 2043 18835 734 18836 2043 18836 2042 18836 315 18837 2024 18837 653 18837 2042 18838 315 18838 653 18838 732 18839 731 18839 1988 18839 656 18840 639 18840 654 18840 1988 18841 312 18841 732 18841 732 18842 312 18842 306 18842 2028 18843 726 18843 2027 18843 2026 18844 635 18844 2044 18844 637 18845 635 18845 2026 18845 656 18846 659 18846 2029 18846 726 18847 721 18847 2025 18847 1677 18848 1676 18848 1561 18848 1677 18849 1558 18849 789 18849 784 18850 790 18850 1989 18850 1560 18851 791 18851 1990 18851 1559 18852 1560 18852 1990 18852 1555 18853 1559 18853 1672 18853 1990 18854 1717 18854 1559 18854 1559 18855 1717 18855 1673 18855 2047 18856 2048 18856 799 18856 793 18857 791 18857 2049 18857 2049 18858 791 18858 1560 18858 1560 18859 1555 18859 2011 18859 1560 18860 2011 18860 2013 18860 2012 18861 2011 18861 1554 18861 1554 18862 799 18862 2012 18862 1659 18863 2012 18863 1716 18863 800 18864 799 18864 1991 18864 2051 18865 1554 18865 1552 18865 2051 18866 2050 18866 1554 18866 1993 18867 2053 18867 703 18867 703 18868 2053 18868 2052 18868 1993 18869 1712 18869 1714 18869 2054 18870 801 18870 706 18870 2052 18871 704 18871 703 18871 2052 18872 2016 18872 704 18872 2055 18873 704 18873 2016 18873 2016 18874 2052 18874 2014 18874 1552 18875 1549 18875 2052 18875 2052 18876 1549 18876 2015 18876 1663 18877 2015 18877 1711 18877 2054 18878 1701 18878 801 18878 801 18879 1701 18879 1711 18879 1550 18880 1548 18880 2056 18880 2057 18881 2056 18881 2058 18881 1994 18882 1995 18882 804 18882 1994 18883 804 18883 706 18883 718 18884 662 18884 2009 18884 2009 18885 2010 18885 721 18885 637 18886 2010 18886 636 18886 661 18887 1739 18887 1740 18887 661 18888 632 18888 634 18888 2009 18889 662 18889 325 18889 2059 18890 663 18890 662 18890 718 18891 713 18891 2060 18891 2060 18892 713 18892 665 18892 631 18893 632 18893 660 18893 1742 18894 660 18894 1741 18894 287 18895 1741 18895 333 18895 333 18896 1741 18896 663 18896 2059 18897 333 18897 663 18897 667 18898 1745 18898 711 18898 1745 18899 713 18899 711 18899 667 18900 666 18900 1744 18900 1744 18901 1745 18901 667 18901 1744 18902 666 18902 2061 18902 631 18903 664 18903 2061 18903 664 18904 329 18904 331 18904 2062 18905 2063 18905 667 18905 711 18906 709 18906 2064 18906 711 18907 2064 18907 2062 18907 668 18908 2008 18908 2064 18908 2064 18909 709 18909 668 18909 630 18910 667 18910 1746 18910 2063 18911 1746 18911 667 18911 289 18912 1746 18912 338 18912 338 18913 1746 18913 2063 18913 2062 18914 336 18914 338 18914 2062 18915 338 18915 2063 18915 1999 18916 2065 18916 695 18916 623 18917 622 18917 691 18917 1999 18918 345 18918 351 18918 2066 18919 670 18919 619 18919 619 18920 621 18920 2066 18920 1751 18921 2066 18921 621 18921 1753 18922 2066 18922 1751 18922 1752 18923 1751 18923 623 18923 2000 18924 2001 18924 689 18924 623 18925 689 18925 2001 18925 2001 18926 347 18926 349 18926 2067 18927 809 18927 676 18927 676 18928 2068 18928 2067 18928 2068 18929 804 18929 806 18929 806 18930 1545 18930 2017 18930 1545 18931 1544 18931 2017 18931 1707 18932 1544 18932 809 18932 809 18933 1705 18933 1707 18933 2005 18934 671 18934 2004 18934 2004 18935 671 18935 686 18935 672 18936 618 18936 2069 18936 618 18937 619 18937 2007 18937 619 18938 671 18938 2007 18938 2070 18939 672 18939 2069 18939 354 18940 353 18940 2070 18940 2070 18941 353 18941 2004 18941 624 18942 626 18942 669 18942 1749 18943 669 18943 1748 18943 1749 18944 624 18944 669 18944 669 18945 668 18945 1748 18945 695 18946 628 18946 2002 18946 668 18947 709 18947 2003 18947 2003 18948 341 18948 343 18948 668 18949 2003 18949 343 18949 685 18950 399 18950 682 18950 399 18951 673 18951 682 18951 680 18952 2020 18952 608 18952 2020 18953 2021 18953 608 18953 397 18954 396 18954 808 18954 1329 18955 812 18955 1327 18955 1329 18956 814 18956 812 18956 1329 18957 1331 18957 814 18957 1331 18958 683 18958 688 18958 1321 18959 1320 18959 684 18959 684 18960 1320 18960 1322 18960 1324 18961 1326 18961 807 18961 1324 18962 807 18962 810 18962 1326 18963 1327 18963 812 18963 1346 18964 708 18964 1345 18964 1346 18965 694 18965 708 18965 694 18966 816 18966 708 18966 1346 18967 1348 18967 694 18967 1348 18968 1349 18968 687 18968 811 18969 1343 18969 803 18969 1343 18970 707 18970 803 18970 1344 18971 708 18971 707 18971 1358 18972 696 18972 698 18972 693 18973 1363 18973 1365 18973 1365 18974 1367 18974 705 18974 702 18975 1357 18975 700 18975 797 18976 796 18976 1388 18976 797 18977 1379 18977 710 18977 1379 18978 1380 18978 697 18978 1379 18979 697 18979 710 18979 1380 18980 1381 18980 698 18980 698 18981 1381 18981 1383 18981 1383 18982 1385 18982 699 18982 699 18983 1385 18983 701 18983 788 18984 1408 18984 716 18984 1398 18985 1399 18985 712 18985 1398 18986 712 18986 716 18986 1399 18987 1400 18987 717 18987 798 18988 717 18988 1401 18988 1405 18989 786 18989 794 18989 1406 18990 788 18990 786 18990 1419 18991 1420 18991 714 18991 1419 18992 714 18992 719 18992 1420 18993 715 18993 714 18993 787 18994 1421 18994 1423 18994 787 18995 715 18995 1421 18995 1423 18996 1425 18996 787 18996 1425 18997 1426 18997 780 18997 1426 18998 1428 18998 782 18998 1426 18999 782 18999 780 18999 1438 19000 725 19000 1448 19000 1438 19001 1439 19001 722 19001 1439 19002 1440 19002 720 19002 1440 19003 1441 19003 720 19003 783 19004 720 19004 1441 19004 781 19005 783 19005 1441 19005 1445 19006 1446 19006 774 19006 1445 19007 774 19007 776 19007 1446 19008 1448 19008 775 19008 1458 19009 727 19009 730 19009 1459 19010 723 19010 727 19010 1460 19011 1461 19011 724 19011 1460 19012 724 19012 723 19012 817 19013 1463 19013 772 19013 1465 19014 1466 19014 764 19014 1465 19015 764 19015 772 19015 1478 19016 821 19016 1488 19016 1478 19017 733 19017 821 19017 1479 19018 1480 19018 728 19018 1480 19019 1481 19019 729 19019 729 19020 1481 19020 1483 19020 822 19021 1483 19021 763 19021 1486 19022 1488 19022 819 19022 1486 19023 819 19023 760 19023 1498 19024 739 19024 756 19024 1498 19025 1499 19025 739 19025 739 19026 1499 19026 735 19026 1499 19027 1500 19027 740 19027 1499 19028 740 19028 735 19028 818 19029 820 19029 1503 19029 1503 19030 1505 19030 818 19030 1505 19031 1506 19031 755 19031 1505 19032 755 19032 769 19032 1519 19033 1521 19033 738 19033 738 19034 1523 19034 824 19034 738 19035 1521 19035 1523 19035 1523 19036 1525 19036 754 19036 1525 19037 751 19037 754 19037 751 19038 1526 19038 748 19038 1526 19039 1516 19039 748 19039 618 19040 297 19040 298 19040 300 19041 1750 19041 351 19041 2064 19042 342 19042 339 19042 2060 19043 330 19043 327 19043 1653 19044 1723 19044 1676 19044 1676 19045 1723 19045 779 19045 2049 19046 1718 19046 1696 19046 1660 19047 2050 19047 1661 19047 1661 19048 2050 19048 2051 19048 1714 19049 2051 19049 2053 19049 2055 19050 1713 19050 1700 19050 1664 19051 1665 19051 1550 19051 1550 19052 2057 19052 1664 19052 1664 19053 2057 19053 1666 19053 2058 19054 1546 19054 1666 19054 1666 19055 1546 19055 1709 19055 2018 19056 1708 19056 2068 19056 679 19057 614 19057 615 19057 618 19058 356 19058 2069 19058 2022 19059 241 19059 244 19059 314 19060 2041 19060 2039 19060 278 19061 279 19061 651 19061 651 19062 2040 19062 278 19062 278 19063 2040 19063 260 19063 2043 19064 313 19064 311 19064 655 19065 313 19065 2043 19065 2043 19066 310 19066 2042 19066 2064 19067 336 19067 2062 19067 280 19068 2044 19068 2029 19068 327 19069 326 19069 2060 19069 2060 19070 326 19070 2059 19070 305 19071 654 19071 306 19071 306 19072 654 19072 732 19072 657 19073 284 19073 1986 19073 283 19074 284 19074 657 19074 305 19075 657 19075 654 19075 2037 19076 1681 19076 1682 19076 1720 19077 1719 19077 2046 19077 2046 19078 1719 19078 2045 19078 1684 19079 1729 19079 766 19079 1690 19080 1735 19080 768 19080 1574 19081 1642 19081 758 19081 1700 19082 1701 19082 2055 19082 2055 19083 1701 19083 2054 19083 439 19084 428 19084 1294 19084 1294 19085 428 19085 433 19085 2071 19086 517 19086 1276 19086 2073 19087 1277 19087 1278 19087 2074 19088 1278 19088 1284 19088 520 19089 1268 19089 1269 19089 519 19090 1269 19090 1275 19090 519 19091 520 19091 1269 19091 520 19092 521 19092 1268 19092 522 19093 523 19093 1285 19093 506 19094 1206 19094 1159 19094 1153 19095 1210 19095 490 19095 1141 19096 1214 19096 1137 19096 1135 19097 1137 19097 1230 19097 1119 19098 471 19098 1197 19098 1159 19099 1205 19099 1157 19099 1157 19100 1210 19100 1155 19100 1147 19101 1213 19101 1145 19101 1143 19102 1214 19102 1141 19102 1131 19103 1133 19103 1129 19103 1123 19104 471 19104 1121 19104 1167 19105 1200 19105 1165 19105 503 19106 1165 19106 500 19106 1089 19107 1228 19107 1229 19107 2075 19108 1093 19108 2074 19108 1089 19109 1229 19109 1091 19109 2074 19110 1231 19110 1233 19110 2072 19111 1233 19111 1228 19111 2076 19112 2077 19112 2078 19112 2078 19113 2077 19113 2079 19113 2082 19114 2081 19114 2083 19114 2083 53 2084 53 2082 53 2082 53 2084 53 2085 53 2083 19115 2081 19115 2084 19115 2076 19116 2078 19116 2087 19116 2087 19117 2078 19117 2088 19117 2089 19118 2090 19118 2079 19118 2094 19119 2095 19119 2096 19119 2098 19120 2099 19120 2095 19120 2099 19121 2101 19121 2102 19121 2098 19122 2095 19122 2101 19122 2108 19123 2105 19123 2104 19123 2110 19124 2111 19124 2104 19124 2104 19125 2111 19125 2109 19125 2104 19126 2103 19126 2110 19126 2110 19127 2103 19127 2112 19127 2116 19128 2106 19128 2107 19128 2112 19129 2103 19129 2117 19129 2121 19130 2122 19130 2123 19130 2127 19131 2128 19131 2126 19131 2115 19132 2118 19132 2113 19132 2131 19133 2130 19133 2132 19133 2131 19134 2133 19134 2118 19134 2134 19135 2130 19135 2135 19135 2138 19136 2137 19136 2134 19136 2142 19137 2122 19137 2143 19137 2143 19138 2144 19138 2142 19138 2145 19139 2122 19139 2121 19139 2148 19140 2121 19140 2124 19140 2124 19141 2125 19141 2126 19141 2150 19142 2126 19142 2151 19142 2126 19143 2128 19143 2152 19143 2151 19144 2126 19144 2152 19144 2122 19145 2142 19145 2140 19145 2140 19146 2142 19146 2153 19146 2135 19147 2139 19147 2155 19147 2135 19148 2155 19148 2136 19148 2130 19149 2156 19149 2132 19149 2115 19150 2114 19150 2157 19150 2162 53 2157 53 2161 53 2162 53 2163 53 2157 53 2164 19151 2162 19151 2165 19151 2165 19152 2132 19152 2156 19152 2114 19153 2166 19153 2159 19153 2166 19154 2114 19154 2113 19154 2160 19155 2168 19155 2167 19155 2133 19156 2131 19156 2168 19156 2172 53 2171 53 2173 53 2177 19157 2176 19157 2138 19157 2170 19158 2176 19158 2177 19158 2177 19159 2138 19159 2134 19159 2174 19160 2136 19160 2155 19160 2180 53 2157 53 2179 53 2180 53 2181 53 2157 53 2182 19161 2180 19161 2183 19161 2179 19162 2178 19162 2185 19162 2179 19163 2185 19163 2186 19163 2184 19164 2154 19164 2153 19164 2192 53 2193 53 2187 53 2193 19165 2192 19165 2194 19165 2196 19166 2195 19166 2147 19166 2196 19167 2147 19167 2145 19167 2189 19168 2190 19168 2191 19168 2191 19169 2144 19169 2143 19169 2193 53 2197 53 2187 53 2200 19170 2199 19170 2201 19170 2198 19171 2197 19171 2203 19171 2198 19172 2203 19172 2204 19172 2187 19173 2206 19173 2207 19173 2208 19174 2209 19174 2187 19174 2208 19175 2210 19175 2209 19175 2207 53 2211 53 2212 53 2215 19176 2216 19176 2217 19176 2215 19177 2218 19177 2216 19177 2219 19178 2220 19178 2217 19178 2221 19179 2220 19179 2219 19179 2223 19180 2224 19180 2225 19180 2228 19181 2223 19181 2225 19181 2229 19182 2228 19182 2225 19182 2233 19183 2229 19183 2234 19183 2236 19184 2237 19184 2238 19184 2236 19185 2238 19185 2239 19185 2239 19186 2240 19186 2236 19186 2239 19187 2241 19187 2242 19187 2239 19188 2242 19188 2240 19188 2244 19189 2245 19189 2241 19189 2244 19190 2246 19190 2245 19190 2244 19191 2238 19191 2247 19191 2247 19192 2238 19192 2237 19192 2248 19193 2247 19193 2250 19193 2251 19194 2236 19194 2252 19194 2238 19195 2244 19195 2239 19195 2244 19196 2241 19196 2239 19196 2256 19197 2255 19197 2254 19197 2259 19198 2256 19198 2260 19198 2258 19199 2261 19199 2259 19199 2256 19200 2254 19200 2260 19200 2265 19201 2266 19201 2267 19201 2268 19202 2269 19202 2270 19202 2271 19203 2268 19203 2270 19203 2272 19204 2268 19204 2271 19204 2274 19205 2266 19205 2265 19205 2275 19206 2274 19206 2265 19206 2278 19207 2279 19207 2280 19207 2278 19208 2281 19208 2279 19208 2284 19209 2285 19209 2286 19209 2286 19210 2283 19210 2284 19210 2284 19211 2282 19211 2281 19211 2284 19212 2281 19212 2287 19212 2288 19213 2287 19213 2289 19213 2291 19214 2281 19214 2278 19214 2292 19215 2291 19215 2278 19215 2292 19216 2278 19216 2280 19216 2279 19217 2282 19217 2283 19217 2293 19218 2294 19218 2295 19218 2294 19219 2293 19219 2298 19219 2300 19220 2269 19220 2273 19220 2301 19221 2300 19221 2273 19221 2301 19222 2273 19222 2274 19222 2304 19223 2305 19223 2306 19223 2286 19224 2307 19224 2310 19224 2310 19225 2283 19225 2286 19225 2305 19226 2311 19226 2302 19226 2311 19227 2305 19227 2304 19227 2314 19228 2295 19228 2115 19228 2115 19229 2294 19229 2119 19229 2315 19230 2316 19230 2317 19230 2318 19231 2317 19231 2322 19231 2323 19232 2324 19232 2325 19232 2326 19233 2327 19233 2328 19233 2335 19234 2336 19234 2337 19234 2348 19235 2349 19235 2350 19235 2351 19236 2350 19236 2352 19236 2351 19237 2352 19237 2345 19237 2353 19238 2357 19238 2354 19238 2354 19239 2357 19239 2358 19239 2358 19240 2357 19240 2359 19240 2359 19241 2362 19241 2361 19241 2362 19242 2363 19242 2361 19242 2360 19243 2361 19243 2365 19243 2355 19244 2366 19244 2356 19244 2355 19245 2367 19245 2366 19245 2371 587 2355 587 2372 587 2372 19246 2355 19246 2373 19246 2373 19247 2355 19247 2354 19247 2373 19248 2354 19248 2374 19248 2375 19249 2358 19249 2360 19249 2378 19250 2379 19250 2380 19250 2379 19251 2381 19251 2382 19251 2379 19252 2378 19252 2381 19252 2383 19253 2381 19253 2384 19253 2385 19254 2386 19254 2387 19254 2389 53 2387 53 2390 53 2387 19255 2389 19255 2385 19255 2385 19256 2389 19256 2391 19256 2394 53 2393 53 2395 53 2394 53 2392 53 2393 53 2385 19257 2391 19257 2396 19257 2396 19258 2391 19258 2392 19258 2393 53 2397 53 2395 53 2395 19259 2397 19259 2398 19259 2401 19260 2400 19260 2402 19260 2403 19261 2401 19261 2402 19261 2398 19262 2397 19262 2399 19262 2399 19263 2400 19263 2405 19263 2404 53 2402 53 2406 53 2407 19264 2402 19264 2408 19264 2408 53 2402 53 2390 53 2390 53 2387 53 2408 53 2387 19265 2409 19265 2410 19265 2413 19266 2414 19266 2415 19266 2414 19267 2416 19267 2415 19267 2415 19268 2416 19268 2419 19268 2417 19269 2421 19269 2422 19269 2422 19270 2421 19270 2423 19270 2423 19271 2418 19271 2422 19271 2422 19272 2418 19272 2417 19272 2379 19273 2423 19273 2380 19273 2379 19274 2424 19274 2423 19274 2423 19275 2424 19275 2418 19275 2380 19276 2423 19276 2425 19276 2409 19277 2426 19277 2410 19277 2409 19278 2427 19278 2425 19278 2409 19279 2428 19279 2427 19279 2426 19280 2429 19280 2410 19280 2420 19281 2431 19281 2426 19281 2432 19282 2412 19282 2433 19282 2434 19283 2433 19283 2435 19283 2436 19284 2429 19284 2426 19284 2412 19285 2436 19285 2433 19285 2432 19286 2434 19286 2407 19286 2406 19287 2434 19287 2435 19287 2404 19288 2435 19288 2438 19288 2408 19289 2432 19289 2407 19289 2407 19290 2434 19290 2406 19290 2404 19291 2438 19291 2403 19291 2440 19292 2439 19292 2416 19292 2416 19293 2442 19293 2441 19293 2443 19294 2444 19294 2445 19294 2446 19295 2443 19295 2445 19295 2444 19296 2447 19296 2448 19296 2428 19297 2448 19297 2430 19297 2430 19298 2448 19298 2449 19298 2450 19299 2443 19299 2446 19299 2428 19300 2451 19300 2448 19300 2453 19301 2452 19301 2411 19301 2427 19302 2454 19302 2425 19302 2425 19303 2454 19303 2380 19303 2456 19304 2457 19304 2226 19304 2224 19305 2457 19305 2458 19305 2226 19306 2457 19306 2224 19306 2458 19307 2225 19307 2224 19307 2459 19308 2225 19308 2458 19308 2459 19309 2458 19309 2460 19309 2465 19310 2462 19310 2461 19310 2467 19311 2264 19311 2464 19311 2467 19312 2468 19312 2264 19312 2467 19313 2470 19313 2469 19313 2471 19314 2470 19314 2472 19314 2472 19315 2470 19315 2474 19315 2474 19316 2470 19316 2475 19316 2474 19317 2475 19317 2476 19317 2479 19318 2480 19318 2475 19318 2479 19319 2481 19319 2480 19319 2479 19320 2482 19320 2481 19320 2479 19321 2483 19321 2482 19321 2484 19322 2483 19322 2485 19322 2488 19323 2489 19323 2483 19323 2490 19324 2493 19324 2494 19324 2495 19325 2496 19325 2492 19325 2492 19326 2496 19326 2497 19326 2498 19327 2497 19327 2496 19327 2497 19328 2498 19328 2499 19328 2490 19329 2502 19329 2491 19329 2489 19330 2506 19330 2483 19330 2485 19331 2483 19331 2506 19331 2507 19332 2508 19332 2509 19332 2506 19333 2507 19333 2509 19333 2484 19334 2485 19334 2486 19334 2510 19335 2511 19335 2512 19335 2482 19336 2511 19336 2510 19336 2510 19337 2512 19337 2513 19337 2514 19338 2481 19338 2515 19338 2480 19339 2516 19339 2517 19339 2480 19340 2476 19340 2475 19340 2226 19341 2227 19341 2232 19341 2232 19342 2524 19342 2226 19342 2456 19343 2226 19343 2524 19343 2525 19344 2459 19344 2460 19344 2230 19345 2233 19345 2232 19345 2229 19346 2225 19346 2235 19346 2235 19347 2225 19347 2459 19347 2264 19348 2462 19348 2464 19348 2257 19349 2462 19349 2264 19349 2526 19350 2523 19350 2262 19350 2526 19351 2262 19351 2261 19351 2527 19352 2460 19352 2458 19352 2466 19353 2529 19353 2527 19353 2466 19354 2530 19354 2529 19354 2466 19355 2523 19355 2531 19355 2535 19356 2532 19356 2534 19356 2536 19357 2537 19357 2538 19357 2536 19358 2539 19358 2537 19358 2536 19359 2521 19359 2539 19359 2537 19360 2539 19360 2540 19360 2540 19361 2539 19361 2541 19361 2540 19362 2541 19362 2542 19362 2540 19363 2542 19363 2543 19363 2544 19364 2540 19364 2543 19364 2541 19365 2539 19365 2473 19365 2551 19366 2549 19366 2552 19366 2553 19367 2554 19367 2555 19367 2553 19368 2556 19368 2557 19368 2565 19369 2561 19369 2564 19369 2547 19370 2558 19370 2559 19370 2566 19371 2560 19371 2561 19371 2515 19372 2562 19372 2514 19372 2567 19373 2568 19373 2562 19373 2567 19374 2569 19374 2568 19374 2567 19375 2570 19375 2569 19375 2569 19376 2570 19376 2571 19376 2571 19377 2570 19377 2572 19377 2571 19378 2572 19378 2573 19378 2572 19379 2570 19379 2575 19379 2576 19380 2508 19380 2577 19380 2576 19381 2577 19381 2578 19381 2508 19382 2575 19382 2509 19382 2577 19383 2508 19383 2580 19383 2587 19384 2583 19384 2586 19384 2577 19385 2580 19385 2581 19385 2582 19386 2504 19386 2503 19386 2588 19387 2582 19387 2583 19387 2589 19388 2590 19388 2584 19388 2589 19389 2591 19389 2590 19389 2589 19390 2592 19390 2591 19390 2591 19391 2592 19391 2593 19391 2595 19392 2594 19392 2596 19392 2598 19393 2599 19393 2597 19393 2602 19394 2601 19394 2603 19394 2602 19395 2603 19395 2604 19395 2598 19396 2605 19396 2600 19396 2601 19397 2109 19397 2606 19397 2603 19398 2601 19398 2607 19398 2610 19399 2612 19399 2611 19399 2617 19400 2607 19400 2608 19400 2609 19401 2618 19401 2619 19401 2612 19402 2610 19402 2620 19402 2620 19403 2610 19403 2621 19403 2621 19404 2624 19404 2625 19404 2627 19405 2628 19405 2629 19405 2631 19406 2630 19406 2632 19406 2633 19407 2632 19407 2568 19407 2568 19408 2569 19408 2633 19408 2637 19409 2636 19409 2638 19409 2565 19410 2637 19410 2638 19410 2565 19411 2564 19411 2637 19411 2554 19412 2552 19412 2643 19412 2647 19413 2642 19413 2648 19413 2649 19414 2647 19414 2648 19414 2649 19415 2650 19415 2647 19415 2643 19416 2651 19416 2652 19416 2551 19417 2554 19417 2553 19417 2655 19418 2555 19418 2656 19418 2657 19419 2656 19419 2525 19419 2660 19420 2525 19420 2658 19420 2661 19421 2655 19421 2662 19421 2538 19422 2537 19422 2663 19422 2658 19423 2665 19423 2660 19423 2660 19424 2657 19424 2525 19424 2546 19425 2542 19425 2545 19425 2646 19426 2636 19426 2641 19426 2667 19427 2620 19427 2623 19427 2574 19428 2573 19428 2667 19428 2668 19429 2617 19429 2669 19429 2670 19430 2671 19430 2581 19430 2582 19431 2588 19431 2581 19431 2579 19432 2578 19432 2672 19432 2673 19433 2672 19433 2611 19433 2611 19434 2612 19434 2673 19434 2611 19435 2608 19435 2609 19435 2587 19436 2586 19436 2674 19436 2604 19437 2674 19437 2602 19437 2602 19438 2599 19438 2601 19438 2670 19439 2668 19439 2671 19439 2617 19440 2603 19440 2607 19440 2623 19441 2574 19441 2667 19441 2552 19442 2642 19442 2643 19442 2527 19443 2529 19443 2528 19443 2678 19444 2679 19444 2680 19444 2678 19445 2681 19445 2682 19445 2683 19446 2678 19446 2682 19446 2684 19447 2685 19447 2681 19447 2688 19448 2677 19448 2687 19448 2687 19449 2677 19449 2689 19449 2693 19450 2694 19450 2695 19450 2695 19451 2694 19451 2696 19451 2699 19452 2698 19452 2700 19452 2703 19453 2702 19453 2704 19453 2707 19454 2706 19454 2708 19454 2709 19455 2710 19455 2711 19455 2715 19456 2714 19456 2716 19456 2717 19457 2718 19457 2719 19457 2721 19458 2722 19458 2723 19458 2723 19459 2722 19459 2724 19459 2729 19460 2730 19460 2731 19460 2731 19461 2730 19461 2732 19461 2733 19462 2734 19462 2735 19462 2735 19463 2734 19463 2736 19463 2737 19464 2738 19464 2739 19464 2741 19465 2742 19465 2454 19465 2743 19466 2744 19466 2745 19466 2745 19467 2744 19467 2746 19467 2751 19468 2752 19468 2753 19468 2755 19469 2756 19469 2757 19469 2757 19470 2756 19470 2758 19470 2761 19471 2760 19471 2762 19471 2763 19472 2764 19472 2765 19472 2765 19473 2764 19473 2766 19473 2767 19474 2768 19474 2769 19474 2769 19475 2768 19475 2770 19475 2771 19476 2772 19476 2773 19476 2773 19477 2772 19477 2774 19477 2775 19478 2776 19478 2777 19478 2777 19479 2776 19479 2778 19479 2779 19480 2780 19480 2781 19480 2783 19481 2784 19481 2785 19481 2785 19482 2784 19482 2786 19482 2787 19483 2788 19483 2090 19483 2790 19484 2791 19484 2792 19484 2794 19485 2795 19485 2796 19485 2796 19486 2795 19486 2093 19486 2794 2960 2796 2960 2799 2960 2799 19487 2796 19487 2797 19487 2795 53 2799 53 2800 53 2795 19488 2800 19488 2093 19488 2801 19489 2790 19489 2802 19489 2738 19490 2081 19490 2080 19490 2080 19491 2085 19491 2803 19491 2076 53 2087 53 2077 53 2077 19492 2805 19492 2079 19492 2787 19493 2090 19493 2806 19493 2806 19494 2090 19494 2089 19494 2738 19495 2807 19495 2804 19495 2787 19496 2806 19496 2788 19496 2788 19497 2806 19497 2808 19497 2788 19498 2808 19498 2789 19498 2789 19499 2808 19499 2810 19499 2809 19500 2740 19500 2811 19500 2785 53 2789 53 2812 53 2812 19501 2789 19501 2810 19501 2811 19502 2734 19502 2813 19502 2814 19503 2785 19503 2812 19503 2733 19504 2815 19504 2734 19504 2734 19505 2815 19505 2813 19505 2783 53 2814 53 2784 53 2733 53 2817 53 2815 53 2786 19506 2816 19506 2818 19506 2735 19507 2736 19507 2817 19507 2817 19508 2736 19508 2819 19508 2820 19509 2786 19509 2818 19509 2736 19510 2730 19510 2819 19510 2779 53 2822 53 2780 53 2729 840 2825 840 2823 840 2780 19511 2824 19511 2782 19511 2732 19512 2726 19512 2827 19512 2827 19513 2726 19513 2829 19513 2775 19514 2777 19514 2830 19514 2727 53 2833 53 2725 53 2727 19515 2728 19515 2833 19515 2833 19516 2728 19516 2835 19516 2773 53 2778 53 2836 53 2771 19517 2773 19517 2838 19517 2721 2633 2839 2633 2722 2633 2722 19518 2839 19518 2837 19518 2721 820 2841 820 2839 820 2772 19519 2840 19519 2774 19519 2774 19520 2840 19520 2842 19520 2723 19521 2724 19521 2841 19521 2767 19522 2769 19522 2846 19522 2767 53 2846 53 2768 53 2768 19523 2846 19523 2848 19523 2719 2649 2849 2649 2717 2649 2717 53 2849 53 2847 53 2768 19524 2848 19524 2770 19524 2770 19525 2848 19525 2850 19525 2852 19526 2770 19526 2850 19526 2720 2646 2714 2646 2851 2646 2851 2647 2714 2647 2853 2647 2713 19527 2855 19527 2714 19527 2713 19528 2857 19528 2855 19528 2766 19529 2856 19529 2858 19529 2761 53 2766 53 2860 53 2860 19530 2766 19530 2858 19530 2709 19531 2863 19531 2710 19531 2710 19532 2863 19532 2861 19532 2760 53 2862 53 2864 53 2711 879 2865 879 2709 879 2760 19533 2864 19533 2762 19533 2762 19534 2864 19534 2866 19534 2711 19535 2712 19535 2865 19535 2868 19536 2762 19536 2866 19536 2706 19537 2871 19537 2869 19537 2756 53 2870 53 2872 53 2705 53 2873 53 2871 53 2707 19538 2708 19538 2873 19538 2873 19539 2708 19539 2875 19539 2753 53 2758 53 2876 53 2708 19540 2702 19540 2875 19540 2875 19541 2702 19541 2877 19541 2751 19542 2753 19542 2878 19542 2701 19543 2879 19543 2702 19543 2703 53 2881 53 2701 53 2701 53 2881 53 2879 53 2752 19544 2880 19544 2754 19544 2754 19545 2880 19545 2882 19545 2703 19546 2704 19546 2881 19546 2881 19547 2704 19547 2883 19547 2884 19548 2754 19548 2882 19548 2883 19549 2698 19549 2885 19549 2747 19550 2749 19550 2886 19550 2698 19551 2887 19551 2885 19551 2748 17677 2886 17677 2888 17677 2748 19552 2888 19552 2750 19552 2750 19553 2888 19553 2890 19553 2889 19554 2700 19554 2891 19554 2892 19555 2750 19555 2890 19555 2700 19556 2694 19556 2891 19556 2743 19557 2745 19557 2894 19557 2894 19558 2745 19558 2892 19558 2694 19559 2895 19559 2893 19559 2695 879 2897 879 2693 879 2693 53 2897 53 2895 53 2380 19560 2898 19560 2381 19560 2692 19561 2453 19561 2899 19561 2899 19562 2453 19562 2411 19562 2744 19563 2896 19563 2746 19563 2746 19564 2896 19564 2901 19564 2742 19565 2741 19565 2898 19565 2741 19566 2746 19566 2903 19566 2696 19567 2691 19567 2902 19567 2902 19568 2691 19568 2904 19568 2362 19569 2906 19569 2363 19569 2363 19570 2906 19570 2792 19570 2790 19571 2906 19571 2738 19571 2738 19572 2906 19572 2740 19572 2730 19573 2906 19573 2732 19573 2722 19574 2728 19574 2445 19574 2445 19575 2451 19575 2694 19575 2702 19576 2445 19576 2704 19576 2445 19577 2710 19577 2716 19577 2714 19578 2445 19578 2716 19578 2714 2697 2720 2697 2445 2697 2452 19579 2691 19579 2451 19579 2451 19580 2691 19580 2696 19580 2093 19581 2908 19581 2796 19581 2093 19582 2090 19582 2908 19582 2782 19583 2777 19583 2908 19583 2446 19584 2778 19584 2773 19584 2446 19585 2769 19585 2770 19585 2446 19586 2766 19586 2761 19586 2762 19587 2446 19587 2761 19587 2762 19588 2757 19588 2446 19588 2750 19589 2745 19589 2446 19589 2450 19590 2746 19590 2741 19590 2364 19591 2363 19591 2909 19591 2909 19592 2363 19592 2910 19592 2368 19593 2911 19593 2798 19593 2361 19594 2364 19594 2311 19594 2311 19595 2364 19595 2302 19595 2678 19596 2683 19596 2679 19596 2679 19597 2683 19597 2912 19597 2912 19598 2913 19598 2679 19598 2913 19599 2914 19599 2313 19599 2297 19600 2915 19600 2916 19600 2917 19601 2916 19601 2918 19601 2297 19602 2916 19602 2917 19602 2918 19603 2919 19603 2920 19603 2920 19604 2919 19604 2921 19604 2922 19605 2331 19605 2324 19605 2920 19606 2921 19606 2923 19606 2327 19607 2926 19607 2925 19607 2926 19608 2327 19608 2320 19608 2926 19609 2320 19609 2927 19609 2927 19610 2928 19610 2926 19610 2322 19611 2929 19611 2928 19611 2933 19612 2932 19612 2934 19612 2937 19613 2939 19613 2938 19613 2938 19614 2939 19614 2940 19614 2942 19615 2944 19615 2943 19615 2942 19616 2945 19616 2944 19616 2942 19617 2686 19617 2945 19617 2933 19618 2934 19618 2685 19618 2946 19619 2944 19619 2947 19619 2948 19620 2947 19620 2949 19620 2952 19621 2951 19621 2336 19621 2334 19622 2344 19622 2955 19622 2955 19623 2344 19623 2956 19623 2343 19624 2957 19624 2956 19624 2340 19625 2957 19625 2343 19625 2347 19626 2961 19626 2960 19626 2963 19627 2962 19627 2964 19627 2948 19628 2949 19628 2950 19628 2950 19629 2951 19629 2952 19629 2963 19630 2304 19630 2962 19630 2913 19631 2313 19631 2367 19631 2304 19632 2306 19632 2960 19632 2959 19633 2306 19633 2312 19633 2957 19634 2958 19634 2312 19634 2960 19635 2306 19635 2959 19635 2959 19636 2312 19636 2958 19636 2966 19637 2917 19637 2918 19637 2297 19638 2917 19638 2966 19638 2967 19639 2970 19639 2968 19639 2967 19640 2971 19640 2970 19640 2970 19641 2971 19641 2972 19641 2972 19642 2971 19642 2973 19642 2974 19643 2973 19643 2975 19643 2976 19644 2975 19644 2977 19644 2980 19645 2979 19645 2981 19645 2988 19646 2987 19646 2989 19646 2990 19647 2989 19647 2991 19647 2992 19648 2991 19648 2993 19648 2998 19649 2997 19649 2999 19649 3004 19650 3003 19650 3005 19650 3008 19651 3007 19651 3009 19651 2906 19652 3010 19652 3011 19652 2972 19653 2973 19653 2974 19653 2974 19654 2975 19654 2976 19654 2978 19655 2979 19655 2980 19655 2980 19656 2981 19656 2982 19656 2984 19657 2985 19657 2986 19657 2988 19658 2989 19658 2990 19658 2990 19659 2991 19659 2992 19659 2992 19660 2993 19660 2994 19660 2996 19661 2997 19661 2998 19661 2998 19662 2999 19662 3000 19662 3002 19663 3003 19663 3004 19663 3004 19664 3005 19664 3006 19664 3008 19665 3009 19665 2362 19665 3011 19666 3012 19666 2907 19666 2907 19667 3012 19667 2908 19667 2356 19668 2370 19668 3014 19668 3013 19669 3015 19669 3014 19669 3014 19670 3015 19670 3016 19670 3016 19671 3015 19671 3017 19671 3018 19672 3017 19672 3019 19672 3020 19673 3019 19673 3021 19673 3022 19674 3021 19674 3023 19674 3024 19675 3023 19675 2969 19675 2968 19676 3024 19676 2969 19676 3018 19677 3019 19677 3020 19677 3022 19678 3023 19678 3024 19678 3027 19679 2683 19679 2682 19679 3025 19680 3027 19680 2682 19680 2945 19681 2689 19681 3028 19681 2679 19682 2685 19682 2680 19682 3034 19683 3033 19683 3035 19683 2321 19684 3032 19684 2319 19684 2321 19685 2315 19685 3032 19685 3032 19686 2315 19686 3033 19686 2328 19687 2319 19687 3032 19687 3037 19688 3038 19688 3036 19688 3037 19689 3036 19689 3039 19689 3035 19690 3039 19690 3036 19690 2315 19691 3040 19691 3033 19691 3041 19692 3042 19692 3043 19692 3042 19693 3041 19693 3044 19693 3039 19694 3049 19694 3038 19694 3036 19695 3050 19695 3034 19695 3046 19696 3039 19696 3035 19696 3035 19697 3048 19697 3046 19697 2332 19698 3053 19698 3054 19698 2337 19699 3055 19699 3056 19699 3054 19700 3055 19700 2337 19700 3057 19701 3058 19701 3059 19701 3057 19702 3061 19702 3062 19702 2335 19703 3056 19703 3068 19703 3056 19704 3070 19704 3071 19704 3071 19705 3070 19705 3074 19705 3070 19706 3055 19706 3075 19706 3075 19707 3055 19707 3069 19707 3074 19708 3070 19708 3059 19708 3060 19709 3075 19709 2351 19709 3075 19710 3069 19710 2351 19710 3055 19711 3070 19711 3056 19711 3073 19712 3072 19712 3056 19712 3076 19713 3077 19713 3078 19713 3079 19714 3077 19714 3080 19714 3081 19715 3082 19715 3083 19715 3083 19716 3076 19716 3078 19716 2329 19717 3031 19717 2330 19717 2919 19718 3034 19718 3050 19718 2331 19719 2921 19719 2329 19719 2329 19720 2921 19720 3051 19720 3051 19721 2921 19721 3050 19721 3084 19722 3031 19722 3034 19722 2919 19723 3084 19723 3034 19723 2330 19724 3031 19724 3084 19724 2324 19725 2323 19725 2328 19725 2326 19726 3032 19726 3030 19726 2328 19727 3032 19727 2326 19727 2332 19728 3054 19728 2333 19728 2332 19729 2953 19729 3064 19729 3066 19730 3064 19730 2953 19730 3085 19731 3054 19731 2337 19731 2336 19732 3085 19732 2337 19732 2338 19733 2340 19733 2342 19733 2344 19734 3052 19734 2341 19734 2347 19735 3086 19735 2345 19735 2347 19736 2960 19736 3086 19736 3086 19737 3061 19737 3057 19737 2348 19738 3061 19738 2349 19738 2319 19739 2927 19739 2320 19739 2322 19740 2927 19740 3087 19740 2927 19741 2319 19741 3087 19741 2315 19742 2321 19742 2316 19742 2338 19743 3061 19743 2348 19743 2345 19744 3086 19744 3057 19744 2335 19745 3068 19745 3066 19745 3066 19746 3068 19746 3067 19746 2352 19747 2962 19747 2961 19747 2346 19748 2352 19748 2961 19748 2961 19749 2347 19749 2346 19749 3089 19750 2352 19750 2350 19750 2350 19751 3085 19751 3089 19751 2350 19752 2339 19752 3085 19752 2339 19753 2349 19753 2958 19753 2340 19754 2339 19754 2958 19754 3052 19755 2334 19755 2333 19755 2334 19756 3052 19756 2344 19756 3085 19757 3052 19757 2333 19757 2949 19758 3090 19758 2951 19758 2328 19759 3092 19759 2319 19759 3092 19760 2328 19760 2323 19760 3087 19761 3093 19761 2318 19761 3045 19762 3094 19762 3093 19762 3093 19763 3094 19763 2318 19763 2934 19764 2317 19764 3095 19764 2934 19765 2932 19765 2317 19765 2930 19766 2322 19766 2317 19766 3095 19767 2317 19767 3096 19767 2316 19768 3084 19768 3096 19768 2316 19769 2326 19769 3084 19769 3030 19770 2331 19770 2330 19770 2331 19771 3030 19771 2324 19771 3084 19772 3030 19772 2330 19772 3096 19773 3084 19773 3097 19773 3097 19774 2919 19774 2918 19774 2916 19775 3097 19775 2918 19775 3098 19776 2915 19776 2914 19776 3097 19777 3100 19777 3096 19777 3096 19778 3100 19778 3101 19778 3095 19779 3101 19779 3102 19779 2916 19780 3104 19780 3099 19780 3095 19781 3102 19781 3098 19781 3105 19782 3099 19782 3106 19782 3105 19783 3100 19783 3099 19783 3102 19784 3107 19784 3108 19784 3100 19785 3105 19785 3101 19785 3101 19786 3107 19786 3102 19786 3104 19787 3109 19787 3106 19787 3088 19788 3114 19788 3110 19788 3091 19789 3088 19789 3110 19789 3091 19790 3111 19790 2947 19790 2947 19791 3112 19791 2949 19791 3090 19792 3113 19792 3089 19792 3089 19793 3114 19793 3088 19793 3115 19794 3110 19794 3116 19794 3115 19795 3111 19795 3110 19795 3111 19796 3115 19796 3112 19796 3113 19797 3119 19797 3114 19797 3045 19798 3041 19798 3094 19798 3094 19799 2315 19799 2318 19799 2323 19800 2325 19800 3051 19800 3065 19801 3067 19801 3072 19801 2353 19802 3122 19802 3121 19802 2353 19803 3123 19803 3122 19803 3049 19804 3124 19804 2353 19804 3125 19805 3049 19805 3039 19805 3047 19806 3126 19806 3039 19806 3126 19807 3043 19807 3127 19807 3127 19808 3043 19808 3128 19808 3129 19809 3044 19809 3130 19809 3130 19810 3044 19810 3076 19810 3076 19811 3082 19811 3130 19811 3130 19812 3082 19812 3131 19812 3132 19813 3082 19813 2986 19813 3132 19814 2986 19814 3133 19814 3080 19815 2986 19815 3082 19815 3135 19816 3072 19816 3074 19816 3136 19817 3074 19817 3137 19817 3131 19818 3136 19818 3137 19818 3136 19819 3131 19819 3082 19819 3065 19820 3072 19820 2986 19820 3134 19821 3072 19821 3135 19821 3138 19822 3074 19822 2357 19822 3139 19823 3138 19823 2357 19823 3121 19824 3139 19824 2357 19824 3132 19825 3136 19825 3082 19825 3123 19826 3109 19826 3108 19826 3127 19827 3107 19827 3105 19827 3126 19828 3105 19828 3106 19828 3124 19829 3109 19829 3123 19829 3127 19830 3105 19830 3126 19830 3116 19831 3119 19831 3136 19831 3134 19832 3119 19832 3118 19832 3133 19833 3117 19833 3115 19833 3135 19834 3119 19834 3134 19834 3133 19835 3115 19835 3132 19835 2685 19836 2679 19836 2933 19836 2933 19837 2679 19837 2913 19837 2913 19838 2371 19838 2933 19838 2933 19839 2371 19839 2936 19839 2377 19840 2964 19840 2942 19840 2941 19841 2377 19841 2942 19841 2676 19842 2686 19842 2942 19842 2964 19843 2676 19843 2942 19843 2363 19512 2792 19512 2910 19512 2910 19844 2792 19844 3140 19844 2792 19845 3141 19845 3140 19845 2883 19846 2215 19846 2877 19846 2217 19847 2829 19847 2835 19847 2217 19848 2827 19848 2829 19848 2217 19849 2821 19849 2827 19849 2217 19850 2811 19850 2813 19850 2217 19851 2804 19851 2811 19851 2217 19852 2086 19852 2804 19852 2217 19853 2803 19853 2086 19853 2217 19854 2910 19854 3140 19854 2217 19855 2220 19855 2910 19855 2215 19856 2845 19856 2851 19856 2853 19857 2215 19857 2851 19857 2215 19858 2861 19858 2867 19858 2875 19859 2877 19859 2215 19859 2898 19860 3143 19860 2381 19860 2293 19861 2295 19861 2911 19861 2868 19862 2872 19862 2870 19862 2862 19863 2860 19863 2864 19863 2852 19864 2856 19864 2854 19864 2848 19865 2844 19865 2850 19865 2842 19866 2840 19866 2836 19866 2832 19867 2828 19867 2834 19867 2820 19868 2824 19868 2822 19868 2814 19869 2812 19869 2816 19869 2810 19870 2808 19870 2089 19870 2805 19871 2088 19871 2091 19871 2092 19872 2800 19872 2797 19872 2797 19873 2800 19873 2799 19873 2904 19874 2899 19874 3142 19874 2910 19875 2303 19875 2909 19875 2910 19876 2220 19876 2303 19876 2879 19877 2881 19877 2877 19877 2861 19878 2865 19878 2867 19878 2847 19879 2849 19879 2845 19879 2845 19880 2849 19880 2851 19880 2843 19881 2837 19881 2841 19881 2841 19882 2837 19882 2839 19882 2829 19883 2833 19883 2835 19883 2827 19884 2821 19884 2825 19884 2803 19885 2084 19885 2086 19885 2802 19886 3140 19886 2801 19886 2895 19887 2897 19887 2893 19887 2893 19888 2897 19888 2902 19888 2891 19889 2885 19889 2889 19889 2889 19890 2885 19890 2887 19890 2793 19891 2801 19891 3141 19891 3145 19892 2308 19892 2309 19892 2288 19893 3147 19893 3146 19893 3147 19894 3148 19894 3149 19894 2288 19895 2289 19895 3148 19895 3149 19896 3148 19896 3150 19896 3151 19897 3147 19897 3149 19897 3149 19898 3152 19898 3151 19898 3153 19899 2291 19899 3154 19899 3154 19900 3155 19900 3156 19900 3157 19901 3158 19901 3159 19901 3153 19902 3154 19902 3156 19902 2499 19903 2498 19903 2301 19903 2498 19904 2496 19904 2300 19904 2300 19905 2301 19905 2498 19905 3161 19906 3162 19906 3163 19906 3163 19907 3162 19907 3164 19907 3167 19908 3164 19908 3166 19908 3164 19909 3172 19909 3165 19909 3165 19910 3172 19910 3171 19910 3172 19911 3167 19911 3174 19911 3168 19912 3177 19912 3176 19912 3176 19913 3177 19913 3178 19913 3177 19914 3166 19914 3179 19914 3177 19915 3179 19915 3178 19915 3180 19916 3161 19916 3170 19916 3181 19917 3182 19917 3183 19917 3182 19918 3181 19918 3184 19918 3182 19919 3184 19919 3185 19919 3181 19920 3187 19920 3184 19920 3181 19921 3183 19921 3188 19921 3188 19922 3190 19922 3191 19922 3184 19923 3187 19923 3186 19923 3186 19924 3187 19924 3192 19924 3191 19925 3189 19925 3188 19925 3191 19926 3194 19926 3189 19926 3189 19927 3194 19927 3193 19927 3195 19928 3196 19928 3197 19928 3196 19929 3190 19929 3183 19929 3199 19930 3200 19930 3201 19930 3199 19931 3201 19931 3203 19931 3204 19932 3203 19932 3201 19932 3200 19933 3199 19933 3206 19933 3206 19934 3199 19934 3207 19934 3208 19935 3209 19935 3210 19935 3209 19936 3205 19936 3211 19936 3211 19937 3212 19937 3209 19937 3209 19938 3212 19938 3210 19938 3211 19939 3213 19939 3212 19939 3213 19940 3215 19940 3214 19940 3214 19941 3215 19941 3216 19941 3215 19942 3201 19942 3216 19942 3218 19943 3219 19943 3220 19943 3220 19944 3224 19944 3221 19944 3225 19945 3221 19945 3224 19945 3219 19946 3218 19946 3227 19946 3227 19947 3218 19947 3228 19947 3218 19948 3223 19948 3228 19948 3229 19949 3223 19949 3222 19949 3226 19950 3231 19950 3230 19950 3230 19951 3231 19951 3232 19951 3231 19952 3233 19952 3232 19952 3233 19953 3224 19953 3234 19953 3234 19954 3224 19954 3235 19954 3224 19955 3237 19955 3235 19955 3224 19956 3220 19956 3236 19956 3220 19957 3219 19957 3236 19957 3238 19958 3239 19958 3240 19958 3241 19959 3238 19959 3240 19959 3240 19960 3244 19960 3241 19960 3245 19961 3241 19961 3244 19961 3245 19962 3242 19962 3241 19962 3239 19963 3238 19963 3247 19963 3247 19964 3238 19964 3248 19964 3238 19965 3243 19965 3248 19965 3248 19966 3243 19966 3249 19966 3249 19967 3243 19967 3242 19967 3246 19968 3245 19968 3251 19968 3246 19969 3251 19969 3250 19969 3245 19970 3253 19970 3251 19970 3252 19971 3253 19971 3254 19971 3253 19972 3245 19972 3244 19972 3253 19973 3244 19973 3254 19973 3254 19974 3244 19974 3255 19974 3256 19975 3239 19975 3257 19975 3261 19976 3258 19976 3260 19976 3262 19977 3258 19977 3261 19977 3258 19978 3262 19978 3263 19978 3262 19979 3265 19979 3266 19979 3267 19980 3258 19980 3268 19980 3269 19981 3263 19981 3262 19981 3270 19982 3271 19982 3272 19982 3265 19983 3273 19983 3271 19983 3271 19984 3273 19984 3272 19984 3272 19985 3273 19985 3274 19985 3273 19986 3265 19986 3264 19986 3273 19987 3264 19987 3274 19987 3276 19988 3277 19988 3264 19988 3264 19989 3277 19989 3275 19989 3264 19990 3260 19990 3276 19990 3278 19991 3279 19991 3280 19991 3282 19992 3278 19992 3281 19992 3285 19993 3281 19993 3284 19993 3285 19994 3282 19994 3281 19994 3279 19995 3278 19995 3287 19995 3287 19996 3278 19996 3288 19996 3288 19997 3283 19997 3289 19997 3289 19998 3283 19998 3282 19998 3286 19999 3290 19999 3282 19999 3286 20000 3291 20000 3290 20000 3291 20001 3293 20001 3292 20001 3298 20002 3299 20002 3300 20002 3302 20003 3298 20003 3301 20003 3298 20004 3302 20004 3303 20004 3300 20005 3304 20005 3301 20005 3302 20006 3305 20006 3306 20006 3299 20007 3298 20007 3307 20007 3307 20008 3298 20008 3308 20008 3308 20009 3303 20009 3309 20009 3306 20010 3305 20010 3311 20010 3305 20011 3313 20011 3311 20011 3313 20012 3304 20012 3314 20012 3300 20013 3299 20013 3316 20013 3316 20014 3299 20014 3317 20014 3317 20015 3299 20015 3307 20015 3318 20016 3322 20016 3323 20016 3322 20017 3325 20017 3326 20017 3319 20018 3318 20018 3327 20018 3318 20019 3323 20019 3328 20019 3328 20020 3323 20020 3329 20020 3326 20021 3331 20021 3330 20021 3325 20022 3333 20022 3331 20022 3332 20023 3333 20023 3334 20023 3333 20024 3325 20024 3324 20024 3334 20025 3324 20025 3335 20025 3336 20026 3337 20026 3324 20026 3320 20027 3319 20027 3336 20027 3338 20028 3339 20028 3340 20028 3341 20029 3338 20029 3340 20029 3340 20030 3344 20030 3341 20030 3345 20031 3341 20031 3344 20031 3346 20032 3350 20032 3342 20032 3342 20033 3350 20033 3349 20033 3346 20034 3345 20034 3351 20034 3346 20035 3351 20035 3350 20035 3350 20036 3351 20036 3352 20036 3351 20037 3353 20037 3352 20037 3354 20038 3344 20038 3355 20038 3356 20039 3357 20039 3344 20039 3340 20040 3339 20040 3356 20040 3357 20041 3339 20041 3347 20041 3358 20042 3359 20042 3360 20042 3363 20043 3364 20043 3362 20043 3358 20044 3361 20044 2595 20044 3367 20045 3361 20045 3364 20045 3367 20046 3364 20046 3369 20046 3367 20047 3370 20047 3368 20047 3363 20048 3371 20048 3364 20048 3369 20049 3371 20049 3370 20049 3370 20050 3371 20050 3372 20050 3371 20051 3363 20051 3373 20051 3371 20052 3373 20052 3372 20052 3373 20053 3363 20053 3360 20053 3373 20054 3360 20054 3374 20054 3374 20055 3360 20055 3375 20055 3359 20056 3365 20056 3360 20056 3360 20057 3365 20057 3375 20057 3377 20058 3376 20058 3157 20058 3380 20059 3376 20059 3379 20059 3378 20060 3382 20060 3379 20060 3381 20061 3383 20061 3386 20061 2605 20062 3388 20062 3382 20062 2291 20063 2292 20063 2600 20063 2291 20064 3153 20064 2290 20064 2289 20065 3153 20065 3150 20065 2292 20066 3391 20066 2600 20066 3392 20067 2457 20067 2456 20067 3393 20068 2456 20068 2524 20068 3395 20069 3393 20069 3394 20069 3394 20070 2234 20070 2659 20070 3396 20071 3395 20071 3397 20071 3393 20072 3395 20072 3398 20072 3398 20073 3395 20073 3399 20073 3399 20074 3400 20074 3398 20074 3400 20075 3403 20075 3398 20075 3398 20076 3403 20076 3404 20076 3406 20077 3403 20077 3407 20077 3410 20078 3409 20078 3408 20078 2639 20079 3410 20079 2640 20079 3412 20080 3408 20080 2645 20080 3412 20081 2645 20081 2644 20081 3411 20082 3413 20082 3409 20082 3415 20083 3414 20083 3416 20083 3417 20084 3415 20084 3416 20084 3417 20085 3418 20085 3415 20085 2628 20086 3413 20086 2629 20086 2624 20087 3416 20087 2625 20087 3419 20088 3422 20088 3423 20088 3424 20089 3419 20089 3423 20089 3424 20090 3425 20090 3419 20090 3427 20091 3426 20091 3424 20091 3422 20092 3428 20092 3423 20092 3422 20093 2616 20093 3428 20093 3428 20094 2616 20094 2615 20094 3146 20095 3425 20095 3145 20095 3425 20096 2117 20096 3144 20096 2310 20097 2117 20097 3391 20097 2116 20098 2600 20098 3391 20098 3392 20099 3429 20099 2457 20099 2457 20100 3429 20100 2458 20100 2277 20101 2271 20101 3430 20101 3160 20102 3430 20102 2270 20102 2593 20103 3384 20103 2591 20103 2592 20104 3157 20104 2593 20104 3157 20105 3155 20105 3432 20105 2594 20106 3387 20106 2596 20106 2594 20107 3385 20107 3387 20107 3439 20108 3437 20108 3440 20108 3445 20109 3444 20109 3446 20109 3447 20110 3446 20110 3448 20110 3449 20111 3448 20111 3450 20111 3150 20112 3451 20112 3452 20112 3434 20113 3152 20113 3435 20113 3149 20114 3150 20114 3452 20114 3150 20115 3153 20115 3451 20115 3158 20116 3431 20116 3450 20116 3449 20117 3454 20117 3448 20117 3447 20118 3455 20118 3446 20118 3455 20119 3456 20119 3446 20119 3445 20120 3458 20120 3444 20120 3458 20121 3443 20121 3444 20121 3441 20122 3439 20122 3440 20122 3439 20123 3461 20123 3437 20123 3462 20124 2948 20124 2950 20124 2946 20125 3462 20125 3464 20125 2938 20126 3465 20126 3466 20126 2938 20127 3466 20127 3467 20127 2931 20128 3467 20128 3468 20128 2926 20129 3469 20129 3470 20129 2924 20130 2925 20130 3456 20130 2946 20131 3464 20131 2943 20131 2943 20132 3465 20132 2940 20132 2940 20133 3465 20133 2938 20133 2938 20134 3467 20134 2935 20134 2931 20135 3468 20135 2929 20135 2928 20136 3469 20136 2926 20136 3472 20137 3445 20137 3471 20137 3458 20138 3472 20138 3473 20138 3473 20139 3443 20139 3458 20139 3474 20140 3460 20140 3459 20140 3460 20141 3474 20141 3475 20141 3441 20142 3476 20142 3477 20142 3478 20143 3461 20143 3439 20143 3480 20144 3481 20144 3438 20144 2954 20145 3433 20145 3463 20145 3457 20146 3471 20146 3445 20146 3461 20147 3479 20147 3438 20147 3436 20148 3463 20148 3433 20148 3463 20149 2950 20149 2952 20149 3454 20150 3482 20150 3447 20150 3023 20151 3446 20151 2969 20151 3023 20152 3021 20152 3448 20152 3448 20153 3021 20153 3019 20153 3450 20154 3017 20154 3015 20154 3450 20155 3015 20155 3013 20155 3159 20156 3012 20156 3011 20156 3156 20157 3159 20157 3011 20157 3448 20158 3017 20158 3450 20158 3011 20159 3010 20159 3156 20159 3451 6 3009 6 3007 6 3452 20160 3007 20160 3005 20160 3452 20161 3005 20161 3003 20161 3453 20162 3003 20162 3001 20162 3437 20163 2995 20163 2993 20163 3437 20164 2993 20164 2991 20164 3437 20165 2989 20165 2987 20165 3451 20166 3007 20166 3452 20166 3437 20167 2987 20167 3440 20167 2983 20168 2981 20168 3442 20168 3442 20169 2979 20169 2977 20169 3444 6 2977 6 2975 6 3446 20170 2971 20170 2967 20170 3446 20171 2967 20171 2969 20171 2220 20172 2221 20172 2302 20172 3419 20173 3483 20173 3484 20173 3409 20174 3485 20174 3486 20174 3404 20175 3486 20175 3487 20175 3398 20176 3487 20176 3488 20176 3393 20177 3488 20177 3489 20177 2456 20178 3489 20178 3490 20178 2456 20179 3393 20179 3489 20179 3409 20180 3486 20180 3404 20180 2312 20181 3151 20181 2955 20181 2966 20182 2495 20182 2298 20182 2966 20183 2922 20183 3491 20183 3491 20184 3447 20184 3482 20184 2119 20185 2495 20185 2492 20185 2120 20186 2492 20186 2488 20186 2135 20187 2483 20187 2479 20187 2140 20188 2479 20188 2475 20188 2123 20189 2470 20189 2467 20189 2119 20190 2492 20190 2120 20190 2130 20191 2483 20191 2135 20191 2140 20192 2475 20192 2122 20192 3482 20193 3160 20193 2495 20193 3492 20194 3482 20194 3454 20194 3160 20195 3492 20195 3431 20195 3483 20196 3493 20196 3484 20196 3490 20197 3489 20197 3494 20197 3495 20198 2219 20198 3496 20198 3500 20199 3484 20199 3499 20199 3503 20200 3504 20200 3485 20200 3485 20201 3504 20201 3505 20201 3507 20202 3505 20202 3506 20202 3507 20203 3508 20203 3505 20203 3484 20204 3502 20204 3485 20204 3505 20205 3508 20205 3486 20205 3486 20206 3508 20206 3509 20206 3486 20207 3509 20207 3510 20207 3486 20208 3512 20208 3487 20208 3516 20209 3487 20209 3515 20209 3516 20210 3517 20210 3488 20210 3517 20211 3519 20211 3488 20211 3488 20212 3519 20212 3489 20212 3489 20213 3519 20213 3520 20213 3521 20214 3522 20214 3490 20214 3490 20215 3522 20215 3523 20215 3486 20216 3485 20216 3505 20216 3483 20217 2222 20217 3493 20217 3508 20218 3526 20218 3509 20218 3533 20219 3532 20219 3503 20219 3501 20220 3536 20220 3537 20220 3536 20221 2613 20221 3537 20221 3536 20222 3500 20222 3538 20222 3499 20223 3498 20223 3541 20223 3541 20224 3498 20224 3542 20224 3545 20225 3546 20225 3427 20225 3496 20226 2216 20226 3547 20226 2218 20227 3550 20227 3549 20227 2218 20228 3551 20228 3550 20228 2218 20229 3552 20229 3551 20229 2218 53 3553 53 3552 53 2218 20230 3554 20230 3553 20230 2218 20231 3555 20231 3554 20231 2218 20232 3558 20232 3557 20232 2218 20233 3559 20233 3558 20233 3559 20234 3560 20234 3561 20234 3557 20235 3562 20235 3563 20235 3563 20236 3562 20236 3520 20236 3563 20237 3520 20237 3519 20237 3555 20238 3556 20238 3564 20238 3568 20239 3567 20239 3515 20239 3551 20240 3569 20240 3570 20240 3570 20241 3513 20241 3511 20241 3571 20242 3550 20242 3572 20242 3525 20243 3572 20243 3510 20243 3549 53 3550 53 3571 53 3574 20244 3575 20244 2216 20244 3576 20245 3574 20245 3577 20245 3531 20246 3577 20246 3504 20246 3527 20247 3573 20247 3548 20247 3578 20248 3527 20248 3508 20248 3576 20249 3577 20249 3531 20249 2216 20250 3579 20250 3580 20250 3581 20251 2216 20251 3580 20251 3582 20252 3581 20252 3583 20252 3585 20253 3584 20253 3533 20253 3533 20254 3503 20254 3585 20254 3580 20255 3584 20255 3585 20255 3582 20256 3583 20256 3537 20256 3537 20257 3502 20257 3501 20257 3582 20258 3586 20258 2216 20258 3589 20259 3588 20259 3590 20259 3590 20260 3544 20260 3589 20260 3497 20261 3590 20261 3498 20261 3587 20262 3586 20262 3591 20262 3499 20263 3540 20263 3500 20263 3592 20264 3540 20264 3499 20264 3546 20265 3495 20265 3496 20265 2155 20266 3594 20266 3593 20266 3594 20267 2139 20267 3595 20267 2139 20268 2185 20268 3595 20268 2141 20269 2154 20269 3596 20269 3601 20270 2147 20270 3602 20270 2205 20271 2477 20271 3604 20271 2146 20272 2149 20272 3605 20272 3605 20273 2149 20273 2472 20273 2148 20274 2124 20274 3606 20274 2214 20275 2520 20275 2124 20275 2299 20276 2496 20276 2495 20276 3609 20277 3610 20277 3611 20277 3613 20278 3612 20278 3614 20278 2384 20279 3616 20279 2383 20279 3611 20280 3612 20280 3613 20280 3613 20281 3614 20281 3615 20281 3615 20282 3616 20282 2384 20282 2152 20283 3615 20283 2209 20283 2127 20284 2464 20284 2129 20284 2129 20285 2464 20285 3617 20285 3609 20286 3618 20286 3610 20286 3619 20287 2396 20287 2392 20287 3620 20288 2392 20288 2394 20288 3621 20289 2394 20289 2395 20289 3622 20290 2395 20290 2398 20290 3619 20291 2392 20291 3620 20291 3620 20292 2394 20292 3621 20292 3621 20293 2395 20293 3622 20293 3623 20294 3524 20294 3622 20294 3622 20295 3524 20295 3523 20295 3621 20296 3523 20296 3522 20296 3560 20297 3619 20297 3620 20297 3621 20298 3522 20298 3620 20298 2385 20299 2396 20299 2388 20299 2900 20300 2411 20300 2388 20300 3619 20301 3560 20301 3142 20301 2416 20302 2414 20302 2442 20302 2442 20303 2414 20303 2413 20303 3625 20304 2379 20304 2382 20304 2382 20305 2383 20305 3626 20305 3614 20306 3612 20306 3627 20306 3628 20307 3629 20307 3610 20307 3629 53 3630 53 3631 53 3631 53 3632 53 2441 53 3633 20308 2441 20308 2442 20308 2413 20309 3633 20309 2442 20309 2413 20310 3634 20310 3633 20310 3634 20311 3624 20311 2424 20311 3634 53 2424 53 3635 53 3627 20312 3610 20312 3629 20312 3631 53 2441 53 3633 53 2424 20313 2379 20313 3635 20313 3635 20314 2379 20314 3625 20314 2187 20315 2209 20315 3143 20315 3636 20316 2187 20316 3143 20316 2209 20317 2384 20317 3143 20317 2380 20318 2381 20318 2378 20318 2187 20319 3636 20319 2157 20319 2892 20320 3636 20320 2901 20320 2874 20321 2868 20321 3636 20321 2876 20322 2874 20322 3636 20322 2850 20323 2844 20323 3636 20323 3636 20324 2844 20324 2842 20324 2834 20325 2828 20325 2314 20325 2826 20326 2820 20326 2314 20326 2818 20327 2812 20327 2314 20327 2820 20328 2818 20328 2314 20328 2810 20329 2089 20329 2314 20329 2812 20330 2810 20330 2314 20330 2089 20331 2091 20331 2314 20331 2798 20332 2295 20332 2314 20332 2903 20333 3636 20333 3143 20333 2890 20334 2888 20334 2884 20334 2884 20335 2888 20335 2886 20335 2313 20336 2293 20336 2366 20336 3432 20337 3390 20337 3377 20337 3157 20338 3432 20338 3377 20338 3463 20339 3637 20339 3638 20339 3463 20340 3638 20340 3462 20340 3641 20341 3465 20341 3464 20341 3641 20342 3642 20342 3465 20342 3466 20343 3642 20343 3643 20343 3643 20344 3644 20344 3467 20344 3646 20345 3647 20345 3469 20345 3469 20346 3647 20346 3648 20346 3470 20347 3648 20347 3649 20347 3470 20348 3469 20348 3648 20348 3467 20349 3645 20349 3468 20349 3472 20350 3652 20350 3653 20350 3472 20351 3471 20351 3652 20351 2925 20352 3650 20352 3651 20352 3472 20353 3653 20353 3473 20353 3654 20354 3473 20354 3653 20354 3655 20355 3656 20355 3474 20355 3474 20356 3656 20356 3475 20356 3656 20357 3657 20357 3475 20357 3659 20358 3660 20358 3661 20358 3662 20359 3663 20359 3664 20359 3665 20360 3663 20360 3660 20360 3660 20361 3666 20361 3665 20361 3664 20362 3663 20362 3665 20362 3668 20363 3660 20363 3663 20363 3672 20364 3673 20364 3674 20364 3672 20365 3674 20365 3675 20365 3675 20366 3671 20366 3670 20366 3678 20367 3673 20367 3672 20367 3671 20368 3674 20368 3679 20368 3667 20369 3674 20369 3678 20369 3680 20370 3682 20370 3683 20370 3685 20371 3684 20371 3686 20371 3686 20372 3684 20372 3687 20372 3689 20373 3690 20373 3681 20373 3680 20374 3689 20374 3681 20374 3688 20375 3683 20375 3691 20375 3691 20376 3683 20376 3681 20376 3637 20377 3692 20377 3638 20377 3694 20378 3640 20378 3639 20378 3696 20379 3641 20379 3686 20379 3665 20380 3696 20380 3688 20380 3665 20381 3689 20381 3697 20381 3665 20382 3697 20382 3664 20382 3698 20383 3680 20383 3695 20383 3689 20384 3698 20384 3697 20384 3680 20385 3698 20385 3689 20385 3697 20386 3658 20386 3664 20386 3664 20387 3658 20387 3662 20387 3662 20388 3657 20388 3671 20388 3643 20389 3667 20389 3644 20389 3666 20390 3643 20390 3642 20390 3665 20391 3666 20391 3642 20391 3657 20392 3656 20392 3671 20392 3671 20393 3656 20393 3677 20393 3677 20394 3656 20394 3699 20394 3653 20395 3648 20395 3647 20395 3648 20396 3652 20396 3649 20396 3470 20397 3651 20397 3650 20397 3470 20398 3649 20398 3651 20398 3656 20399 3655 20399 3699 20399 3676 20400 3654 20400 3646 20400 3672 20401 3676 20401 3646 20401 3676 20402 3672 20402 3675 20402 3645 20403 3644 20403 3678 20403 3641 20404 3640 20404 3685 20404 3661 20405 3668 20405 3662 20405 3688 20406 3696 20406 3686 20406 3667 20407 3671 20407 3679 20407 3692 20408 3480 20408 3693 20408 3693 20409 3480 20409 3479 20409 3694 20410 3479 20410 3478 20410 3695 20411 3478 20411 3698 20411 3698 20412 3478 20412 3477 20412 3698 20413 3477 20413 3697 20413 3697 20414 3477 20414 3476 20414 3392 20415 2456 20415 3700 20415 3701 20416 3392 20416 3700 20416 3701 20417 3702 20417 3392 20417 3392 20418 3702 20418 3429 20418 3703 20419 3704 20419 3705 20419 3706 20420 3707 20420 3708 20420 3708 6 3707 6 3709 6 3707 6 3714 6 3709 6 3709 6 3714 6 3715 6 3719 6 3718 6 3720 6 3722 20421 3723 20421 3721 20421 3722 6 3724 6 3723 6 3723 20422 3724 20422 3725 20422 3720 20423 3726 20423 3727 20423 3730 20424 3729 20424 3731 20424 3429 20425 3731 20425 2465 20425 3429 20426 3732 20426 3730 20426 3429 20427 3733 20427 3732 20427 3429 20428 3702 20428 3733 20428 3733 20429 3702 20429 3701 20429 3733 20430 3701 20430 3724 20430 3734 20431 3735 20431 3736 20431 3739 6 3735 6 3738 6 3739 6 3740 6 3735 6 3741 20432 2465 20432 3731 20432 3738 20433 3703 20433 3705 20433 3713 20434 3723 20434 3725 20434 3721 20435 3719 20435 3720 20435 3719 6 3717 6 3718 6 3734 6 3726 6 3718 6 3701 20436 3743 20436 3725 20436 3742 20437 3739 20437 2463 20437 2463 20438 3739 20438 3617 20438 2464 20439 2463 20439 3617 20439 3617 20440 3739 20440 3618 20440 3706 20441 3708 20441 2440 20441 3746 20442 3618 20442 3705 20442 3747 20443 3706 20443 2440 20443 3747 20444 3705 20444 3706 20444 3747 20445 3748 20445 3705 20445 3746 20446 3705 20446 3748 20446 3745 20447 2401 20447 2439 20447 3745 20448 2405 20448 2401 20448 3745 20449 3744 20449 2405 20449 2398 20450 3712 20450 3743 20450 3623 20451 2398 20451 3743 20451 3748 20452 3630 20452 3628 20452 3618 20453 3746 20453 3610 20453 3747 20454 3630 20454 3748 20454 2391 20455 3749 20455 3751 20455 2393 20456 3751 20456 3752 20456 2397 20457 3752 20457 3753 20457 2402 20458 3754 20458 3755 20458 2390 20459 3755 20459 3750 20459 2391 20460 3751 20460 2393 20460 2402 20461 3755 20461 2390 20461 3749 20462 3756 20462 3751 20462 3751 20463 3756 20463 3758 20463 3752 20464 3758 20464 3759 20464 3753 20465 3759 20465 3760 20465 3751 20466 3758 20466 3752 20466 3752 20467 3759 20467 3753 20467 3753 20468 3761 20468 3754 20468 3755 20469 3757 20469 3750 20469 3626 20470 3763 20470 3765 20470 3625 20471 3765 20471 3766 20471 3635 20472 3766 20472 3634 20472 3634 20473 3768 20473 3633 20473 3631 20474 3769 20474 3629 20474 3765 20475 3770 20475 3772 20475 3767 20476 3773 20476 3774 20476 3768 20477 3774 20477 3775 20477 3768 20478 3775 20478 3776 20478 3769 20479 3776 20479 3771 20479 3764 20480 3771 20480 3763 20480 3765 20481 3772 20481 3766 20481 3766 20482 3773 20482 3767 20482 3768 20483 3776 20483 3769 20483 3769 20484 3771 20484 3764 20484 3736 20485 3777 20485 3779 20485 3726 20486 3779 20486 3780 20486 3727 20487 3780 20487 3781 20487 3741 20488 3782 20488 3783 20488 3735 20489 3740 20489 3778 20489 3726 20490 3780 20490 3727 20490 3729 20491 3782 20491 3731 20491 3741 20492 3784 20492 3740 20492 3779 20493 3777 20493 3780 20493 3785 20494 3786 20494 3720 20494 3720 20495 3786 20495 3722 20495 3728 20496 3790 20496 3791 20496 3728 20497 3791 20497 3785 20497 3722 20498 3787 20498 3724 20498 3733 20499 3789 20499 3732 20499 3730 20500 3790 20500 3728 20500 3791 20501 3786 20501 3785 20501 3787 20502 3786 20502 3792 20502 3790 20503 3792 20503 3791 20503 3713 20504 3795 20504 3796 20504 3723 20505 3797 20505 3798 20505 3719 20506 3799 20506 3800 20506 3715 20507 3717 20507 3793 20507 3711 20508 3795 20508 3713 20508 3723 20509 3798 20509 3721 20509 3721 20510 3799 20510 3719 20510 3801 20511 3794 20511 3793 20511 3797 20512 3804 20512 3805 20512 3799 20513 3806 20513 3807 20513 3800 20514 3807 20514 3801 20514 3793 20515 3800 20515 3801 20515 3798 20516 3806 20516 3799 20516 3799 20517 3807 20517 3800 20517 3808 20518 3809 20518 3704 20518 3714 20519 3810 20519 3811 20519 3704 20520 3810 20520 3707 20520 3707 20521 3810 20521 3714 20521 3714 20522 3811 20522 3716 20522 3716 20523 3812 20523 3718 20523 3816 20524 3809 20524 3808 20524 3816 20525 3817 20525 3809 20525 3809 20526 3817 20526 3810 20526 3810 20527 3817 20527 3818 20527 3811 20528 3818 20528 3819 20528 3812 20529 3819 20529 3820 20529 3815 20530 3822 20530 3816 20530 3808 20531 3815 20531 3816 20531 3811 20532 3819 20532 3812 20532 3813 20533 3821 20533 3814 20533 3783 20534 3823 20534 3777 20534 3780 20535 3777 20535 3823 20535 3771 20536 3776 20536 3824 20536 3817 20537 3816 20537 3824 20537 3826 20538 3822 20538 3821 20538 3827 20539 3820 20539 3819 20539 3776 20540 3828 20540 3817 20540 3776 20541 3775 20541 3828 20541 3819 20542 3774 20542 3827 20542 3820 20543 3773 20543 3772 20543 3826 20544 3772 20544 3770 20544 3825 20545 3770 20545 3771 20545 3826 20546 3770 20546 3822 20546 3822 20547 3770 20547 3825 20547 3757 20548 3829 20548 3801 20548 3757 20549 3762 20549 3829 20549 3802 20550 3829 20550 3762 20550 3830 20551 3801 20551 3807 20551 3833 20552 3803 20552 3802 20552 3762 20553 3761 20553 3833 20553 3803 20554 3833 20554 3761 20554 3761 20555 3760 20555 3804 20555 3760 20556 3759 20556 3832 20556 3805 20557 3759 20557 3758 20557 3830 20558 3756 20558 3757 20558 3801 20559 3830 20559 3757 20559 3805 20560 3758 20560 3806 20560 3831 20561 3756 20561 3807 20561 3586 20562 3582 20562 3834 20562 3834 20563 3582 20563 3835 20563 3838 20564 2138 20564 2176 20564 3840 20565 2163 20565 2164 20565 3841 20566 3549 20566 3842 20566 3842 20567 3549 20567 3571 20567 3844 20568 3569 20568 3552 20568 3845 20569 3553 20569 3566 20569 2654 20570 3564 20570 3556 20570 3556 20571 3557 20571 3846 20571 3846 20572 3557 20572 3847 20572 3600 20573 2181 20573 3848 20573 3848 20574 2181 20574 2182 20574 2149 20575 2201 20575 2472 20575 3850 20576 2201 20576 2199 20576 3849 20577 2201 20577 3850 20577 2199 20578 2198 20578 3850 20578 3850 20579 2198 20579 3851 20579 3852 20580 2214 20580 2211 20580 3852 20581 2200 20581 3853 20581 3854 20582 2205 20582 2203 20582 3855 20583 2193 20583 2194 20583 3856 20584 2207 20584 2212 20584 3857 20585 2212 20585 2213 20585 3856 20586 2212 20586 3857 20586 2150 20587 3859 20587 2213 20587 2147 20588 2195 20588 3602 20588 3597 20589 2183 20589 2515 20589 2178 20590 2172 20590 3861 20590 3861 20591 2172 20591 3862 20591 3862 20592 2172 20592 2173 20592 3862 20593 2173 20593 2486 20593 2486 20594 2173 20594 2175 20594 3510 20595 3863 20595 3511 20595 3515 20596 3865 20596 3516 20596 3520 20597 3869 20597 3494 20597 3520 20598 3562 20598 3869 20598 2240 20599 3871 20599 2236 20599 2236 20600 3871 20600 2252 20600 3871 20601 2242 20601 3872 20601 2243 20602 2245 20602 3873 20602 3182 20603 3185 20603 3183 20603 2101 20604 2094 20604 2102 20604 2102 20605 2094 20605 3874 20605 2132 20606 2165 20606 3875 20606 3878 20607 2170 20607 3880 20607 2509 20608 3881 20608 2177 20608 2134 20609 3882 20609 2177 20609 3883 20610 3575 20610 3576 20610 3883 20611 3531 20611 2628 20611 3581 20612 3580 20612 3884 20612 3884 20613 3580 20613 3885 20613 3885 20614 3580 20614 3585 20614 2624 20615 3886 20615 3585 20615 3885 20616 3585 20616 3886 20616 3585 20617 3534 20617 2624 20617 3887 20618 3587 20618 3592 20618 2618 20619 3887 20619 3592 20619 3499 20620 3541 20620 3592 20620 3592 20621 3541 20621 2618 20621 2615 20622 3589 20622 3544 20622 3428 20623 2615 20623 3544 20623 2112 20624 2117 20624 2110 20624 2110 20625 2117 20625 2111 20625 2601 20626 2600 20626 2107 20626 2601 20627 2107 20627 2108 20627 2600 20628 2116 20628 2107 20628 3391 20629 2117 20629 2116 20629 3425 20630 3426 20630 2117 20630 3545 20631 3427 20631 3424 20631 3424 20632 3423 20632 3888 20632 3545 20633 3888 20633 3543 20633 3545 20634 3424 20634 3888 20634 3543 20635 3423 20635 3428 20635 2606 20636 2615 20636 2607 20636 2606 20637 3589 20637 2615 20637 3887 20638 2618 20638 2609 20638 3541 20639 2619 20639 2618 20639 2609 20640 2607 20640 3889 20640 3588 20641 3587 20641 3889 20641 2616 20642 3590 20642 3889 20642 2609 20643 2619 20643 3834 20643 3834 20644 2610 20644 2609 20644 3539 20645 3420 20645 3538 20645 3420 20646 3539 20646 2619 20646 3420 20647 3421 20647 3536 20647 2613 20648 3536 20648 3421 20648 2613 20649 3582 20649 3537 20649 3885 20650 3886 20650 2621 20650 3535 20651 3418 20651 3417 20651 3417 20652 2624 20652 3534 20652 3416 20653 3532 20653 2625 20653 3416 20654 3414 20654 3891 20654 3530 20655 3532 20655 3891 20655 3532 20656 3416 20656 3891 20656 2628 20657 3530 20657 3891 20657 3533 20658 3584 20658 3890 20658 2501 20659 3874 20659 3892 20659 3874 20660 2493 20660 2102 20660 2497 20661 2499 20661 2099 20661 2099 20662 2499 20662 2100 20662 2589 20663 2095 20663 2100 20663 2501 20664 3837 20664 3893 20664 2490 20665 3894 20665 2502 20665 2494 20666 3895 20666 3894 20666 2582 20667 3897 20667 3896 20667 2505 20668 3877 20668 3897 20668 2505 20669 3875 20669 3877 20669 2488 20670 2491 20670 3875 20670 3875 20671 2491 20671 3876 20671 2504 20672 3876 20672 2491 20672 3896 20673 2161 20673 2167 20673 3896 20674 2167 20674 2504 20674 3838 20675 3839 20675 2508 20675 3839 20676 3840 20676 2580 20676 2505 20677 2580 20677 3840 20677 3899 20678 2505 20678 3898 20678 3840 20679 2164 20679 3898 20679 3881 20680 2575 20680 3880 20680 2487 20681 2485 20681 3879 20681 3882 20682 2485 20682 2506 20682 3900 20683 2485 20683 3882 20683 2506 20684 2509 20684 3882 20684 2575 20685 3881 20685 2509 20685 2575 20686 3878 20686 3880 20686 2487 20687 3879 20687 3878 20687 2487 20688 3878 20688 2570 20688 3901 20689 2639 20689 2634 20689 2634 20690 2627 20690 3902 20690 2634 20691 3902 20691 3901 20691 2629 20692 3413 20692 3528 20692 3529 20693 3411 20693 2639 20693 3901 20694 3573 20694 3578 20694 3901 20695 3578 20695 2639 20695 3841 20696 2641 20696 2634 20696 2644 20697 2641 20697 3842 20697 3412 20698 3410 20698 3408 20698 3842 20699 3571 20699 2644 20699 3903 20700 2651 20700 2643 20700 2643 20701 3904 20701 3903 20701 3904 20702 2641 20702 2645 20702 3408 20703 3405 20703 3863 20703 3864 20704 3863 20704 3405 20704 3405 20705 2651 20705 3864 20705 3511 20706 3864 20706 3570 20706 3570 20707 3864 20707 2651 20707 3903 20708 3551 20708 3570 20708 2643 20709 2652 20709 3844 20709 3844 20710 2554 20710 2643 20710 3407 20711 2554 20711 3845 20711 3844 20712 2652 20712 3843 20712 3905 20713 3843 20713 2652 20713 3845 20714 3406 20714 3407 20714 3845 20715 3566 20715 3568 20715 3406 20716 3845 20716 3568 20716 3907 20717 2653 20717 2555 20717 3907 20718 2554 20718 3908 20718 3908 20719 2554 20719 3867 20719 3403 20720 3400 20720 3865 20720 3865 20721 3400 20721 3866 20721 3516 20722 3866 20722 3565 20722 3402 20723 2653 20723 3565 20723 3909 20724 3910 20724 3401 20724 3401 20725 3399 20725 3909 20725 3399 20726 3395 20726 3911 20726 3910 20727 3909 20727 3911 20727 3911 20728 3395 20728 3396 20728 3847 20729 3396 20729 3397 20729 2555 20730 2654 20730 3846 20730 3846 20731 3847 20731 2656 20731 3846 20732 2656 20732 2555 20732 3397 20733 2656 20733 3847 20733 3396 20734 3847 20734 3563 20734 2567 20735 2512 20735 3861 20735 2487 20736 2570 20736 3862 20736 2487 20737 3862 20737 2486 20737 2511 20738 3594 20738 3595 20738 3594 20739 2484 20739 3593 20739 3594 20740 2511 20740 2484 20740 2486 20741 3593 20741 2484 20741 3861 20742 2512 20742 2178 20742 3912 20743 2513 20743 2512 20743 2567 20744 2562 20744 3913 20744 2567 20745 3913 20745 3912 20745 3913 20746 2562 20746 2515 20746 2481 20747 2482 20747 2510 20747 3597 20748 2510 20748 3596 20748 3912 20749 2179 20749 2186 20749 3600 20750 3848 20750 2562 20750 2514 20751 2562 20751 3848 20751 3600 20752 2517 20752 3599 20752 2516 20753 2480 20753 3914 20753 2514 20754 3598 20754 3914 20754 2481 20755 2514 20755 3914 20755 2514 20756 2182 20756 2184 20756 3915 20757 3916 20757 2517 20757 2560 20758 2558 20758 3917 20758 2560 20759 3917 20759 3915 20759 3917 20760 2558 20760 2518 20760 2480 20761 2517 20761 3601 20761 2143 20762 3601 20762 2191 20762 3915 20763 2189 20763 2191 20763 3851 20764 3918 20764 2545 20764 2473 20765 2472 20765 2541 20765 2541 20766 2472 20766 3849 20766 3605 20767 2472 20767 2474 20767 2474 20768 2478 20768 3605 20768 3918 20769 3605 20769 2478 20769 2541 20770 3849 20770 3850 20770 3851 20771 2198 20771 2204 20771 3851 20772 2204 20772 3918 20772 2521 20773 3852 20773 2539 20773 3606 20774 3919 20774 2471 20774 3607 20775 3606 20775 2473 20775 3607 20776 3853 20776 2202 20776 3920 20777 2659 20777 2525 20777 2525 20778 2656 20778 3921 20778 3397 20779 3870 20779 3921 20779 3921 20780 2656 20780 3397 20780 3397 20781 3395 20781 3869 20781 3395 20782 3394 20782 3869 20782 3561 20783 3868 20783 2659 20783 3920 20784 3559 20784 2659 20784 3857 20785 2521 20785 3856 20785 2522 20786 2468 20786 3922 20786 3859 20787 2521 20787 3858 20787 3857 20788 3858 20788 2521 20788 3856 20789 2536 20789 3923 20789 3923 20790 2522 20790 3922 20790 2208 20791 2207 20791 3923 20791 3923 20792 2207 20792 3856 20792 3922 20793 2208 20793 3923 20793 3604 20794 3924 20794 3603 20794 2519 20795 2518 20795 3603 20795 2545 20796 2478 20796 3854 20796 3854 20797 3855 20797 2558 20797 2518 20798 2558 20798 3855 20798 2250 20799 2251 20799 2535 20799 2252 20800 2530 20800 2531 20800 2529 20801 3872 20801 2528 20801 2249 20802 2248 20802 2658 20802 3178 20803 2662 20803 3176 20803 3178 20804 2664 20804 2662 20804 3178 20805 3180 20805 2664 20805 2664 20806 3180 20806 2538 20806 3170 20807 2534 20807 2533 20807 3171 20808 3173 20808 2665 20808 3173 20809 3175 20809 2657 20809 3173 20810 2657 20810 2660 20810 3175 20811 3176 20811 2662 20811 3195 20812 2544 20812 2557 20812 2544 20813 2666 20813 2557 20813 3195 20814 3197 20814 2544 20814 2544 20815 3197 20815 2540 20815 3197 20816 2537 20816 2540 20816 3185 20817 2663 20817 3198 20817 3198 20818 2663 20818 2537 20818 3186 20819 3192 20819 2661 20819 2661 20820 3192 20820 2655 20820 3192 20821 3193 20821 2556 20821 3193 20822 2557 20822 2556 20822 3207 20823 2548 20823 2550 20823 3207 20824 2546 20824 2548 20824 3210 20825 3212 20825 2543 20825 3210 20826 2543 20826 2542 20826 2543 20827 3214 20827 2666 20827 2543 20828 3212 20828 3214 20828 3216 20829 2551 20829 2553 20829 3206 20830 2551 20830 3217 20830 2551 20831 3206 20831 2550 20831 3228 20832 3229 20832 2547 20832 3229 20833 3230 20833 2548 20833 3229 20834 2548 20834 2547 20834 3234 20835 2642 20835 2552 20835 3247 20836 2565 20836 3257 20836 2638 20837 3257 20837 2565 20837 3248 20838 3249 20838 2566 20838 3249 20839 3250 20839 2650 20839 3249 20840 2650 20840 2566 20840 2647 20841 3250 20841 3252 20841 2647 20842 2650 20842 3250 20842 3255 20843 2638 20843 2636 20843 3267 20844 2632 20844 3277 20844 2568 20845 2632 20845 3267 20845 3269 20846 3270 20846 2564 20846 2637 20847 3270 20847 3272 20847 3287 20848 2574 20848 3297 20848 3287 20849 2571 20849 2574 20849 3289 20850 2633 20850 2569 20850 2631 20851 3290 20851 3292 20851 3292 20852 3294 20852 2631 20852 3317 20853 2579 20853 2673 20853 3307 20854 3308 20854 2576 20854 3308 20855 3309 20855 2572 20855 3309 20856 3310 20856 2573 20856 2573 20857 3310 20857 3312 20857 2667 20858 3312 20858 2620 20858 3314 20859 2612 20859 2620 20859 3315 20860 3317 20860 2673 20860 3327 20861 2671 20861 3337 20861 2669 20862 3337 20862 2671 20862 3328 20863 3329 20863 2577 20863 3329 20864 3330 20864 2578 20864 3329 20865 2578 20865 2577 20865 2578 20866 3330 20866 3332 20866 3332 20867 3334 20867 2672 20867 3334 20868 3335 20868 2608 20868 3335 20869 3337 20869 2669 20869 3335 20870 2669 20870 2608 20870 3347 20871 2604 20871 3357 20871 2587 20872 2674 20872 2604 20872 3347 20873 3348 20873 2587 20873 2587 20874 3348 20874 2583 20874 3348 20875 2588 20875 2583 20875 2668 20876 3350 20876 3352 20876 3355 20877 2604 20877 2603 20877 2595 20878 2596 20878 2597 20878 3366 20879 3368 20879 2585 20879 3368 20880 2586 20880 2585 20880 2586 20881 3372 20881 2674 20881 2586 20882 3370 20882 3372 20882 2674 20883 3372 20883 2602 20883 3365 20884 2597 20884 3375 20884 2146 20885 3605 20885 2204 20885 3917 20886 2195 20886 2192 20886 3506 20887 3577 20887 3528 20887 3528 20888 3577 20888 2629 20888 3904 20889 3572 20889 3550 20889 2645 20890 3572 20890 3904 20890 3905 20891 3512 20891 3513 20891 3512 20892 3905 20892 3514 20892 3514 20893 3905 20893 3906 20893 3406 20894 3514 20894 3906 20894 3401 20895 3910 20895 3517 20895 3517 20896 3910 20896 3519 20896 3519 20897 3910 20897 3911 20897 3519 20898 3396 20898 3563 20898 3429 20899 2465 20899 2527 20899 2527 20900 2465 20900 2466 20900 2151 20901 2210 20901 2468 20901 2468 20902 2210 20902 3922 20902 3874 20903 2094 20903 2097 20903 3874 20904 2097 20904 3892 20904 3892 20905 2096 20905 2589 20905 2113 20906 3895 20906 2166 20906 2166 20907 3895 20907 3893 20907 2502 20908 2133 20908 2168 20908 2502 20909 3894 20909 2133 20909 2133 20910 3894 20910 2113 20910 2113 20911 3894 20911 3895 20911 2162 20912 2161 20912 3897 20912 3897 20913 2161 20913 3896 20913 3917 20914 2189 20914 3915 20914 2136 20915 2174 20915 3900 20915 2136 20916 3900 20916 2134 20916 3899 20917 3898 20917 2156 20917 2156 20918 3898 20918 2164 20918 2137 20919 2507 20919 2156 20919 2512 20920 3595 20920 2185 20920 3890 20921 2625 20921 3533 20921 2629 20922 3577 20922 3902 20922 3574 20923 3573 20923 3902 20923 3502 20924 3583 20924 3535 20924 3535 20925 3583 20925 2614 20925 3498 20926 3590 20926 3542 20926 2292 20927 2280 20927 3391 20927 3925 20928 2371 20928 3129 20928 3129 20929 3926 20929 3925 20929 3129 20930 3130 20930 3926 20930 2374 20931 3121 20931 3122 20931 2372 20932 2373 20932 3128 20932 2373 20933 2374 20933 3122 20933 2374 20934 2375 20934 3121 20934 2375 20935 2376 20935 3139 20935 2376 20936 2377 20936 3138 20936 2377 20937 3929 20937 3137 20937 3929 20938 3928 20938 3137 20938 3928 20939 3927 20939 3131 20939 3008 20940 3058 20940 3057 20940 3002 20941 3062 20941 2342 20941 2998 20942 2342 20942 3064 20942 2990 20943 3065 20943 2986 20943 2976 20944 3044 20944 3120 20944 2972 20945 3120 20945 2323 20945 3049 20946 3022 20946 3051 20946 3049 20947 3020 20947 3022 20947 3018 20948 3020 20948 3016 20948 3002 20949 2342 20949 2998 20949 2992 20950 3065 20950 2990 20950 2990 20951 2986 20951 2988 20951 2978 20952 3044 20952 2976 20952 2976 20953 3120 20953 2974 20953 2974 20954 3120 20954 2972 20954 2970 20955 2323 20955 2968 20955 3024 20956 2968 20956 3022 20956 3016 20957 3049 20957 3014 20957 2356 20958 3014 20958 2353 20958 3077 20959 2982 20959 2984 20959 3079 20960 2941 20960 2939 20960 2941 20961 3081 20961 3928 20961 3929 20962 2941 20962 3928 20962 3929 20963 2377 20963 2941 20963 3932 20964 3933 20964 3934 20964 3931 20965 3936 20965 3933 20965 3940 20966 3943 20966 3944 20966 3944 20967 3943 20967 3945 20967 3945 20968 3943 20968 3946 20968 3946 20969 3943 20969 3942 20969 3942 20970 3948 20970 3947 20970 3949 20971 3950 20971 3951 20971 3952 20972 3950 20972 3949 20972 3956 20973 3940 20973 3944 20973 3957 20974 3940 20974 3956 20974 3960 20975 3961 20975 3962 20975 3963 20976 3962 20976 3964 20976 3966 20977 3968 20977 3967 20977 3973 20978 3972 20978 3970 20978 3974 20979 3975 20979 3976 20979 3978 20980 3977 20980 3974 20980 3983 20981 3984 20981 3982 20981 3988 20982 3963 20982 3989 20982 3988 20983 3960 20983 3963 20983 3963 20984 3964 20984 3965 20984 3991 20985 3965 20985 3992 20985 3965 20986 3967 20986 3993 20986 3992 20987 3965 20987 3993 20987 3965 20988 3991 20988 3963 20988 3989 20989 3963 20989 3991 20989 3990 20990 3986 20990 3960 20990 3987 20991 3983 20991 3961 20991 3980 20992 3982 20992 3994 20992 3980 20993 3994 20993 3995 20993 3981 20994 3980 20994 3995 20994 3980 20995 3979 20995 3975 20995 3977 20996 3997 20996 3969 20996 3969 20997 3997 20997 3971 20997 3998 20998 4000 20998 4001 20998 4002 20999 4003 20999 3998 20999 4003 21000 4002 21000 4004 21000 4005 21001 3971 21001 3997 21001 4001 21002 4000 21002 4007 21002 4000 21003 3973 21003 4007 21003 4007 21004 3973 21004 3970 21004 4003 21005 4008 21005 3998 21005 4010 21006 3998 21006 4009 21006 4010 53 4011 53 3998 53 4014 21007 4013 21007 3996 21007 4016 21008 4015 21008 3978 21008 4009 21009 4015 21009 4016 21009 4016 21010 3978 21010 3974 21010 4012 21011 4013 21011 4014 21011 4013 21012 3976 21012 3996 21012 4019 21013 4020 21013 3998 21013 4021 21014 4019 21014 4022 21014 4018 21015 4017 21015 4024 21015 4025 21016 4024 21016 3979 21016 4018 21017 4024 21017 4025 21017 4021 21018 4022 21018 4023 21018 4030 21019 4029 21019 3984 21019 4032 53 4031 53 4033 53 4035 21020 4034 21020 3987 21020 4035 21021 3987 21021 3985 21021 4032 21022 4036 21022 4026 21022 4026 21023 4036 21023 4037 21023 4038 21024 4039 21024 4026 21024 4041 21025 4040 21025 3990 21025 4037 21026 4036 21026 4042 21026 4042 21027 4044 21027 4043 21027 4039 21028 4045 21028 4026 21028 4047 21029 4026 21029 4046 21029 4047 21030 4048 21030 4026 21030 3992 21031 4048 21031 4049 21031 4046 21032 4045 21032 4050 21032 4052 21033 4050 21033 4053 21033 4053 21034 3989 21034 3991 21034 4052 21035 4053 21035 3991 21035 4048 21036 3992 21036 3993 21036 4058 21037 4060 21037 4059 21037 4062 21038 4063 21038 4064 21038 4066 21039 4068 21039 4067 21039 4066 21040 4065 21040 4071 21040 4071 21041 4065 21041 4072 21041 4073 21042 4072 21042 4065 21042 4068 21043 4062 21043 4067 21043 4074 21044 4075 21044 4076 21044 4077 21045 4074 21045 4076 21045 4077 21046 4078 21046 4074 21046 4077 21047 4080 21047 4078 21047 4082 21048 4084 21048 4083 21048 4082 21049 4076 21049 4085 21049 4082 21050 4085 21050 4084 21050 4086 21051 4085 21051 4088 21051 4089 21052 4074 21052 4090 21052 4082 21053 4079 21053 4077 21053 4091 21054 4092 21054 4093 21054 4094 21055 4095 21055 4093 21055 4093 21056 4095 21056 4091 21056 4092 21057 4097 21057 4093 21057 4096 21058 4098 21058 4099 21058 4096 21059 4099 21059 4097 21059 4096 21060 4100 21060 4098 21060 4102 21061 4092 21061 4091 21061 4093 21062 4097 21062 4094 21062 4110 21063 4109 21063 4108 21063 4109 21064 4106 21064 4104 21064 4113 21065 4104 21065 4114 21065 4114 21066 4104 21066 4103 21066 4105 21067 4109 21067 4110 21067 4123 21068 4122 21068 4121 21068 4120 21069 4119 21069 4117 21069 4124 21070 4120 21070 4125 21070 4118 21071 4119 21071 4122 21071 4122 21072 4119 21072 4120 21072 4115 21073 4105 21073 4133 21073 4133 21074 4105 21074 4110 21074 4134 21075 4133 21075 4110 21075 4135 21076 4134 21076 4108 21076 4136 21077 4137 21077 4138 21077 4139 21078 4123 21078 4140 21078 4124 21079 4141 21079 4120 21079 4139 21080 4142 21080 4122 21080 4138 21081 4144 21081 4143 21081 4137 21082 4145 21082 4138 21082 4146 21083 4145 21083 4137 21083 4148 21084 4129 21084 4149 21084 4148 21085 4149 21085 4150 21085 3950 21086 3999 21086 4152 21086 4152 21087 4151 21087 3950 21087 3950 21088 4149 21088 3951 21088 4156 21089 4154 21089 4153 21089 4157 21090 4158 21090 4154 21090 4157 21091 4154 21091 4156 21091 4161 21092 4162 21092 4163 21092 4167 21093 4168 21093 4169 21093 4178 21094 4179 21094 4176 21094 4183 21095 4184 21095 4185 21095 4188 21096 4192 21096 4189 21096 4189 21097 4192 21097 4193 21097 4193 21098 4194 21098 4195 21098 4194 21099 4196 21099 4195 21099 4194 21100 4197 21100 4196 21100 4197 21101 4198 21101 4196 21101 4196 21102 4198 21102 4199 21102 4195 21103 4196 21103 4200 21103 4190 21104 4201 21104 4191 21104 4190 21105 4202 21105 4201 21105 4203 21106 4201 21106 4204 21106 4205 21107 4191 21107 4201 21107 4202 53 4190 53 4206 53 4206 53 4190 53 4207 53 4208 21108 4190 21108 4189 21108 4189 21109 4193 21109 4209 21109 4209 21110 4193 21110 4210 21110 4210 21111 4193 21111 4195 21111 4211 53 4195 53 4212 53 4211 21112 4210 21112 4195 21112 4213 21113 4215 21113 4216 21113 4217 21114 4216 21114 4218 21114 4218 21115 4216 21115 4219 21115 4220 21116 4221 21116 4222 21116 4220 21117 4223 21117 4221 21117 4222 21118 4224 21118 4220 21118 4220 21119 4224 21119 4226 21119 4220 21120 4226 21120 4231 21120 4231 21121 4226 21121 4227 21121 4236 21122 4235 21122 4237 21122 4238 53 4237 53 4239 53 4232 53 4233 53 4240 53 4239 53 4237 53 4241 53 4241 53 4237 53 4242 53 4242 53 4237 53 4243 53 4222 21123 4246 21123 4244 21123 4245 21124 4247 21124 4222 21124 4248 21125 4249 21125 4250 21125 4248 21126 4251 21126 4249 21126 4249 21127 4252 21127 4255 21127 4256 21128 4253 21128 4249 21128 4257 21129 4258 21129 4253 21129 4253 21130 4258 21130 4259 21130 4259 21131 4258 21131 4260 21131 4260 21132 4254 21132 4259 21132 4213 21133 4261 21133 4260 21133 4214 21134 4260 21134 4262 21134 4260 21135 4257 21135 4262 21135 4264 21136 4267 21136 4245 21136 4271 21137 4267 21137 4264 21137 4269 21138 4271 21138 4264 21138 4270 21139 4273 21139 4242 21139 4239 21140 4274 21140 4275 21140 4242 21141 4273 21141 4241 21141 4269 21142 4256 21142 4272 21142 4269 21143 4253 21143 4256 21143 4273 21144 4272 21144 4256 21144 4273 21145 4255 21145 4274 21145 4273 21146 4249 21146 4255 21146 4275 21147 4255 21147 4252 21147 4238 21148 4275 21148 4276 21148 4276 21149 4275 21149 4252 21149 4277 21150 4252 21150 4278 21150 4252 21151 4279 21151 4278 21151 4281 21152 4284 21152 4285 21152 4266 21153 4285 21153 4268 21153 4268 21154 4285 21154 4286 21154 4266 21155 4244 21155 4289 21155 4288 21156 4266 21156 4289 21156 4287 21157 4291 21157 4265 21157 4265 21158 4291 21158 4262 21158 4296 21159 4295 21159 4297 21159 4095 21160 4298 21160 4299 21160 4300 21161 4299 21161 4302 21161 4302 21162 4298 21162 4303 21162 4304 21163 4305 21163 4301 21163 4304 21164 4307 21164 4306 21164 4304 21165 4308 21165 4307 21165 4307 21166 4308 21166 4309 21166 4309 21167 4310 21167 4311 21167 4312 21168 4308 21168 4313 21168 4312 21169 4313 21169 4314 21169 4315 21170 4316 21170 4312 21170 4317 21171 4319 21171 4318 21171 4317 21172 4320 21172 4319 21172 4317 21173 4322 21173 4321 21173 4321 21174 4322 21174 4323 21174 4326 21175 4327 21175 4322 21175 4329 21176 4328 21176 4330 21176 4332 21177 4331 21177 4330 21177 4333 21178 4334 21178 4328 21178 4328 21179 4334 21179 4335 21179 4335 21180 4112 21180 3937 21180 3937 21181 4112 21181 4336 21181 4329 21182 4337 21182 4338 21182 4327 21183 4326 21183 4339 21183 4327 21184 4340 21184 4322 21184 4323 21185 4322 21185 4340 21185 4340 21186 4341 21186 4343 21186 4344 21187 4345 21187 4346 21187 4319 21188 4320 21188 4347 21188 4307 21189 4353 21189 4354 21189 4306 21190 4355 21190 4102 21190 4070 21191 4357 21191 4293 21191 4358 21192 4073 21192 4296 21192 4070 21193 4071 21193 4357 21193 4066 21194 4071 21194 4070 21194 4095 21195 4098 21195 4298 21195 4355 21196 4356 21196 4100 21196 4299 21197 4301 21197 4305 21197 4298 21198 4098 21198 4101 21198 4356 21199 4363 21199 4298 21199 4356 21200 4364 21200 4363 21200 4367 21201 4364 21201 4366 21201 4368 21202 4369 21202 4370 21202 4372 21203 4371 21203 4351 21203 4372 21204 4351 21204 4373 21204 4377 21205 4376 21205 4378 21205 4378 21206 4376 21206 4388 21206 4391 21207 4388 21207 4392 21207 4393 21208 4394 21208 4395 21208 4393 21209 4395 21209 4396 21209 4397 21210 4393 21210 4396 21210 4378 21211 4388 21211 4391 21211 4399 21212 4400 21212 4394 21212 4401 21213 4402 21213 4403 21213 4408 21214 4407 21214 4342 21214 4408 21215 4342 21215 4409 21215 4408 21216 4409 21216 4410 21216 4411 21217 4408 21217 4410 21217 4342 21218 4407 21218 4343 21218 4409 21219 4342 21219 4412 21219 4415 21220 4414 21220 4416 21220 4409 21221 4412 21221 4413 21221 4425 21222 3937 21222 4336 21222 4429 21223 4423 21223 4428 21223 4429 21224 4428 21224 4430 21224 4430 21225 4431 21225 4432 21225 4432 21226 4433 21226 4430 21226 4436 21227 4435 21227 4437 21227 4432 21228 4439 21228 4434 21228 4435 21229 3947 21229 4440 21229 4437 21230 4435 21230 4441 21230 4442 21231 4441 21231 4443 21231 4444 21232 4446 21232 4445 21232 4447 21233 4448 21233 4444 21233 4454 21234 4444 21234 4455 21234 4454 21235 4456 21235 4457 21235 4461 21236 4462 21236 4463 21236 4460 21237 4464 21237 4465 21237 4465 21238 4464 21238 4466 21238 4467 21239 4465 21239 4466 21239 4400 21240 4401 21240 4468 21240 4470 21241 4469 21241 4471 21241 4472 21242 4471 21242 4473 21242 4397 21243 4472 21243 4473 21243 4397 21244 4396 21244 4472 21244 4469 21245 4474 21245 4475 21245 4471 21246 4469 21246 4476 21246 4384 21247 4479 21247 4382 21247 4482 21248 4476 21248 4477 21248 4478 21249 4486 21249 4487 21249 4385 21250 4488 21250 4489 21250 4386 21251 4385 21251 4490 21251 4490 21252 4385 21252 4491 21252 4492 21253 4491 21253 4358 21253 4493 21254 4358 21254 4297 21254 4490 21255 4491 21255 4492 21255 4370 21256 4369 21256 4498 21256 4370 21257 4365 21257 4368 21257 4368 21258 4365 21258 4356 21258 4379 21259 4377 21259 4378 21259 4377 21260 4373 21260 4376 21260 4483 21261 4482 21261 4477 21261 4482 21262 4471 21262 4476 21262 4502 21263 4454 21263 4457 21263 4406 21264 4405 21264 4502 21264 4442 21265 4504 21265 4451 21265 4505 21266 4506 21266 4413 21266 4421 21267 4505 21267 4413 21267 4414 21268 4421 21268 4413 21268 4411 21269 4410 21269 4507 21269 4419 21270 4418 21270 4509 21270 4436 21271 4433 21271 4435 21271 4506 21272 4503 21272 4504 21272 4451 21273 4437 21273 4441 21273 4408 21274 4404 21274 4407 21274 4457 21275 4406 21275 4502 21275 4398 21276 4391 21276 4392 21276 4382 21277 4477 21277 4478 21277 4510 21278 4511 21278 4512 21278 4518 21279 4513 21279 4517 21279 4516 21280 4513 21280 4519 21280 4519 21281 4515 21281 4520 21281 4510 21282 4512 21282 4522 21282 4523 21283 4512 21283 4524 21283 4528 21284 4529 21284 4530 21284 4530 21285 4529 21285 4531 21285 4534 21286 4533 21286 4535 21286 4536 21287 4537 21287 4538 21287 4542 21288 4541 21288 4543 21288 4546 21289 4545 21289 4547 21289 4548 21290 4549 21290 4550 21290 4550 21291 4549 21291 4551 21291 4558 21292 4557 21292 4559 21292 4562 21293 4561 21293 4563 21293 4564 21294 4565 21294 4566 21294 4576 21295 4577 21295 4578 21295 4580 21296 4581 21296 4291 21296 4291 21297 4581 21297 4292 21297 4582 21298 4583 21298 4584 21298 4586 21299 4587 21299 4588 21299 4588 21300 4587 21300 4589 21300 4596 21301 4595 21301 4597 21301 4598 21302 4599 21302 4600 21302 4606 21303 4607 21303 4608 21303 4608 21304 4607 21304 4609 21304 4620 21305 4619 21305 4621 21305 4624 21306 4623 21306 4625 21306 4628 21307 4627 21307 4629 21307 4630 21308 4631 21308 4632 21308 4632 21309 4631 21309 4633 21309 4634 21310 4635 21310 4636 21310 4638 21311 4639 21311 4640 21311 4640 21312 4639 21312 4641 21312 4640 53 4203 53 4642 53 4644 21313 4640 21313 4642 21313 4641 21314 4645 21314 4646 21314 4635 4533 4634 4533 4647 4533 4647 21315 4634 21315 4648 21315 4632 53 4641 53 4649 53 4630 21316 4632 21316 4651 21316 4651 21317 4632 21317 4649 21317 4578 21318 4654 21318 4576 21318 4633 21319 4653 21319 4655 21319 4578 21320 4579 21320 4654 21320 4659 21321 4628 21321 4657 21321 4572 21322 4660 21322 4573 21322 4573 21323 4660 21323 4658 21323 4626 819 4659 819 4627 819 4572 53 4662 53 4660 53 4627 21324 4661 21324 4629 21324 4629 21325 4661 21325 4663 21325 4574 21326 4575 21326 4662 21326 4662 21327 4575 21327 4664 21327 4624 53 4629 53 4665 53 4665 21328 4629 21328 4663 21328 4575 21329 4569 21329 4664 21329 4664 21330 4569 21330 4666 21330 4622 21331 4624 21331 4667 21331 4667 21332 4624 21332 4665 21332 4569 21333 4668 21333 4666 21333 4622 53 4667 53 4623 53 4625 21334 4669 21334 4671 21334 4570 21335 4571 21335 4670 21335 4620 53 4625 53 4673 53 4571 21336 4565 21336 4672 21336 4675 21337 4620 21337 4673 21337 4564 21338 4676 21338 4565 21338 4619 53 4675 53 4677 53 4564 53 4678 53 4676 53 4619 21324 4677 21324 4621 21324 4566 4500 4567 4500 4678 4500 4678 21339 4567 21339 4680 21339 4681 21340 4621 21340 4679 21340 4680 21341 4561 21341 4682 21341 4614 21342 4616 21342 4683 21342 4683 21343 4616 21343 4681 21343 4560 21344 4684 21344 4561 21344 4561 21345 4684 21345 4682 21345 4614 21346 4683 21346 4615 21346 4562 53 4686 53 4560 53 4617 21347 4685 21347 4687 21347 4689 21348 4617 21348 4687 21348 4688 21349 4557 21349 4690 21349 4691 21350 4612 21350 4689 21350 4556 21351 4692 21351 4557 21351 4610 53 4691 53 4611 53 4611 53 4691 53 4693 53 4556 21352 4694 21352 4692 21352 4559 21353 4553 21353 4696 21353 4696 21354 4553 21354 4698 21354 4606 21355 4608 21355 4699 21355 4699 21356 4608 21356 4697 21356 4553 21357 4700 21357 4698 21357 4607 21358 4701 21358 4609 21358 4609 21359 4701 21359 4703 21359 4604 53 4609 53 4705 53 4704 21360 4549 21360 4706 21360 4602 21361 4604 21361 4707 21361 4548 21362 4708 21362 4549 21362 4549 21363 4708 21363 4706 21363 4550 53 4710 53 4548 53 4603 21364 4709 21364 4605 21364 4605 21365 4709 21365 4711 21365 4550 21366 4551 21366 4710 21366 4710 21367 4551 21367 4712 21367 4713 21368 4605 21368 4711 21368 4712 21369 4545 21369 4714 21369 4598 21370 4600 21370 4715 21370 4544 21371 4716 21371 4545 21371 4545 21372 4716 21372 4714 21372 4599 21373 4715 21373 4717 21373 4546 53 4718 53 4544 53 4601 21374 4717 21374 4719 21374 4594 21375 4596 21375 4723 21375 4723 21376 4596 21376 4721 21376 4595 53 4723 53 4725 53 4542 4531 4726 4531 4540 4531 4595 4551 4725 4551 4597 4551 4597 21377 4725 21377 4727 21377 4726 21378 4543 21378 4728 21378 4592 53 4597 53 4729 53 4729 21379 4597 21379 4727 21379 4543 21380 4537 21380 4728 21380 4728 21381 4537 21381 4730 21381 4731 21382 4592 21382 4729 21382 4537 21383 4732 21383 4730 21383 4590 4564 4731 4564 4591 4564 4734 21384 4539 21384 4736 21384 4588 2659 4593 2659 4737 2659 4586 21385 4588 21385 4739 21385 4739 21386 4588 21386 4737 21386 4586 2650 4739 2650 4587 2650 4587 53 4739 53 4741 53 4534 825 4742 825 4532 825 4589 21387 4741 21387 4743 21387 4534 21388 4535 21388 4742 21388 4742 21389 4535 21389 4744 21389 4582 21390 4584 21390 4747 21390 4528 21391 4748 21391 4529 21391 4582 4564 4747 4564 4583 4564 4583 53 4747 53 4749 53 4292 21392 4751 21392 4263 21392 4527 21393 4290 21393 4752 21393 4753 21394 4752 21394 4246 21394 4530 21395 4531 21395 4750 21395 4750 21396 4531 21396 4755 21396 4751 21397 4580 21397 4756 21397 4527 21398 4752 21398 4526 21398 4526 21399 4752 21399 4757 21399 4580 21400 4585 21400 4756 21400 4531 21401 4526 21401 4755 21401 4282 21402 4759 21402 4758 21402 4283 21403 4760 21403 4761 21403 4636 21404 4759 21404 4634 21404 4575 21405 4759 21405 4569 21405 4569 21406 4759 21406 4571 21406 4557 21407 4282 21407 4559 21407 4557 21408 4563 21408 4282 21408 4282 21409 4288 21409 4529 21409 4535 21410 4282 21410 4529 21410 4535 21411 4533 21411 4282 21411 4547 21412 4282 21412 4541 21412 4282 21413 4545 21413 4551 21413 4549 21414 4282 21414 4551 21414 4282 21415 4555 21415 4553 21415 4559 21416 4282 21416 4553 21416 4761 21417 4203 21417 4640 21417 4641 21418 4761 21418 4640 21418 4761 21419 4632 21419 4633 21419 4628 21420 4761 21420 4633 21420 4761 21421 4629 21421 4624 21421 4625 21422 4620 21422 4761 21422 4761 21423 4620 21423 4621 21423 4761 21424 4617 21424 4283 21424 4283 21425 4608 21425 4609 21425 4601 21426 4283 21426 4600 21426 4601 21427 4596 21427 4283 21427 4283 21428 4596 21428 4597 21428 4592 21429 4283 21429 4597 21429 4283 21430 4593 21430 4588 21430 4589 21431 4283 21431 4588 21431 4584 21432 4585 21432 4287 21432 4204 21433 4764 21433 4203 21433 4143 21434 4199 21434 4136 21434 4199 21435 4762 21435 4136 21435 4766 21436 4767 21436 4147 21436 4147 21437 4767 21437 4130 21437 4130 21438 4767 21438 4768 21438 4132 21439 4768 21439 4769 21439 4771 21440 4772 21440 4773 21440 4773 21441 4772 21441 4774 21441 4775 21442 4166 21442 4162 21442 4162 21443 4777 21443 4775 21443 4782 21444 4783 21444 4784 21444 4784 21445 4783 21445 4785 21445 4788 21446 4786 21446 4789 21446 4790 21447 4792 21447 4791 21447 4793 21448 4792 21448 4794 21448 4795 21449 4793 21449 4794 21449 4795 21450 4796 21450 4793 21450 4523 21451 4524 21451 4521 21451 4520 21452 4517 21452 4516 21452 4784 21453 4786 21453 4788 21453 4799 21454 4797 21454 4800 21454 4801 21455 4800 21455 4802 21455 4805 21456 4804 21456 4171 21456 4806 21457 4807 21457 4805 21457 4808 21458 4179 21458 4809 21458 4178 21459 4810 21459 4809 21459 4813 21460 4812 21460 4184 21460 4813 21461 4814 21461 4144 21461 4816 21462 4815 21462 4817 21462 4801 21463 4802 21463 4803 21463 4815 21464 4818 21464 4817 21464 4511 21465 4525 21465 4512 21465 4816 21466 4144 21466 4815 21466 4766 21467 4147 21467 4202 21467 4816 21468 4196 21468 4143 21468 4813 21469 4138 21469 4145 21469 4812 21470 4145 21470 4146 21470 4813 21471 4145 21471 4812 21471 4812 21472 4146 21472 4811 21472 4131 21473 4132 21473 4770 21473 4819 21474 4770 21474 4771 21474 4819 21475 4771 21475 4773 21475 4131 21476 4770 21476 4819 21476 4820 21477 4821 21477 4822 21477 4820 21478 4823 21478 4821 21478 4823 21479 4824 21479 4825 21479 4827 21480 4826 21480 4828 21480 4829 21481 4828 21481 4830 21481 4831 21482 4830 21482 4832 21482 4833 21483 4832 21483 4834 21483 4837 21484 4836 21484 4838 21484 4841 21485 4840 21485 4842 21485 4843 21486 4842 21486 4844 21486 4849 21487 4848 21487 4850 21487 4851 21488 4850 21488 4852 21488 4853 21489 4852 21489 4854 21489 4855 21490 4854 21490 4856 21490 4759 21491 4863 21491 4864 21491 4827 21492 4828 21492 4829 21492 4831 21493 4832 21493 4833 21493 4837 21494 4838 21494 4839 21494 4845 21495 4846 21495 4847 21495 4853 21496 4854 21496 4855 21496 4855 21497 4856 21497 4857 21497 4857 21498 4858 21498 4859 21498 4859 21499 4860 21499 4861 21499 4861 21500 4862 21500 4197 21500 4197 21501 4863 21501 4759 21501 4761 21502 4865 21502 4866 21502 4205 21503 4866 21503 4867 21503 4191 21504 4205 21504 4867 21504 4867 21505 4868 21505 4869 21505 4871 21506 4870 21506 4872 21506 4873 21507 4872 21507 4874 21507 4875 21508 4874 21508 4876 21508 4877 21509 4876 21509 4822 21509 4821 21510 4877 21510 4822 21510 4869 21511 4870 21511 4871 21511 4205 21512 4761 21512 4866 21512 4879 21513 4787 21513 4765 21513 4881 21514 4818 21514 4882 21514 4882 21515 4818 21515 4798 21515 4514 21516 4520 21516 4515 21516 4157 21517 4156 21517 4884 21517 4885 21518 4884 21518 4156 21518 4886 21519 4885 21519 4887 21519 4889 21520 4886 21520 4164 21520 4887 21521 4891 21521 4888 21521 4159 21522 4892 21522 4153 21522 4153 21523 4893 21523 4156 21523 4894 21524 4895 21524 4896 21524 4896 21525 4885 21525 4893 21525 4900 21526 4901 21526 4902 21526 4888 21527 4903 21527 4904 21527 4888 21528 4891 21528 4903 21528 4902 21529 4891 21529 4899 21529 4899 21530 4891 21530 4887 21530 4896 21531 4887 21531 4885 21531 4903 21532 4902 21532 4901 21532 4183 21533 4186 21533 4906 21533 4906 21534 4186 21534 4187 21534 4907 21535 4906 21535 4187 21535 4907 21536 4172 21536 4908 21536 4170 21537 4172 21537 4909 21537 4911 21538 4912 21538 4913 21538 4911 21539 4915 21539 4916 21539 4177 21540 4917 21540 4918 21540 4916 21541 4915 21541 4177 21541 4187 21542 4924 21542 4907 21542 4925 21543 4926 21543 4927 21543 4928 21544 4925 21544 4927 21544 4930 21545 4927 21545 4929 21545 4927 21546 4907 21546 4928 21546 4928 21547 4907 21547 4924 21547 4928 21548 4913 21548 4925 21548 4926 21549 4912 21549 4192 21549 4913 21550 4928 21550 4914 21550 4914 21551 4928 21551 4187 21551 4923 21552 4914 21552 4187 21552 4928 21553 4924 21553 4187 21553 4909 21554 4930 21554 4922 21554 4938 21555 4937 21555 4939 21555 4934 21556 4935 21556 4936 21556 4936 21557 4937 21557 4938 21557 4938 21558 4940 21558 4932 21558 4164 21559 4774 21559 4905 21559 4941 21560 4164 21560 4886 21560 4772 21561 4886 21561 4888 21561 4161 21562 4883 21562 4779 21562 4883 21563 4884 21563 4890 21563 4167 21564 4908 21564 4168 21564 4171 21565 4170 21565 4920 21565 4169 21566 4806 21566 4167 21566 4167 21567 4806 21567 4918 21567 4168 21568 4908 21568 4942 21568 4173 21569 4175 21569 4178 21569 4173 21570 4178 21570 4177 21570 4179 21571 4910 21571 4176 21571 4910 21572 4906 21572 4908 21572 4180 21573 4813 21573 4184 21573 4180 21574 4184 21574 4915 21574 4187 21575 4181 21575 4180 21575 4160 21576 4158 21576 4943 21576 4173 21577 4183 21577 4174 21577 4910 21578 4167 21578 4176 21578 4176 21579 4167 21579 4917 21579 4917 21580 4167 21580 4918 21580 4917 21581 4177 21581 4176 21581 4818 21582 4944 21582 4798 21582 4818 21583 4181 21583 4944 21583 4818 21584 4815 21584 4181 21584 4181 21585 4815 21585 4814 21585 4814 21586 4182 21586 4181 21586 4944 21587 4181 21587 4945 21587 4185 21588 4942 21588 4945 21588 4185 21589 4174 21589 4942 21589 4174 21590 4184 21590 4811 21590 4910 21591 4169 21591 4168 21591 4169 21592 4910 21592 4179 21592 4942 21593 4910 21593 4168 21593 4945 21594 4942 21594 4946 21594 4171 21595 4946 21595 4942 21595 4802 21596 4946 21596 4804 21596 4883 21597 4948 21597 4157 21597 4943 21598 4892 21598 4159 21598 4787 21599 4155 21599 4949 21599 4787 21600 4785 21600 4155 21600 4155 21601 4785 21601 4783 21601 4154 21602 4941 21602 4950 21602 4154 21603 4883 21603 4941 21603 4883 21604 4154 21604 4158 21604 4941 21605 4883 21605 4890 21605 4890 21606 4166 21606 4165 21606 4166 21607 4890 21607 4162 21607 4952 21608 4768 21608 4767 21608 4952 21609 4765 21609 4949 21609 4950 21610 4954 21610 4955 21610 4949 21611 4955 21611 4956 21611 4768 21612 4957 21612 4958 21612 4769 21613 4958 21613 4953 21613 4950 21614 4955 21614 4949 21614 4949 21615 4956 21615 4952 21615 4768 21616 4958 21616 4769 21616 4954 21617 4960 21617 4961 21617 4955 21618 4961 21618 4962 21618 4954 21619 4961 21619 4955 21619 4955 21620 4962 21620 4956 21620 4962 21621 4963 21621 4956 21621 4953 21622 4964 21622 4959 21622 4957 21623 4964 21623 4958 21623 4958 21624 4964 21624 4953 21624 4965 21625 4966 21625 4947 21625 4800 21626 4966 21626 4967 21626 4945 21627 4968 21627 4969 21627 4944 21628 4969 21628 4965 21628 4947 21629 4944 21629 4965 21629 4946 21630 4968 21630 4945 21630 4970 21631 4965 21631 4971 21631 4970 21632 4966 21632 4965 21632 4969 21633 4975 21633 4971 21633 4968 21634 4974 21634 4969 21634 4898 21635 4894 21635 4892 21635 4898 21636 4943 21636 4897 21636 4897 21637 4943 21637 4976 21637 4977 21638 4161 21638 4163 21638 4901 21639 4905 21639 4903 21639 4976 21640 4948 21640 4977 21640 4977 21641 4163 21641 4905 21641 4188 21642 4979 21642 4978 21642 4871 21643 4981 21643 4188 21643 4871 21644 4982 21644 4981 21644 4982 21645 4871 21645 4900 21645 4900 21646 4902 21646 4899 21646 4983 21647 4896 21647 4984 21647 4984 21648 4896 21648 4985 21648 4979 21649 4980 21649 4984 21649 4985 21650 4896 21650 4895 21650 4895 21651 4897 21651 4986 21651 4986 21652 4897 21652 4987 21652 4987 21653 4897 21653 4940 21653 4987 21654 4939 21654 4988 21654 4990 21655 4937 21655 4839 21655 4990 21656 4839 21656 4991 21656 4991 21657 4839 21657 4841 21657 4992 21658 4931 21658 4930 21658 4993 21659 4930 21659 4929 21659 4994 21660 4929 21660 4926 21660 4989 21661 4988 21661 4939 21661 4919 21662 4931 21662 4841 21662 4992 21663 4930 21663 4993 21663 4993 21664 4929 21664 4994 21664 4995 21665 4926 21665 4996 21665 4996 21666 4926 21666 4192 21666 4997 21667 4996 21667 4192 21667 4978 21668 4997 21668 4192 21668 4989 21669 4994 21669 4926 21669 4964 21670 4982 21670 4959 21670 4983 21671 4961 21671 4960 21671 4900 21672 4960 21672 4959 21672 4981 21673 4963 21673 4980 21673 4983 21674 4960 21674 4900 21674 4971 21675 4994 21675 4989 21675 4993 21676 4975 21676 4974 21676 4992 21677 4974 21677 4973 21677 4990 21678 4972 21678 4970 21678 4993 21679 4974 21679 4992 21679 4520 21680 4514 21680 4786 21680 4786 21681 4514 21681 4766 21681 4202 21682 4206 21682 4766 21682 4766 21683 4206 21683 4786 21683 4786 21684 4206 21684 4789 21684 4212 21685 4817 21685 4795 21685 4794 21686 4212 21686 4795 21686 4511 21687 4521 21687 4795 21687 4763 21688 4636 21688 4998 21688 4637 21689 4999 21689 4636 21689 4755 21690 4054 21690 4746 21690 4755 21691 4757 21691 4054 21691 4738 21692 4744 21692 4054 21692 4736 21693 4054 21693 4730 21693 4056 21694 4696 21694 4054 21694 4056 21695 4690 21695 4696 21695 4056 21696 4688 21696 4690 21696 4056 21697 4682 21697 4688 21697 4056 21698 4680 21698 4682 21698 4056 21699 4674 21699 4680 21699 4056 21700 4666 21700 4672 21700 4056 21701 4664 21701 4666 21701 4056 21702 4656 21702 4658 21702 4056 21703 4648 21703 4650 21703 4706 21704 4712 21704 4054 21704 4712 21705 4714 21705 4054 21705 4722 21706 4054 21706 4720 21706 4728 21707 4730 21707 4054 21707 4151 21708 4643 21708 4764 21708 4148 21709 4150 21709 4764 21709 4731 21710 4729 21710 4733 21710 4721 21711 4725 21711 4723 21711 4715 21712 4713 21712 4717 21712 4711 21713 4709 21713 4705 21713 4689 21714 4693 21714 4691 21714 4683 21715 4681 21715 4685 21715 4685 21716 4681 21716 4687 21716 4669 21717 4665 21717 4671 21717 4663 21718 4661 21718 4657 21718 4651 21719 4649 21719 4653 21719 4646 21720 4645 21720 4642 21720 4642 21721 4645 21721 4644 21721 4757 21722 4752 21722 5000 21722 5000 21723 4752 21723 4753 21723 4762 21724 4059 21724 4136 21724 4728 21725 4722 21725 4726 21725 4712 21726 4706 21726 4710 21726 4710 21727 4706 21727 4708 21727 4700 21728 4702 21728 4698 21728 4694 21729 4690 21729 4692 21729 4684 21730 4686 21730 4682 21730 4668 21731 4670 21731 4666 21731 4666 21732 4670 21732 4672 21732 4664 21733 4658 21733 4662 21733 4652 21734 4654 21734 4650 21734 4647 21735 4998 21735 4999 21735 4748 21736 4750 21736 4746 21736 4746 21737 4750 21737 4755 21737 4742 21738 4738 21738 4740 21738 4764 21739 4204 21739 4148 21739 5003 21740 4140 21740 4141 21740 5004 21741 5005 21741 5006 21741 5005 21742 5004 21742 5009 21742 5009 21743 5008 21743 5005 21743 5010 21744 4127 21744 5011 21744 5017 21745 5016 21745 4133 21745 4135 21746 5018 21746 4334 21746 4336 21747 4112 21747 4113 21747 4112 21748 4335 21748 5019 21748 4334 21749 5019 21749 4335 21749 5019 21750 4334 21750 5018 21750 4112 21751 5019 21751 4109 21751 4112 21752 4109 21752 4111 21752 4107 21753 4109 21753 5019 21753 5018 21754 4108 21754 4107 21754 5020 21755 5021 21755 5022 21755 5022 21756 5023 21756 5024 21756 5022 21757 5021 21757 5023 21757 5020 21758 5028 21758 5029 21758 5022 21759 5024 21759 5028 21759 5023 21760 5031 21760 5024 21760 5035 21761 5036 21761 5037 21761 5036 21762 5025 21762 5038 21762 5037 21763 5038 21763 5039 21763 5038 21764 5025 21764 5020 21764 5040 21765 5041 21765 5042 21765 5044 21766 5043 21766 5045 21766 5040 21767 5046 21767 5043 21767 5047 21768 5048 21768 5049 21768 5046 21769 5047 21769 5050 21769 5049 21770 5052 21770 5047 21770 5047 21771 5052 21771 5051 21771 5048 21772 5053 21772 5049 21772 5053 21773 5048 21773 5055 21773 5053 21774 5055 21774 5054 21774 5054 21775 5055 21775 5056 21775 5055 21776 5042 21776 5056 21776 5058 21777 5060 21777 5062 21777 5063 21778 5062 21778 5060 21778 5062 21779 5063 21779 5064 21779 5059 21780 5058 21780 5065 21780 5066 21781 5061 21781 5067 21781 5068 21782 5061 21782 5062 21782 5067 21783 5068 21783 5069 21783 5068 21784 5070 21784 5069 21784 5064 21785 5063 21785 5070 21785 5070 21786 5063 21786 5071 21786 5071 21787 5072 21787 5073 21787 5072 21788 5063 21788 5060 21788 5073 21789 5060 21789 5074 21789 5059 21790 5065 21790 5060 21790 5075 21791 5076 21791 5077 21791 5078 21792 5075 21792 5077 21792 5079 21793 5075 21793 5078 21793 5075 21794 5079 21794 5080 21794 5082 21795 5078 21795 5081 21795 5079 21796 5082 21796 5083 21796 5076 21797 5075 21797 5084 21797 5084 21798 5075 21798 5085 21798 5075 21799 5080 21799 5085 21799 5083 21800 5087 21800 5079 21800 5079 21801 5087 21801 5086 21801 5083 21802 5082 21802 5088 21802 5087 21803 5088 21803 5089 21803 5088 21804 5090 21804 5089 21804 5090 21805 5081 21805 5091 21805 5091 21806 5081 21806 5092 21806 5093 21807 5076 21807 5094 21807 5095 21808 5096 21808 5097 21808 5098 21809 5095 21809 5097 21809 5095 21810 5099 21810 5100 21810 5102 21811 5099 21811 5098 21811 5099 21812 5102 21812 5103 21812 5096 21813 5095 21813 5104 21813 5105 21814 5100 21814 5106 21814 5099 21815 5107 21815 5106 21815 5103 21816 5108 21816 5107 21816 5102 21817 5110 21817 5108 21817 5110 21818 5102 21818 5101 21818 5110 21819 5101 21819 5111 21819 5113 21820 5114 21820 5101 21820 5097 21821 5096 21821 5113 21821 5113 21822 5096 21822 5114 21822 5114 21823 5096 21823 5104 21823 5115 21824 5119 21824 5120 21824 5122 21825 5119 21825 5118 21825 5119 21826 5122 21826 5123 21826 5115 21827 5120 21827 5125 21827 5126 21828 5120 21828 5119 21828 5119 21829 5127 21829 5126 21829 5123 21830 5122 21830 5128 21830 5123 21831 5128 21831 5127 21831 5128 21832 5130 21832 5129 21832 5130 21833 5122 21833 5121 21833 5130 21834 5121 21834 5131 21834 5131 21835 5121 21835 5132 21835 5121 21836 5117 21836 5133 21836 5134 21837 5116 21837 5124 21837 5135 21838 5136 21838 5137 21838 5138 21839 5135 21839 5137 21839 5139 21840 5135 21840 5138 21840 5135 21841 5139 21841 5140 21841 5142 21842 5138 21842 5141 21842 5139 21843 5142 21843 5143 21843 5136 21844 5135 21844 5144 21844 5143 21845 5147 21845 5139 21845 5139 21846 5147 21846 5146 21846 5143 21847 5148 21847 5147 21847 5142 21848 5150 21848 5148 21848 5141 21849 5154 21849 5152 21849 5141 21850 5137 21850 5153 21850 5153 21851 5136 21851 5154 21851 5154 21852 5136 21852 5144 21852 5158 21853 5155 21853 5157 21853 5159 21854 5155 21854 5158 21854 5155 21855 5159 21855 5160 21855 5162 21856 5158 21856 5161 21856 5159 21857 5162 21857 5163 21857 5156 21858 5155 21858 5164 21858 5164 21859 5155 21859 5165 21859 5165 21860 5160 21860 5166 21860 5166 21861 5160 21861 5159 21861 5163 21862 5167 21862 5159 21862 5167 21863 5168 21863 5169 21863 5170 21864 5162 21864 5161 21864 5170 21865 5161 21865 5171 21865 5171 21866 5161 21866 5172 21866 5161 21867 5174 21867 5172 21867 5161 21868 5157 21868 5173 21868 5157 21869 5156 21869 5173 21869 5174 21870 5156 21870 5164 21870 5178 21871 5175 21871 5177 21871 5179 21872 5175 21872 5178 21872 5177 21873 5181 21873 5178 21873 5179 21874 5182 21874 5183 21874 5183 21875 5188 21875 5187 21875 5187 21876 5188 21876 5189 21876 5188 21877 5190 21877 5189 21877 5189 21878 5190 21878 5191 21878 5190 21879 5182 21879 5181 21879 5190 21880 5181 21880 5191 21880 5193 21881 5194 21881 5181 21881 5181 21882 5194 21882 5192 21882 5181 21883 5177 21883 5193 21883 5177 21884 5176 21884 5193 21884 5193 21885 5176 21885 5194 21885 5194 21886 5176 21886 5184 21886 5198 21887 5195 21887 5197 21887 5199 21888 5195 21888 5198 21888 5197 21889 5201 21889 5198 21889 5202 21890 5199 21890 5198 21890 5204 21891 5195 21891 5205 21891 5195 21892 5200 21892 5205 21892 5206 21893 5200 21893 5199 21893 5199 21894 5207 21894 5206 21894 5207 21895 5208 21895 5209 21895 5202 21896 5210 21896 5208 21896 5210 21897 5202 21897 5201 21897 5211 21898 5201 21898 5212 21898 5213 21899 5214 21899 5201 21899 5201 21900 5197 21900 5213 21900 5197 21901 5196 21901 5213 21901 5214 21902 5196 21902 5204 21902 5215 21903 5216 21903 5217 21903 5215 21904 5217 21904 5219 21904 5215 21905 5218 21905 4429 21905 5224 21906 5218 21906 5219 21906 5218 21907 5224 21907 5223 21907 5223 21908 5224 21908 5225 21908 5221 21909 5220 21909 5226 21909 5226 21910 5220 21910 5227 21910 5220 21911 5228 21911 5227 21911 5227 21912 5228 21912 5229 21912 5232 21913 5231 21913 5015 21913 5015 21914 5231 21914 4427 21914 5235 21915 5231 21915 5234 21915 5231 21916 5235 21916 5236 21916 5235 21917 5239 21917 5240 21917 4427 21918 5231 21918 5236 21918 5240 21919 5241 21919 5235 21919 5239 21920 5244 21920 5242 21920 5243 21921 5244 21921 5245 21921 5246 21922 5011 21922 5238 21922 5238 21923 5233 21923 5246 21923 4127 21924 4128 21924 4434 21924 4126 21925 5010 21925 4125 21925 4128 21926 5247 21926 4434 21926 4357 21927 4071 21927 5249 21927 5250 21928 4072 21928 4494 21928 5252 21929 5251 21929 5253 21929 5254 21930 5251 21930 5255 21930 5256 21931 5255 21931 5257 21931 5257 21932 4489 21932 5256 21932 5256 21933 4489 21933 4488 21933 5261 21934 5260 21934 5258 21934 5265 21935 5264 21935 5263 21935 5265 21936 5266 21936 5264 21936 4474 21937 5265 21937 4475 21937 5267 21938 5263 21938 4481 21938 5267 21939 4481 21939 4480 21939 5270 21940 5269 21940 5271 21940 4453 21941 5272 21941 5274 21941 5269 21942 5268 21942 4463 21942 5269 21943 4463 21943 4462 21943 5264 21944 5269 21944 5270 21944 5276 21945 4449 21945 5277 21945 5278 21946 5247 21946 5002 21946 5002 21947 5003 21947 5278 21947 4422 21948 4336 21948 4113 21948 4426 21949 4113 21949 4114 21949 4426 21950 4115 21950 5016 21950 4115 21951 4133 21951 5016 21951 5015 21952 5012 21952 5281 21952 5243 21953 5245 21953 4431 21953 4431 21954 5245 21954 4432 21954 4439 21955 4432 21955 5245 21955 4131 21956 4819 21956 4129 21956 5282 21957 5283 21957 5284 21957 5284 21958 5285 21958 5282 21958 5284 21959 5286 21959 5285 21959 5288 21960 5286 21960 5289 21960 5290 21961 5289 21961 5291 21961 5292 21962 5291 21962 5293 21962 5294 21963 5293 21963 5295 21963 5296 21964 5295 21964 5297 21964 5017 21965 5297 21965 5298 21965 5016 21966 5298 21966 5014 21966 5006 21967 5010 21967 5007 21967 5004 21968 5007 21968 5299 21968 5283 21969 5004 21969 5284 21969 5017 21970 5300 21970 5297 21970 5300 21971 5296 21971 5297 21971 5301 21972 5302 21972 5295 21972 5302 21973 5303 21973 5295 21973 5303 21974 5294 21974 5295 21974 5294 21975 5304 21975 5293 21975 5304 21976 5305 21976 5293 21976 5306 21977 5290 21977 5291 21977 5290 21978 5288 21978 5289 21978 5308 21979 4801 21979 4803 21979 4801 21980 5308 21980 4799 21980 4796 21981 5310 21981 5311 21981 4791 21982 5311 21982 5312 21982 4791 21983 5312 21983 5313 21983 4784 21984 5313 21984 5314 21984 4782 21985 5314 21985 5315 21985 4796 21986 5311 21986 4793 21986 4793 21987 5311 21987 4791 21987 4784 21988 5314 21988 4782 21988 4781 21989 5315 21989 4780 21989 4780 21990 5316 21990 4778 21990 5303 21991 4778 21991 5317 21991 5304 21992 5318 21992 5319 21992 5320 21993 5306 21993 5292 21993 5290 21994 5322 21994 5323 21994 5288 21995 5323 21995 5324 21995 5324 21996 5307 21996 5288 21996 5287 21997 5327 21997 5285 21997 5285 21998 5327 21998 5328 21998 4807 21999 5328 21999 4805 21999 4807 22000 5283 22000 5282 22000 4807 22001 4808 22001 5283 22001 5303 22002 5317 22002 5294 22002 5305 22003 5320 22003 5292 22003 5285 22004 5328 22004 5282 22004 5309 22005 4803 22005 4805 22005 5300 22006 5329 22006 5296 22006 5302 22007 5301 22007 4777 22007 4876 22008 5295 22008 4822 22008 4876 22009 4874 22009 5297 22009 5297 22010 4872 22010 4870 22010 5298 22011 4870 22011 4868 22011 5013 22012 5014 22012 4864 22012 5297 22013 4870 22013 5298 22013 5298 22014 4866 22014 5014 22014 5013 22015 4863 22015 5010 22015 5010 22016 4863 22016 4862 22016 5007 22017 4860 22017 4858 22017 5284 22018 4852 22018 4850 22018 5286 22019 4844 22019 4842 22019 5289 22020 4840 22020 4838 22020 5291 22021 4838 22021 4836 22021 5010 22022 4860 22022 5007 22022 5007 22023 4856 22023 5299 22023 5299 22024 4852 22024 5284 22024 5286 22025 4842 22025 5289 22025 4836 22026 4834 22026 5291 22026 5293 22027 4830 22027 4828 22027 5293 22028 4828 22028 4826 22028 5295 22029 4824 22029 4820 22029 5295 22030 4820 22030 4822 22030 5293 22031 4826 22031 5295 22031 5008 22032 4146 22032 5003 22032 4146 22033 5008 22033 5009 22033 5283 22034 4808 22034 5009 22034 5278 22035 4060 22035 5330 22035 5272 22036 5330 22036 5331 22036 5270 22037 5331 22037 5332 22037 5259 22038 5333 22038 5334 22038 5254 22039 5334 22039 5335 22039 5249 22040 5335 22040 5336 22040 5248 22041 5249 22041 5336 22041 5003 22042 4060 22042 5278 22042 5259 22043 5334 22043 5254 22043 5254 22044 5335 22044 5249 22044 4146 22045 5009 22045 4808 22045 4146 22046 4808 22046 4810 22046 4819 22047 4333 22047 4129 22047 4819 22048 5329 22048 4333 22048 4819 22049 5338 22049 5329 22049 5338 22050 5296 22050 5329 22050 3951 22051 4333 22051 4328 22051 3959 22052 4328 22052 4326 22052 3969 22053 4326 22053 4322 22053 3975 22054 4322 22054 4317 22054 3980 22055 4317 22055 4313 22055 3975 22056 4317 22056 3980 22056 5329 22057 5339 22057 4333 22057 5339 22058 4133 22058 4134 22058 5340 22059 5339 22059 5329 22059 4060 22060 3953 22060 5341 22060 5330 22061 5341 22061 5331 22061 5330 22062 4060 22062 5341 22062 5341 22063 3955 22063 5342 22063 5341 22064 5344 22064 5345 22064 5331 22065 5345 22065 5346 22065 5344 22066 5347 22066 5345 22066 5331 22067 5346 22067 5348 22067 5349 22068 5331 22068 5348 22068 5349 22069 5350 22069 5331 22069 5332 22070 5331 22070 5351 22070 5350 22071 5352 22071 5351 22071 5355 22072 5356 22072 5333 22072 5357 22073 5358 22073 5333 22073 5360 22074 5361 22074 5334 22074 5359 22075 5360 22075 5334 22075 5334 22076 5362 22076 5335 22076 5334 22077 5361 22077 5362 22077 5335 22078 5364 22078 5336 22078 5337 22079 5366 22079 5368 22079 5369 22080 5337 22080 5368 22080 5337 22081 5369 22081 5370 22081 5371 22082 5267 22082 4480 22082 5356 22083 5372 22083 5267 22083 5372 22084 5355 22084 5373 22084 5354 22085 5374 22085 5375 22085 5352 22086 5350 22086 5376 22086 5378 22087 5350 22087 4459 22087 4459 22088 5350 22088 5379 22088 5349 22089 5348 22089 5380 22089 5346 22090 5382 22090 5383 22090 5382 22091 4447 22091 5383 22091 5346 22092 5345 22092 5382 22092 5347 22093 5385 22093 5384 22093 5347 22094 5384 22094 5345 22094 5344 22095 5343 22095 5386 22095 5386 22096 5343 22096 5387 22096 5342 22097 5389 22097 5390 22097 5389 22098 4449 22098 5390 22098 5279 22099 3955 22099 5392 22099 4058 22100 4055 22100 3953 22100 3954 22101 4055 22101 5393 22101 4057 22102 5395 22102 5394 22102 4057 22103 5399 22103 5398 22103 4057 22104 5400 22104 5399 22104 4057 22105 5401 22105 5400 22105 4057 22106 5402 22106 5401 22106 4057 22107 5403 22107 5402 22107 4057 22108 5404 22108 5403 22108 4057 22109 5405 22109 5404 22109 4057 22110 5406 22110 5405 22110 5407 22111 5406 22111 5366 22111 5409 22112 5408 22112 5367 22112 5409 22113 5367 22113 5364 22113 5401 22114 5410 22114 5411 22114 5411 22115 5412 22115 5362 22115 5415 22116 5414 22116 5361 22116 5361 22117 5360 22117 5415 22117 5397 53 5398 53 5416 53 5416 22118 5418 22118 5417 22118 5417 22119 5418 22119 5358 22119 5356 22120 5419 22120 5357 22120 5371 22121 5419 22121 5356 22121 4055 22122 5394 22122 5420 22122 5377 22123 5421 22123 5423 22123 5352 22124 5377 22124 5423 22124 5424 22125 5425 22125 5420 22125 5425 22126 5424 22126 5373 22126 5422 22127 5426 22127 4055 22127 4055 22128 5426 22128 5427 22128 5428 22129 4055 22129 5427 22129 5428 22130 5429 22130 4055 22130 5429 22131 5428 22131 5430 22131 5427 22132 5426 22132 5379 22132 5350 22133 5349 22133 5431 22133 5427 22134 5379 22134 5431 22134 5429 22135 5430 22135 5383 22135 5383 22136 5348 22136 5346 22136 4055 22137 5432 22137 5433 22137 5434 22138 4055 22138 5433 22138 5434 22139 5435 22139 4055 22139 5435 22140 5434 22140 5436 22140 5390 22141 5436 22141 5343 22141 5390 22142 5343 22142 5342 22142 5433 53 5432 53 5437 53 5438 22143 5437 22143 5347 22143 5433 22144 5437 22144 5438 22144 5438 22145 5347 22145 5344 22145 5435 22146 5393 22146 4055 22146 3996 22147 5440 22147 5439 22147 3979 22148 4024 22148 5441 22148 5442 22149 3995 22149 5443 22149 3994 22150 4347 22150 4023 22150 5444 22151 3982 22151 5445 22151 3984 22152 4349 22152 5445 22152 5447 22153 3987 22153 5448 22153 3985 22154 5449 22154 4035 22154 4044 22155 4315 22155 5450 22155 3986 22156 3990 22156 5451 22156 5451 22157 3990 22157 4310 22157 3988 22158 5452 22158 4041 22158 3988 22159 3989 22159 5452 22159 5452 22160 3989 22160 5453 22160 5453 22161 3989 22161 4353 22161 5458 22162 5457 22162 5459 22162 4219 22163 5461 22163 4218 22163 3993 22164 5460 22164 4048 22164 3993 22165 5458 22165 5460 22165 3966 22166 4301 22166 3968 22166 3968 22167 4301 22167 5462 22167 5454 22168 5463 22168 5455 22168 5467 22169 4230 22169 4232 22169 5468 22170 5467 22170 4232 22170 5465 22171 4229 22171 5466 22171 5468 22172 5370 22172 5467 22172 5406 22173 5464 22173 5465 22173 5466 22174 5368 22174 5465 22174 4223 22175 4231 22175 5464 22175 4753 22176 5464 22176 5000 22176 4753 22177 4246 22177 4223 22177 4223 22178 4246 22178 4221 22178 4221 22179 4246 22179 4222 22179 5464 22180 5406 22180 5000 22180 5000 22181 5406 22181 4057 22181 4054 22182 5000 22182 4057 22182 4252 22183 4251 22183 4279 22183 5470 22184 4213 22184 4217 22184 4217 22185 4218 22185 5471 22185 5471 22186 4218 22186 5461 22186 5459 22187 5471 22187 5461 22187 5459 53 5472 53 5471 53 5459 22188 5457 22188 5472 22188 5473 53 5475 53 5474 53 5476 22189 5477 22189 4278 22189 4248 22190 5478 22190 4279 22190 4248 22191 5469 22191 5479 22191 5479 22192 5469 22192 4261 22192 5476 53 4278 53 5478 53 4263 22193 4216 22193 4215 22193 3999 22194 5481 22194 4152 22194 4745 22195 5481 22195 4754 22195 4735 22196 4729 22196 5481 22196 4737 22197 4735 22197 5481 22197 4727 22198 4721 22198 5481 22198 4719 22199 4713 22199 5481 22199 4711 22200 4705 22200 5481 22200 4713 22201 4711 22201 5481 22201 4705 22202 4703 22202 5481 22202 4695 22203 4689 22203 4152 22203 5481 22204 4695 22204 4152 22204 4681 22205 4679 22205 4152 22205 4646 22206 4642 22206 4152 22206 4643 22207 4151 22207 4152 22207 4642 22208 4643 22208 4152 22208 4754 22209 5481 22209 4756 22209 4756 22210 5481 22210 5001 22210 4737 22211 4741 22211 4739 22211 5015 22212 5281 22212 5232 22212 5309 22213 5482 22213 5483 22213 5309 22214 5483 22214 5308 22214 5308 22215 5483 22215 5484 22215 5310 22216 5485 22216 5486 22216 5487 22217 5310 22217 5486 22217 5487 22218 5311 22218 5310 22218 5489 22219 5313 22219 5312 22219 5489 22220 5490 22220 5313 22220 5491 22221 5492 22221 5315 22221 5315 22222 5492 22222 5493 22222 5316 22223 5493 22223 5494 22223 5311 22224 5488 22224 5312 22224 5313 22225 5490 22225 5314 22225 5317 22226 4778 22226 5496 22226 5318 22227 5317 22227 5497 22227 5499 22228 5319 22228 5498 22228 5319 22229 5500 22229 5320 22229 5322 22230 5321 22230 5503 22230 5504 22231 5505 22231 5506 22231 5504 22232 5517 22232 5505 22232 5518 22233 5514 22233 5515 22233 5520 22234 5519 22234 5513 22234 5509 22235 5508 22235 5520 22235 5521 22236 5508 22236 5506 22236 5521 22237 5506 22237 5505 22237 5522 22238 5517 22238 5523 22238 5485 22239 5518 22239 5524 22239 5524 22240 5518 22240 5515 22240 5516 22241 5518 22241 5485 22241 5514 22242 5518 22242 5516 22242 5525 22243 5509 22243 5512 22243 5523 22244 5517 22244 5526 22244 5526 22245 5517 22245 5504 22245 5529 22246 5532 22246 5527 22246 5532 22247 5529 22247 5530 22247 5533 22248 5532 22248 5530 22248 5523 22249 5534 22249 5535 22249 5536 22250 5538 22250 5539 22250 5532 22251 5539 22251 5540 22251 5535 22252 5540 22252 5537 22252 5540 22253 5539 22253 5537 22253 5482 22254 5542 22254 5483 22254 5483 22255 5543 22255 5484 22255 5501 22256 5536 22256 5502 22256 5500 22257 5522 22257 5534 22257 5500 22258 5499 22258 5522 22258 5522 22259 5491 22259 5517 22259 5517 22260 5490 22260 5505 22260 5499 22261 5498 22261 5492 22261 5493 22262 5498 22262 5497 22262 5316 22263 5496 22263 5495 22263 5316 22264 5494 22264 5496 22264 5492 22265 5498 22265 5493 22265 5490 22266 5521 22266 5505 22266 5490 22267 5489 22267 5521 22267 5487 22268 5486 22268 5519 22268 5519 22269 5486 22269 5524 22269 5541 22270 5522 22270 5523 22270 5523 22271 5526 22271 5540 22271 5547 22272 5502 22272 5536 22272 5542 22273 5326 22273 5543 22273 5543 22274 5326 22274 5325 22274 5544 22275 5325 22275 5324 22275 5544 22276 5324 22276 5545 22276 5545 22277 5324 22277 5323 22277 5546 22278 5323 22278 5322 22278 5549 22279 4293 22279 5548 22279 5551 22280 5552 22280 5553 22280 5553 22281 5552 22281 5554 22281 5556 6 5555 6 5557 6 5558 22282 5559 22282 5556 22282 5555 6 5560 6 5557 6 5557 22283 5560 22283 5561 22283 5563 6 5562 6 5564 6 5565 22284 5564 22284 5566 22284 5567 22285 5566 22285 5568 22285 5568 22286 5569 22286 5567 22286 5569 6 5570 6 5571 6 5573 22287 5572 22287 5574 22287 5575 22288 5574 22288 5576 22288 5577 22289 5576 22289 5578 22289 5280 22290 5578 22290 4302 22290 5280 22291 5580 22291 5579 22291 5580 22292 5550 22292 5549 22292 5581 22293 5582 22293 5583 22293 5581 6 5584 6 5582 6 5582 22294 5584 22294 5585 22294 5586 6 5587 6 5582 6 5586 22295 5589 22295 5588 22295 5585 22296 5584 22296 5551 22296 5590 22297 5569 22297 5571 22297 5567 6 5565 6 5566 6 5573 6 5566 6 5572 6 5571 22298 5570 22298 5549 22298 5577 6 5575 6 5576 6 5548 22299 5591 22299 5549 22299 5549 22300 5591 22300 5571 22300 4300 22301 5586 22301 5462 22301 5463 22302 5586 22302 5585 22302 5590 22303 5593 22303 5594 22303 5571 22304 5591 22304 5590 22304 5594 22305 4276 22305 5559 22305 5559 22306 4276 22306 5556 22306 4277 22307 5556 22307 4276 22307 5596 22308 5554 22308 4277 22308 5596 22309 5553 22309 5554 22309 5596 22310 5597 22310 5553 22310 5595 22311 5553 22311 5597 22311 5594 22312 4236 22312 4276 22312 5594 22313 4234 22313 4236 22313 4234 22314 5593 22314 4240 22314 4240 22315 5593 22315 5592 22315 4232 22316 5592 22316 5591 22316 4232 22317 4240 22317 5592 22317 5468 22318 5591 22318 5370 22318 5370 22319 5548 22319 5248 22319 5337 22320 5370 22320 5248 22320 4277 22321 4278 22321 5477 22321 5597 22322 5475 22322 5473 22322 4277 22323 5477 22323 5596 22323 5596 22324 5475 22324 5597 22324 5598 22325 5599 22325 4224 22325 4235 22326 5602 22326 5603 22326 4237 22327 5603 22327 5604 22327 4225 22328 5604 22328 5605 22328 4224 22329 4225 22329 5598 22329 4226 22330 5600 22330 4228 22330 4228 22331 5601 22331 4233 22331 4233 22332 5602 22332 4235 22332 4235 22333 5603 22333 4237 22333 4237 22334 5604 22334 4225 22334 5606 22335 5598 22335 5607 22335 5599 22336 5606 22336 5600 22336 5600 22337 5606 22337 5608 22337 5602 22338 5609 22338 5610 22338 5602 22339 5610 22339 5611 22339 5604 22340 5612 22340 5607 22340 5613 22341 5471 22341 5472 22341 5613 22342 5614 22342 5471 22342 5470 22343 5615 22343 5616 22343 5479 22344 5616 22344 5617 22344 5479 22345 5617 22345 5618 22345 5474 22346 5619 22346 5620 22346 5470 22347 5616 22347 5480 22347 5476 22348 5619 22348 5474 22348 5474 22349 5620 22349 5472 22349 5621 22350 5613 22350 5622 22350 5614 22351 5621 22351 5615 22351 5616 22352 5623 22352 5624 22352 5617 22353 5624 22353 5625 22353 5618 22354 5625 22354 5626 22354 5615 22355 5623 22355 5616 22355 5617 22356 5625 22356 5618 22356 5618 22357 5627 22357 5619 22357 5628 22358 5582 22358 5629 22358 5582 22359 5628 22359 5583 22359 5572 22360 5630 22360 5631 22360 5574 22361 5631 22361 5632 22361 5576 22362 5632 22362 5633 22362 5588 22363 5634 22363 5635 22363 5582 22364 5587 22364 5629 22364 5583 22365 5630 22365 5572 22365 5574 22366 5632 22366 5576 22366 5576 22367 5633 22367 5578 22367 5632 22368 5631 22368 5634 22368 5635 22369 5634 22369 5628 22369 5629 22370 5635 22370 5628 22370 5632 22371 5634 22371 5633 22371 5636 22372 5637 22372 5566 22372 5566 22373 5637 22373 5568 22373 5568 22374 5637 22374 5638 22374 5579 22375 5640 22375 5641 22375 5575 22376 5642 22376 5636 22376 5573 22377 5575 22377 5636 22377 5568 22378 5638 22378 5570 22378 5570 22379 5639 22379 5580 22379 5580 22380 5640 22380 5579 22380 5577 22381 5641 22381 5575 22381 5638 22382 5637 22382 5643 22382 5639 22383 5643 22383 5640 22383 5644 22384 5645 22384 5557 22384 5558 22385 5645 22385 5646 22385 5590 22386 5646 22386 5647 22386 5569 22387 5647 22387 5648 22387 5559 22388 5646 22388 5590 22388 5590 22389 5647 22389 5569 22389 5569 22390 5648 22390 5567 22390 5645 22391 5652 22391 5646 22391 5646 22392 5652 22392 5653 22392 5647 22393 5653 22393 5654 22393 5648 22394 5655 22394 5656 22394 5644 22395 5650 22395 5651 22395 5646 22396 5653 22396 5647 22396 5647 22397 5654 22397 5648 22397 5658 22398 5551 22398 5659 22398 5658 22399 5552 22399 5551 22399 5560 22400 5660 22400 5661 22400 5581 22401 5662 22401 5663 22401 5581 22402 5663 22402 5664 22402 5584 22403 5664 22403 5659 22403 5562 22404 5662 22404 5564 22404 5564 22405 5662 22405 5581 22405 5665 22406 5666 22406 5658 22406 5658 22407 5666 22407 5660 22407 5661 22408 5667 22408 5668 22408 5662 22409 5669 22409 5670 22409 5664 22410 5670 22410 5671 22410 5659 22411 5665 22411 5658 22411 5662 22412 5670 22412 5663 22412 5634 22413 5672 22413 5628 22413 5631 22414 5628 22414 5672 22414 5622 22415 5627 22415 5673 22415 5666 22416 5673 22416 5627 22416 5674 22417 5665 22417 5671 22417 5676 22418 5669 22418 5668 22418 5627 22419 5626 22419 5677 22419 5667 22420 5677 22420 5626 22420 5667 22421 5626 22421 5668 22421 5625 22422 5624 22422 5676 22422 5674 22423 5621 22423 5622 22423 5665 22424 5674 22424 5622 22424 5669 22425 5623 22425 5670 22425 5671 22426 5675 22426 5621 22426 5607 22427 5678 22427 5651 22427 5652 22428 5678 22428 5612 22428 5652 22429 5651 22429 5678 22429 5679 22430 5651 22430 5657 22430 5681 22431 5655 22431 5654 22431 5612 22432 5682 22432 5652 22432 5653 22433 5682 22433 5611 22433 5654 22434 5610 22434 5681 22434 5610 22435 5609 22435 5681 22435 5655 22436 5609 22436 5608 22436 5680 22437 5608 22437 5606 22437 5679 22438 5606 22438 5607 22438 5655 22439 5608 22439 5656 22439 5657 22440 5606 22440 5679 22440 5385 22441 5347 22441 5683 22441 5683 22442 5437 22442 5432 22442 5432 22443 5429 22443 5683 22443 5683 22444 5429 22444 5684 22444 5685 22445 3973 22445 5686 22445 5686 22446 3973 22446 4000 22446 4000 22447 3952 22447 5686 22447 5686 22448 3952 22448 5687 22448 5688 22449 3978 22449 4015 22449 5689 22450 5688 22450 4015 22450 5689 22451 4015 22451 4008 22451 4008 22452 4003 22452 5689 22452 4475 22453 5373 22453 5424 22453 4475 22454 5424 22454 5394 22454 5691 22455 4475 22455 5394 22455 4487 22456 5416 22456 5398 22456 5694 22457 5399 22457 5413 22457 5257 22458 5412 22458 4489 22458 4489 22459 5410 22459 5402 22459 5402 22460 5403 22460 5695 22460 5695 22461 5403 22461 5696 22461 4027 22462 4020 22462 5446 22462 5697 22463 4020 22463 4021 22463 5698 22464 4040 22464 5699 22464 4038 22465 4037 22465 5699 22465 5699 22466 4037 22466 5700 22466 4353 22467 4053 22467 5701 22467 5701 22468 4050 22468 4045 22468 4045 22469 4039 22469 5701 22469 4352 22470 5702 22470 4039 22470 5703 22471 4044 22471 4042 22471 5705 22472 4046 22472 4051 22472 5708 22473 3991 22473 4306 22473 5448 22474 4034 22474 4390 22474 5709 22475 4011 22475 5710 22475 5710 22476 4011 22476 4012 22476 5710 22477 4012 22477 4324 22477 5425 22478 5375 22478 4474 22478 5357 22479 5711 22479 5358 22479 5711 22480 5419 22480 4481 22480 5361 22481 5414 22481 5713 22481 5717 22482 5365 22482 5367 22482 5367 22483 5408 22483 5717 22483 5717 22484 5408 22484 5718 22484 4078 22485 5719 22485 4074 22485 4078 22486 4080 22486 5719 22486 5719 22487 4080 22487 5720 22487 4080 22488 4081 22488 5720 22488 5720 22489 4081 22489 5721 22489 3938 22490 3932 22490 4332 22490 3971 22491 5722 22491 3970 22491 3970 22492 5722 22492 5723 22492 5725 22493 4013 22493 4010 22493 5726 22494 4013 22494 5725 22494 4010 22495 4009 22495 5725 22495 5727 22496 4009 22496 4016 22496 3974 22497 5729 22497 4016 22497 5730 22498 5422 22498 5377 22498 5730 22499 5377 22499 4462 22499 4458 22500 5733 22500 5431 22500 5732 22501 5431 22501 5733 22501 5734 22502 5433 22502 5438 22502 5344 22503 5386 22503 5438 22503 5438 22504 5386 22504 4452 22504 4449 22505 5435 22505 5390 22505 3946 22506 3947 22506 4435 22506 4435 22507 4434 22507 3945 22507 4435 22508 3945 22508 3946 22508 5278 22509 3957 22509 5247 22509 3948 22510 5278 22510 5279 22510 5736 22511 5279 22511 5278 22511 5279 22512 5736 22512 5391 22512 5278 22513 5277 22513 5736 22513 5736 22514 5277 22514 5389 22514 5277 22515 4449 22515 5389 22515 4435 22516 4440 22516 5737 22516 5737 22517 4441 22517 4435 22517 4449 22518 4441 22518 5735 22518 5737 22519 5435 22519 5735 22519 4440 22520 3954 22520 5393 22520 5737 22521 4440 22521 5393 22521 5734 22522 4452 22522 4443 22522 4449 22523 5276 22523 4450 22523 5388 22524 5276 22524 5387 22524 5386 22525 5387 22525 5276 22525 5386 22526 5276 22526 5272 22526 5272 22527 4453 22527 5386 22527 5386 22528 4453 22528 4452 22528 4443 22529 4441 22529 5738 22529 4443 22530 5738 22530 5734 22530 5434 22531 5433 22531 5738 22531 5738 22532 5433 22532 5734 22532 5388 22533 5436 22533 4450 22533 4450 22534 5436 22534 5738 22534 4443 22535 4453 22535 5683 22535 4447 22536 4444 22536 5684 22536 5683 22537 4453 22537 5385 22537 5275 22538 5274 22538 5273 22538 4447 22539 5429 22539 5383 22539 5733 22540 4458 22540 4455 22540 5273 22541 5270 22541 5380 22541 4455 22542 4459 22542 5739 22542 5739 22543 5730 22543 4461 22543 4462 22544 4461 22544 5730 22544 5271 22545 5378 22545 4459 22545 5376 22546 5378 22546 5269 22546 5378 22547 5271 22547 5269 22547 4462 22548 5376 22548 5269 22548 5426 22549 5422 22549 5739 22549 5739 22550 5422 22550 5730 22550 5739 22551 5379 22551 5426 22551 3936 22552 3938 22552 4330 22552 3936 22553 4330 22553 4335 22553 4425 22554 3934 22554 3933 22554 4425 22555 3933 22555 3937 22555 4414 22556 4338 22556 5686 22556 5686 22557 5687 22557 4416 22557 5686 22558 4416 22558 4414 22558 5741 22559 4416 22559 5687 22559 4331 22560 5741 22560 5742 22560 5687 22561 3952 22561 5741 22561 5743 22562 4420 22562 4414 22562 4414 22563 4412 22563 5744 22563 4414 22564 5744 22564 5743 22564 4339 22565 5724 22565 5744 22565 4339 22566 4326 22566 5722 22566 4339 22567 5722 22567 5724 22567 4326 22568 4329 22568 5722 22568 4329 22569 4338 22569 5723 22569 3970 22570 5723 22570 4007 22570 5688 22571 5689 22571 4342 22571 5689 22572 4412 22572 4342 22572 4342 22573 4341 22573 5688 22573 4340 22574 4327 22574 5746 22574 4339 22575 5746 22575 4327 22575 5746 22576 4339 22576 5745 22576 5690 22577 4004 22577 5745 22577 4325 22578 4323 22578 5726 22578 5747 22579 4323 22579 5729 22579 4340 22580 4343 22580 5729 22580 4407 22581 5728 22581 4343 22581 4325 22582 5725 22582 4402 22582 4469 22583 5749 22583 5748 22583 5749 22584 4461 22584 4463 22584 5375 22585 5374 22585 5268 22585 5268 22586 5266 22586 5375 22586 5375 22587 5266 22587 4474 22587 5748 22588 5420 22588 5425 22588 5267 22589 5265 22589 5263 22589 5372 22590 5265 22590 5267 22590 5692 22591 5371 22591 4480 22591 5750 22592 5751 22592 4486 22592 4478 22593 5752 22593 5750 22593 4481 22594 5263 22594 5711 22594 5260 22595 4486 22595 5712 22595 5751 22596 5712 22596 4486 22596 5417 22597 5712 22597 5751 22597 5750 22598 5417 22598 5751 22598 5693 22599 4384 22599 4478 22599 5262 22600 4384 22600 5694 22600 4486 22601 5753 22601 4487 22601 4486 22602 5260 22602 5753 22602 5261 22603 5753 22603 5260 22603 5755 22604 5261 22604 5262 22604 5694 22605 5413 22605 5415 22605 5755 22606 5694 22606 5415 22606 5756 22607 4384 22607 5757 22607 5262 22608 5258 22608 5713 22608 4488 22609 5758 22609 5256 22609 5411 22610 5714 22610 5758 22610 4488 22611 5401 22611 5411 22611 5758 22612 4488 22612 5411 22612 5759 22613 5255 22613 5760 22613 5760 22614 5255 22614 5251 22614 5760 22615 5252 22615 5409 22615 4385 22616 4489 22616 5695 22616 5253 22617 4491 22617 5696 22617 5696 22618 5403 22618 5409 22618 5252 22619 5696 22619 5409 22619 4399 22620 4345 22620 5709 22620 4325 22621 5710 22621 4324 22621 4321 22622 4323 22622 5761 22622 5439 22623 5440 22623 5761 22623 4345 22624 4024 22624 4017 22624 5709 22625 4345 22625 4017 22625 5762 22626 4346 22626 4345 22626 5763 22627 4394 22627 4348 22627 3981 22628 5442 22628 4025 22628 5762 22629 4018 22629 4025 22629 5762 22630 4025 22630 4346 22630 4347 22631 4394 22631 5697 22631 5764 22632 5765 22632 4350 22632 5766 22633 4388 22633 4390 22633 5764 22634 4028 22634 4030 22634 5764 22635 4030 22635 5765 22635 5700 22636 5767 22636 4376 22636 4311 22637 4310 22637 4351 22637 4351 22638 4310 22638 5698 22638 5451 22639 4310 22639 4312 22639 5700 22640 4376 22640 5699 22640 5699 22641 4376 22641 4351 22641 4351 22642 5698 22642 5699 22642 4354 22643 5701 22643 4371 22643 4354 22644 4353 22644 5701 22644 4352 22645 4371 22645 5702 22645 4352 22646 4039 22646 4041 22646 4311 22647 4352 22647 4041 22647 5769 22648 4494 22648 4358 22648 4358 22649 4491 22649 5770 22649 5253 22650 5718 22650 5770 22650 5770 22651 4491 22651 5253 22651 5253 22652 5717 22652 5718 22652 5251 22653 5250 22653 5717 22653 4494 22654 5716 22654 5250 22654 4494 22655 5405 22655 5407 22655 5769 22656 5405 22656 4494 22656 4306 22657 4307 22657 5708 22657 4307 22658 4354 22658 5708 22658 5772 22659 4046 22659 5705 22659 5771 22660 4049 22660 4047 22660 5771 22661 4047 22661 5772 22661 4312 22662 4314 22662 5450 22662 5449 22663 5450 22663 4314 22663 4376 22664 4316 22664 5703 22664 5703 22665 4388 22665 4376 22665 4389 22666 5704 22666 4035 22666 4088 22667 4367 22667 4086 22667 4088 22668 4089 22668 4367 22668 4363 22669 5719 22669 4362 22669 5037 22670 4499 22670 4497 22670 4499 22671 4498 22671 4497 22671 5039 22672 5029 22672 4365 22672 5039 22673 4365 22673 4370 22673 4366 22674 5028 22674 5030 22674 5034 22675 5035 22675 4497 22675 5054 22676 4387 22676 5052 22676 5057 22677 4498 22677 4369 22677 4498 22678 5044 22678 5045 22678 4496 22679 5050 22679 4490 22679 5050 22680 4386 22680 4490 22680 5051 22681 5052 22681 4387 22681 5051 22682 4387 22682 4386 22682 5066 22683 5067 22683 4377 22683 5067 22684 4373 22684 4377 22684 5069 22685 5070 22685 4374 22685 4374 22686 5071 22686 4501 22686 4501 22687 5071 22687 4383 22687 5071 22688 5073 22688 4383 22688 5073 22689 5074 22689 4479 22689 5073 22690 4479 22690 4383 22690 5065 22691 4479 22691 5074 22691 4479 22692 5065 22692 4381 22692 4391 22693 4484 22693 5084 22693 5085 22694 5086 22694 4378 22694 5086 22695 4379 22695 4378 22695 4380 22696 4379 22696 5089 22696 5089 22697 5091 22697 4380 22697 5091 22698 5092 22698 4477 22698 5091 22699 4477 22699 4382 22699 5092 22700 5094 22700 4484 22700 5104 22701 4397 22701 5114 22701 4473 22702 5114 22702 4397 22702 5106 22703 5107 22703 4485 22703 5106 22704 4485 22704 4398 22704 4483 22705 5107 22705 5109 22705 4483 22706 4485 22706 5107 22706 5109 22707 5111 22707 4483 22707 4483 22708 5111 22708 4482 22708 5111 22709 4471 22709 4482 22709 5112 22710 5114 22710 4473 22710 5112 22711 4473 22711 4471 22711 4467 22712 5124 22712 4400 22712 5124 22713 5125 22713 4400 22713 5125 22714 5126 22714 4395 22714 5126 22715 5127 22715 4396 22715 4472 22716 5127 22716 5129 22716 4472 22717 4396 22717 5127 22717 5129 22718 5131 22718 4472 22718 5131 22719 5132 22719 4464 22719 5132 22720 5134 22720 4466 22720 5144 22721 4406 22721 5154 22721 4457 22722 5154 22722 4406 22722 5144 22723 5145 22723 4403 22723 5144 22724 4403 22724 4406 22724 5145 22725 5146 22725 4401 22725 5145 22726 4401 22726 4403 22726 5146 22727 5147 22727 4468 22727 5146 22728 4468 22728 4401 22728 4465 22729 4468 22729 5147 22729 5151 22730 5152 22730 4456 22730 5151 22731 4456 22731 4460 22731 5165 22732 5166 22732 4404 22732 5166 22733 5167 22733 4405 22733 5166 22734 4405 22734 4404 22734 4405 22735 5169 22735 4502 22735 5169 22736 5171 22736 4454 22736 5184 22737 4506 22737 5194 22737 4504 22738 5194 22738 4506 22738 5186 22739 5187 22739 4410 22739 4507 22740 5191 22740 4445 22740 5192 22741 5194 22741 4504 22741 5192 22742 4504 22742 4442 22742 5204 22743 4419 22743 5214 22743 5205 22744 5206 22744 4421 22744 5205 22745 4421 22745 4415 22745 5206 22746 5207 22746 4505 22746 4503 22747 5207 22747 5209 22747 4503 22748 5211 22748 4451 22748 5211 22749 5212 22749 4437 22749 5212 22750 5214 22750 4438 22750 5212 22751 4438 22751 4437 22751 5222 22752 4429 22752 4430 22752 5223 22753 4417 22753 4423 22753 5225 22754 5226 22754 4418 22754 4418 22755 5227 22755 4509 22755 4509 22756 5227 22756 4436 22756 4433 22757 5230 22757 4430 22757 5230 22758 5222 22758 4430 22758 3986 22759 5451 22759 4043 22759 4043 22760 5451 22760 5767 22760 5766 22761 4034 22761 4031 22761 4390 22762 4034 22762 5766 22762 5763 22763 4022 22763 4019 22763 5353 22764 5423 22764 5374 22764 5374 22765 5423 22765 4463 22765 5752 22766 5419 22766 5396 22766 5418 22767 5753 22767 5359 22767 5753 22768 5418 22768 4487 22768 5360 22769 5753 22769 5754 22769 5757 22770 5414 22770 5400 22770 5715 22771 5414 22771 5757 22771 5412 22772 5759 22772 5363 22772 5759 22773 5412 22773 5257 22773 5363 22774 5759 22774 5364 22774 5760 22775 5409 22775 5364 22775 5770 22776 5408 22776 5404 22776 4359 22777 4302 22777 4303 22777 4306 22778 4049 22778 5771 22778 5740 22779 3934 22779 4425 22779 4006 22780 5742 22780 5741 22780 3972 22781 4337 22781 3949 22781 5744 22782 4001 22782 5743 22782 4031 22783 4028 22783 5766 22783 5766 22784 4028 22784 5764 22784 3976 22785 5747 22785 3974 22785 4019 22786 4018 22786 5763 22786 5746 22787 5745 22787 3997 22787 3997 22788 5745 22788 4004 22788 4341 22789 3978 22789 5688 22789 3977 22790 4341 22790 3997 22790 3997 22791 4341 22791 5746 22791 4345 22792 5441 22792 4024 22792 5739 22793 4459 22793 5379 22793 5749 22794 5423 22794 5421 22794 4463 22795 5423 22795 5749 22795 5421 22796 5420 22796 5749 22796 5749 22797 5420 22797 5748 22797 5348 22798 5430 22798 5381 22798 5381 22799 5430 22799 4448 22799 5752 22800 5397 22800 5750 22800 5279 22801 5392 22801 4440 22801 5404 22802 5405 22802 5770 22802 5770 22803 5405 22803 5769 22803 4128 22804 4118 22804 5247 22804 4986 22805 4987 22805 5774 22805 5775 22806 4987 22806 4988 22806 4211 22807 4996 22807 4997 22807 4210 22808 4997 22808 4978 22808 4208 22809 4979 22809 4985 22809 4206 22810 4207 22810 4986 22810 4209 22811 4210 22811 4978 22811 4210 22812 4211 22812 4997 22812 4211 22813 4212 22813 4996 22813 5777 22814 5776 22814 4995 22814 5776 22815 5775 22815 4988 22815 5775 22816 5774 22816 4987 22816 4192 22817 4912 22817 4194 22817 4861 22818 4912 22818 4911 22818 4855 22819 4916 22819 4177 22819 4851 22820 4177 22820 4918 22820 4843 22821 4919 22821 4841 22821 4837 22822 4839 22822 4935 22822 4837 22823 4935 22823 4933 22823 4831 22824 4933 22824 4897 22824 4829 22825 4897 22825 4976 22825 4905 22826 4901 22826 4873 22826 4873 22827 4901 22827 4871 22827 4861 22828 4911 22828 4859 22828 4857 22829 4916 22829 4855 22829 4851 22830 4918 22830 4849 22830 4849 22831 4918 22831 4847 22831 4831 22832 4897 22832 4829 22832 4829 22833 4976 22833 4827 22833 4825 22834 4977 22834 4823 22834 4823 22835 4977 22835 4821 22835 4877 22836 4821 22836 4875 22836 4821 22837 4905 22837 4875 22837 4871 22838 4188 22838 4867 22838 4191 22839 4867 22839 4188 22839 4932 22840 4790 22840 4789 22840 4790 22841 4932 22841 4934 22841 4934 22842 4794 22842 4792 22842 4934 53 4936 53 4794 53 4794 22843 4936 22843 5776 22843 5777 22844 4794 22844 5776 22844 5777 22845 4212 22845 4794 22845 4789 22846 5774 22846 4932 22846 4789 22847 5773 22847 5774 22847 4789 22848 4206 22848 5773 22848 5776 22849 4938 22849 5775 22849 5783 22850 5780 22850 5779 22850 5781 22851 5782 22851 5785 22851 5785 22852 5782 22852 5786 22852 5782 22853 5780 22853 5783 22853 5788 22854 5790 22854 5791 22854 5792 22855 5791 22855 5793 22855 5793 22856 5791 22856 5794 22856 5787 22857 5796 22857 5790 22857 5790 22858 5796 22858 5795 22858 5797 22859 5798 22859 5799 22859 5800 22860 5798 22860 5797 22860 5801 22861 5792 22861 5793 22861 5802 22862 5788 22862 5801 22862 5809 22863 5808 22863 5810 22863 5821 22864 5822 22864 5823 22864 5821 22865 5824 22865 5816 22865 5806 22866 5808 22866 5809 22866 5836 22867 5838 22867 5806 22867 5839 22868 5811 22868 5840 22868 5837 22869 5809 22869 5839 22869 5835 22870 5831 22870 5807 22870 5827 22871 5842 22871 5843 22871 5828 22872 5827 22872 5843 22872 5822 22873 5826 22873 5844 22873 5822 22874 5844 22874 5823 22874 5824 22875 5845 22875 5816 22875 5816 22876 5845 22876 5818 22876 5803 22877 5846 22877 5815 22877 5815 22878 5847 22878 5848 22878 5847 22879 5849 22879 5850 22879 5847 22880 5852 22880 5853 22880 5854 53 5847 53 5853 53 5855 22881 5854 22881 5856 22881 5856 22882 5854 22882 5857 22882 5857 22883 5845 22883 5856 22883 5857 22884 5818 22884 5845 22884 5858 22885 5849 22885 5815 22885 5858 22886 5815 22886 5846 22886 5852 22887 5820 22887 5859 22887 5855 53 5860 53 5847 53 5862 22888 5847 22888 5861 22888 5862 22889 5863 22889 5847 22889 5861 53 5860 53 5867 53 5868 22890 5867 22890 5825 22890 5868 22891 5825 22891 5821 22891 5864 22892 5865 22892 5866 22892 5865 22893 5823 22893 5844 22893 5871 53 5847 53 5870 53 5871 53 5872 53 5847 53 5873 22894 5871 22894 5874 22894 5870 22895 5869 22895 5876 22895 5870 22896 5876 22896 5877 22896 5875 22897 5843 22897 5842 22897 5847 22898 5872 22898 5878 22898 5882 22899 5881 22899 5832 22899 5885 22900 5883 22900 5886 22900 5886 22901 5887 22901 5885 22901 5887 22902 5886 22902 5835 22902 5880 22903 5881 22903 5882 22903 5882 22904 5832 22904 5831 22904 5884 53 5888 53 5878 53 5890 53 5878 53 5889 53 5890 22905 5891 22905 5878 22905 5889 22906 5888 22906 5894 22906 5889 22907 5894 22907 5895 22907 5894 22908 5896 22908 5895 22908 5895 22909 5896 22909 5834 22909 5893 22910 5838 22910 5836 22910 5891 22911 5897 22911 5878 22911 5899 22912 5878 22912 5898 22912 5840 22913 5900 22913 5901 22913 5904 22914 5902 22914 5905 22914 5905 22915 5837 22915 5839 22915 5900 22916 5840 22916 5841 22916 5906 22917 5909 22917 5907 22917 5907 22918 5797 22918 5908 22918 5912 22919 5910 22919 5911 22919 5917 22920 5918 22920 5913 22920 5919 22921 5915 22921 5914 22921 5919 22922 5914 22922 5920 22922 5919 22923 5917 22923 5922 22923 5917 22924 5916 22924 5923 22924 5923 22925 5916 22925 5924 22925 5925 22926 5924 22926 5916 22926 5914 22927 5913 22927 5920 22927 5920 22928 5913 22928 5918 22928 5926 22929 5927 22929 5928 22929 5929 22930 5930 22930 5926 22930 5931 22931 5933 22931 5932 22931 5934 22932 5935 22932 5931 22932 5931 22933 5935 22933 5933 22933 5936 22934 5938 22934 5939 22934 5939 22935 5928 22935 5927 22935 5935 22936 5940 22936 5941 22936 5937 22937 5939 22937 5940 22937 5939 22938 5927 22938 5942 22938 5942 22939 5927 22939 5943 22939 5927 22940 5926 22940 5943 22940 5943 22941 5926 22941 5944 22941 5928 22942 5934 22942 5929 22942 5928 22943 5936 22943 5934 22943 5928 22944 5938 22944 5936 22944 5945 22945 5946 22945 5947 22945 5946 22946 5945 22946 5948 22946 5949 22947 5951 22947 5952 22947 5955 22948 5945 22948 5947 22948 5956 22949 5957 22949 5958 22949 5962 22950 5961 22950 5963 22950 5960 22951 5963 22951 5961 22951 5963 22952 5960 22952 5964 22952 5965 22953 5966 22953 5963 22953 5964 22954 5958 22954 5957 22954 5969 22955 5956 22955 5959 22955 5958 22956 5964 22956 5960 22956 5972 22957 5974 22957 5975 22957 5979 22958 5976 22958 5978 22958 5980 22959 5977 22959 5975 22959 5981 22960 5980 22960 5982 22960 5974 22961 5982 22961 5980 22961 5982 22962 5974 22962 5983 22962 5984 22963 5983 22963 5971 22963 5984 22964 5971 22964 5973 22964 5976 22965 5975 22965 5977 22965 5992 22966 5963 22966 5966 22966 5994 22967 5912 22967 5995 22967 5993 22968 5912 22968 5994 22968 5997 22969 5979 22969 5998 22969 5999 22970 5998 22970 5978 22970 6000 22971 5976 22971 5979 22971 6002 22972 5994 22972 5996 22972 6003 22973 5996 22973 5995 22973 6003 22974 5995 22974 6004 22974 6004 22975 5995 22975 6005 22975 6007 22976 5985 22976 5987 22976 5987 22977 6008 22977 6007 22977 5815 22978 6009 22978 5987 22978 6009 22979 6008 22979 5987 22979 5815 22980 5987 22980 5804 22980 6010 22981 6011 22981 6012 22981 6010 22982 6012 22982 6016 22982 6021 22983 6022 22983 6023 22983 6024 22984 6025 22984 6026 22984 6030 22985 6031 22985 6032 22985 6033 22986 6034 22986 6035 22986 6038 22987 6039 22987 6036 22987 6040 22988 6041 22988 6042 22988 6043 22989 6045 22989 6046 22989 6047 22990 6045 22990 6041 22990 6048 22991 6052 22991 6049 22991 6049 22992 6052 22992 6053 22992 6054 22993 6056 22993 6055 22993 6063 22994 6065 22994 6061 22994 6067 22995 6050 22995 6068 22995 6068 22996 6050 22996 6049 22996 6068 22997 6049 22997 6069 22997 6070 22998 6053 22998 6055 22998 6071 22999 6055 22999 6072 22999 6071 23000 6070 23000 6055 23000 6060 53 6072 53 6055 53 6073 23001 6074 23001 6075 23001 6073 23002 6076 23002 6077 23002 6080 23003 6081 23003 6082 23003 6080 23004 6083 23004 6081 23004 6084 53 6082 53 6085 53 6080 23005 6084 23005 6086 23005 6080 23006 6086 23006 6087 23006 6088 23007 6092 23007 6090 23007 6095 23008 6094 23008 6096 23008 6100 53 6094 53 6095 53 6095 53 6096 53 6099 53 6096 53 6101 53 6098 53 6098 53 6101 53 6102 53 6085 23009 6104 23009 6101 23009 6085 53 6082 53 6104 53 6082 23010 6105 23010 6106 23010 6082 23011 6107 23011 6105 23011 6082 23012 6108 23012 6104 23012 6109 23013 6110 23013 6111 23013 6109 23014 6112 23014 6110 23014 6114 23015 6115 23015 6111 23015 6110 23016 6113 23016 6116 23016 6110 23017 6114 23017 6111 23017 6114 23018 6119 23018 6120 23018 6120 23019 6119 23019 6121 23019 6120 23020 6115 23020 6114 23020 6073 23021 6121 23021 6074 23021 6073 23022 6122 23022 6121 23022 6121 23023 6122 23023 6115 23023 6105 53 6123 53 6125 53 6105 23024 6127 23024 6126 23024 6121 23025 6118 23025 6123 23025 6125 53 6128 53 6106 53 6126 23026 6127 23026 6129 23026 6131 23027 6108 23027 6132 23027 6133 23028 6134 23028 6132 23028 6108 23029 6106 23029 6132 23029 6104 23030 6108 23030 6131 23030 6102 23031 6134 23031 6135 23031 6098 23032 6135 23032 6136 23032 6103 23033 6134 23033 6102 23033 6130 23034 6117 23034 6133 23034 6134 23035 6117 23035 6110 23035 6134 23036 6133 23036 6117 23036 6134 23037 6116 23037 6135 23037 6136 23038 6116 23038 6113 23038 6098 23039 6136 23039 6097 23039 6137 23040 6136 23040 6113 23040 6113 23041 6140 23041 6139 23041 6145 23042 6142 23042 6141 23042 6146 23043 6145 23043 6147 23043 6129 23044 6146 23044 6147 23044 6145 23045 6141 23045 6148 23045 6142 23046 6146 23046 6149 23046 6127 23047 6149 23047 6146 23047 6149 23048 6143 23048 6142 23048 6127 23049 6105 23049 6150 23049 6149 23050 6127 23050 6150 23050 6151 23051 6150 23051 6107 23051 6107 23052 6150 23052 6105 23052 6126 23053 6152 23053 6123 23053 6123 23054 6152 23054 6124 23054 6124 23055 6152 23055 6153 23055 6156 23056 5915 23056 6155 23056 6155 23057 6157 23057 6156 23057 6158 23058 6159 23058 6160 23058 6164 23059 6165 23059 6160 23059 6164 23060 6168 23060 6167 23060 6167 23061 6168 23061 6169 23061 6170 23062 6168 23062 6172 23062 6172 23063 6168 23063 6173 23063 6181 23064 6182 23064 6183 23064 6186 23065 6187 23065 6182 23065 6186 23066 6188 23066 6189 23066 6190 23067 6192 23067 6193 23067 6193 23068 5967 23068 6194 23068 6189 23069 6195 23069 6196 23069 6187 23070 6186 23070 6197 23070 6198 23071 6199 23071 6201 23071 6202 23072 6203 23072 6204 23072 6181 23073 6203 23073 6202 23073 6202 23074 6204 23074 6205 23074 6179 23075 6180 23075 6206 23075 6206 23076 6180 23076 6207 23076 6166 23077 6216 23077 5955 23077 5921 23078 5919 23078 5922 23078 6154 23079 5921 23079 6218 23079 5922 23080 6218 23080 5921 23080 6219 23081 5924 23081 5925 23081 6219 23082 6156 23082 6157 23082 6219 23083 5925 23083 6156 23083 5946 23084 5951 23084 6158 23084 6158 23085 5947 23085 5946 23085 6217 23086 5954 23086 6220 23086 6163 23087 6217 23087 6223 23087 6163 23088 6162 23088 6217 23088 6217 23089 6220 23089 6224 23089 6224 23090 6220 23090 6225 23090 6224 23091 6225 23091 6226 23091 6220 23092 6216 23092 6228 23092 6229 23093 6231 23093 6232 23093 6232 23094 6231 23094 6212 23094 6232 23095 6212 23095 6233 23095 6212 23096 6231 23096 6213 23096 6233 23097 6212 23097 6236 23097 6242 23098 6241 23098 6243 23098 6244 23099 6245 23099 6246 23099 6244 23100 6246 23100 6247 23100 6252 23101 6251 23101 6253 23101 6252 23102 6253 23102 6254 23102 6252 23103 6254 23103 6255 23103 6256 23104 6251 23104 6252 23104 6257 23105 6259 23105 6258 23105 6257 23106 6260 23106 6259 23106 6259 23107 6260 23107 6261 23107 6266 23108 6265 23108 6200 23108 6269 23109 6266 23109 6268 23109 6200 23110 6265 23110 6201 23110 6271 23111 6270 23111 6272 23111 6277 23112 6273 23112 6276 23112 6267 23113 6270 23113 6271 23113 6280 23114 6281 23114 6274 23114 6288 23115 6287 23115 6285 23115 6289 23116 6287 23116 6288 23116 6289 23117 6290 23117 6287 23117 6290 23118 6291 23118 6292 23118 6289 23119 5801 23119 6291 23119 6292 23120 5795 23120 6297 23120 6301 23121 6302 23121 6300 23121 6301 23122 6303 23122 6302 23122 6306 23123 6298 23123 6307 23123 6308 23124 6298 23124 6299 23124 6303 23125 6301 23125 6311 23125 6313 23126 6312 23126 6317 23126 6317 23127 6318 23127 6322 23127 6317 23128 6322 23128 6323 23128 6322 23129 6318 23129 6325 23129 6326 23130 6325 23130 6327 23130 6326 23131 6327 23131 6328 23131 6327 23132 6325 23132 6333 23132 6334 23133 6333 23133 6335 23133 6337 23134 6338 23134 6333 23134 6339 23135 6333 23135 6334 23135 6256 23136 6341 23136 6250 23136 6335 23137 6343 23137 6344 23137 6336 23138 6245 23138 6244 23138 6349 23139 6246 23139 6350 23139 6349 23140 6350 23140 6351 23140 6219 23141 6353 23141 5924 23141 6351 23142 6356 23142 6349 23142 6230 23143 6357 23143 6358 23143 6230 23144 6229 23144 6357 23144 6228 23145 6225 23145 6220 23145 6227 23146 6226 23146 6359 23146 6352 23147 6359 23147 6354 23147 6242 23148 6239 23148 6240 23148 6239 23149 6237 23149 6238 23149 6235 23150 6234 23150 6360 23150 6339 23151 6327 23151 6333 23151 6361 23152 6311 23152 6314 23152 6264 23153 6263 23153 6361 23153 6324 23154 6317 23154 6323 23154 6362 23155 6308 23155 6363 23155 6269 23156 6268 23156 6366 23156 6366 23157 6367 23157 6269 23157 6367 23158 6366 23158 6302 23158 6302 23159 6303 23159 6367 23159 6302 23160 6299 23160 6300 23160 6277 23161 6276 23161 6368 23161 6364 23162 6362 23162 6365 23162 6365 23163 6362 23163 6363 23163 6308 23164 6294 23164 6298 23164 6258 23165 6254 23165 6253 23165 6326 23166 6322 23166 6325 23166 6256 23167 6250 23167 6251 23167 6377 23168 6372 23168 6376 23168 6372 23169 6374 23169 6378 23169 6375 23170 6372 23170 6378 23170 6382 23171 6380 23171 6381 23171 6383 23172 6371 23172 6384 23172 6385 23173 6150 23173 6386 23173 6386 23174 6150 23174 6151 23174 6387 23175 6388 23175 6389 23175 6389 23176 6388 23176 6390 23176 6391 23177 6392 23177 6393 23177 6393 23178 6392 23178 6394 23178 6395 23179 6396 23179 6397 23179 6397 23180 6396 23180 6398 23180 6401 23181 6400 23181 6402 23181 6407 23182 6408 23182 6409 23182 6413 23183 6412 23183 6414 23183 6415 23184 6416 23184 6417 23184 6425 23185 6424 23185 6426 23185 6427 23186 6428 23186 6429 23186 6431 23187 6432 23187 6433 23187 6435 23188 6436 23188 6437 23188 6439 23189 6440 23189 6152 23189 6152 23190 6440 23190 6153 23190 6441 23191 6442 23191 6443 23191 6445 23192 6446 23192 6447 23192 6447 23193 6446 23193 6448 23193 6449 23194 6450 23194 6451 23194 6451 23195 6450 23195 6452 23195 6459 23196 6458 23196 6460 23196 6461 23197 6462 23197 6463 23197 6463 23198 6462 23198 6464 23198 6467 23199 6466 23199 6468 23199 6469 23200 6470 23200 6471 23200 6471 23201 6470 23201 6472 23201 6475 23202 6474 23202 6476 23202 6481 23203 6482 23203 6483 23203 6483 23204 6482 23204 6484 23204 6491 23205 6490 23205 6492 23205 6493 23206 6494 23206 6495 23206 6499 23207 6498 23207 6500 23207 6499 23208 6063 23208 6501 23208 6501 23209 6063 23209 6502 23209 6494 23210 6493 23210 6506 23210 6506 23211 6493 23211 6507 23211 6491 23212 6500 23212 6508 23212 6508 23213 6500 23213 6505 23213 6493 23214 6436 23214 6507 23214 6489 23215 6491 23215 6510 23215 6489 4508 6510 4508 6490 4508 6490 53 6510 53 6512 53 6437 6342 6438 6342 6513 6342 6516 23216 6492 23216 6514 23216 6438 23217 6432 23217 6515 23217 6515 23218 6432 23218 6517 23218 6485 23219 6487 23219 6518 23219 6432 23220 6519 23220 6517 23220 6485 23221 6518 23221 6486 23221 6433 23222 6521 23222 6431 23222 6431 23223 6521 23223 6519 23223 6521 23224 6434 23224 6523 23224 6524 23225 6488 23225 6522 23225 6523 23226 6428 23226 6525 23226 6481 23227 6483 23227 6526 23227 6526 23228 6483 23228 6524 23228 6481 53 6526 53 6482 53 6429 23229 6529 23229 6427 23229 6482 23230 6528 23230 6484 23230 6484 23231 6528 23231 6530 23231 6429 23232 6430 23232 6529 23232 6479 6362 6484 6362 6532 6362 6430 23233 6424 23233 6531 23233 6534 23234 6479 23234 6532 23234 6423 6349 6535 6349 6424 6349 6424 23235 6535 23235 6533 23235 6478 53 6534 53 6536 53 6480 23236 6536 23236 6538 23236 6425 23237 6426 23237 6537 23237 6475 6362 6480 6362 6540 6362 6539 23238 6420 23238 6541 23238 6473 23239 6475 23239 6542 23239 6542 23240 6475 23240 6540 23240 6419 23241 6543 23241 6420 23241 6473 23242 6542 23242 6474 23242 6476 23243 6544 23243 6546 23243 6422 23244 6416 23244 6547 23244 6547 23245 6416 23245 6549 23245 6469 53 6550 53 6470 53 6470 53 6550 53 6552 53 6417 53 6553 53 6415 53 6415 53 6553 53 6551 53 6472 23246 6552 23246 6554 23246 6417 23247 6418 23247 6553 23247 6467 53 6472 53 6556 53 6418 23248 6412 23248 6555 23248 6465 23249 6467 23249 6558 23249 6411 23250 6559 23250 6412 23250 6466 23229 6558 23229 6560 23229 6413 53 6561 53 6411 53 6414 23251 6408 23251 6563 23251 6461 23252 6463 23252 6566 23252 6407 23253 6567 23253 6408 23253 6407 6350 6569 6350 6567 6350 6409 23254 6410 23254 6569 23254 6569 23255 6410 23255 6571 23255 6459 23208 6464 23208 6572 23208 6572 23256 6464 23256 6570 23256 6410 23257 6404 23257 6571 23257 6457 23258 6459 23258 6574 23258 6574 23259 6459 23259 6572 23259 6403 23260 6575 23260 6404 23260 6404 23261 6575 23261 6573 23261 6457 53 6574 53 6458 53 6458 53 6574 53 6576 53 6405 53 6577 53 6403 53 6403 53 6577 53 6575 53 6460 23262 6576 23262 6578 23262 6405 23263 6406 23263 6577 23263 6577 23264 6406 23264 6579 23264 6580 23265 6460 23265 6578 23265 6406 23266 6400 23266 6579 23266 6579 23267 6400 23267 6581 23267 6582 23268 6455 23268 6580 23268 6454 53 6582 53 6584 53 6399 53 6585 53 6583 53 6585 23269 6402 23269 6587 23269 6588 23270 6456 23270 6586 23270 6590 23271 6451 23271 6588 23271 6395 23272 6591 23272 6396 23272 6396 23273 6591 23273 6589 23273 6449 53 6590 53 6450 53 6450 6350 6590 6350 6592 6350 6395 23274 6593 23274 6591 23274 6450 23275 6592 23275 6452 23275 6596 23276 6452 23276 6594 23276 6398 23277 6392 23277 6595 23277 6595 6403 6392 6403 6597 6403 6598 23278 6447 23278 6596 23278 6392 23279 6599 23279 6597 23279 6445 53 6598 53 6446 53 6446 53 6598 53 6600 53 6448 23280 6600 23280 6602 23280 6601 23281 6394 23281 6603 23281 6604 23282 6448 23282 6602 23282 6394 23283 6388 23283 6603 23283 6441 23284 6443 23284 6606 23284 6387 23285 6607 23285 6388 23285 6389 53 6609 53 6387 53 6387 53 6609 53 6607 53 6153 23286 6610 23286 6124 23286 6386 23287 6151 23287 6611 23287 6611 23288 6151 23288 6107 23288 6612 23289 6611 23289 6107 23289 6444 6391 6608 6391 6613 6391 6609 23290 6390 23290 6614 23290 6440 23291 6439 23291 6610 23291 6610 23292 6439 23292 6615 23292 6615 23293 6444 23293 6613 23293 6143 23294 6617 23294 6144 23294 6143 23295 6618 23295 6617 23295 6436 23296 6618 23296 6438 23296 6438 23297 6618 23297 6432 23297 6432 23298 6618 23298 6434 23298 6434 23299 6618 23299 6428 23299 6424 23300 6618 23300 6426 23300 6420 23301 6618 23301 6422 23301 6422 23302 6618 23302 6143 23302 6416 23303 6143 23303 6418 23303 6416 23304 6422 23304 6143 23304 6143 23305 6149 23305 6388 23305 6394 23306 6143 23306 6388 23306 6143 23307 6392 23307 6398 23307 6396 23308 6402 23308 6143 23308 6143 23309 6402 23309 6400 23309 6143 23310 6404 23310 6410 23310 6408 23311 6143 23311 6410 23311 6143 23312 6414 23312 6412 23312 6418 23313 6143 23313 6412 23313 6065 23314 6063 23314 6620 23314 6620 23315 6063 23315 6499 23315 6620 23316 6491 23316 6492 23316 6620 23317 6488 23317 6483 23317 6484 6437 6479 6437 6620 6437 6475 23318 6476 23318 6620 23318 6463 23319 6144 23319 6468 23319 6463 23320 6464 23320 6144 23320 6460 23321 6455 23321 6144 23321 6144 23322 6455 23322 6456 23322 6451 23323 6144 23323 6456 23323 6448 23324 6443 23324 6144 23324 6443 23325 6444 23325 6148 23325 6148 23326 6444 23326 6439 23326 6152 23327 6148 23327 6439 23327 6059 23328 6058 23328 6621 23328 6621 23329 6058 23329 6622 23329 6064 23330 6623 23330 6063 23330 6063 23331 6623 23331 6502 23331 6056 23332 6059 23332 6002 23332 6002 23333 6059 23333 6001 23333 6624 23334 6625 23334 6373 23334 6624 23335 6626 23335 6625 23335 6062 23336 6006 23336 6061 23336 5989 23337 6626 23337 6627 23337 5989 23338 6627 23338 6628 23338 6628 23339 6629 23339 6630 23339 6633 23340 6632 23340 6634 23340 6634 23341 6635 23341 6636 23341 6635 23342 6634 23342 6026 23342 6019 23343 6638 23343 6637 23343 6638 23344 6019 23344 6022 23344 6015 23345 6639 23345 6638 23345 6639 23346 6015 23346 6640 23346 6641 23347 6640 23347 6017 23347 6017 23348 6643 23348 6642 23348 6642 23349 6643 23349 6644 23349 6644 23350 6643 23350 6645 23350 6379 23351 6648 23351 6647 23351 6651 23352 6649 23352 6650 23352 6651 23353 6652 23353 6649 23353 6651 23354 6653 23354 6652 23354 6654 23355 6653 23355 6655 23355 6656 23356 6654 23356 6655 23356 6656 23357 6657 23357 6654 23357 6656 23358 6659 23358 6658 23358 6656 23359 6380 23359 6659 23359 6644 23360 6646 23360 6649 23360 6657 23361 6658 23361 6660 23361 6662 23362 6661 23362 6663 23362 6666 23363 6665 23363 6031 23363 6667 23364 6669 23364 6668 23364 6028 23365 6039 23365 6669 23365 6669 23366 6039 23366 6670 23366 6042 23367 6672 23367 6673 23367 6673 23368 6672 23368 5996 23368 6675 23369 6674 23369 6676 23369 6060 23370 6675 23370 6676 23370 6060 23371 6056 23371 6675 23371 6660 23372 6661 23372 6662 23372 6662 23373 6663 23373 6664 23373 6664 23374 6665 23374 6666 23374 6370 23375 6384 23375 6371 23375 5996 23376 6675 23376 6002 23376 5996 23377 6003 23377 6673 23377 5988 23378 5989 23378 6628 23378 6679 23379 6630 23379 6631 23379 6680 23380 6684 23380 6683 23380 6685 23381 6684 23381 6686 23381 6687 23382 6686 23382 6688 23382 6689 23383 6688 23383 6690 23383 6695 23384 6694 23384 6696 23384 6697 23385 6696 23385 6698 23385 6699 23386 6698 23386 6700 23386 6701 23387 6700 23387 6702 23387 6705 23388 6704 23388 6706 23388 6707 23389 6706 23389 6708 23389 6709 23390 6708 23390 6710 23390 6711 23391 6710 23391 6712 23391 6717 23392 6716 23392 6718 23392 6719 23393 6718 23393 6720 23393 6721 23394 6720 23394 6722 23394 6618 23395 6723 23395 6724 23395 6617 23396 6724 23396 6619 23396 6617 23397 6618 23397 6724 23397 6685 23398 6686 23398 6687 23398 6689 23399 6690 23399 6691 23399 6691 23400 6692 23400 6693 23400 6693 23401 6694 23401 6695 23401 6697 23402 6698 23402 6699 23402 6699 23403 6700 23403 6701 23403 6701 23404 6702 23404 6703 23404 6703 23405 6704 23405 6705 23405 6707 23406 6708 23406 6709 23406 6709 23407 6710 23407 6711 23407 6711 23408 6712 23408 6713 23408 6713 23409 6714 23409 6715 23409 6717 23410 6718 23410 6719 23410 6719 23411 6720 23411 6721 23411 6721 23412 6722 23412 6057 23412 6724 23413 6725 23413 6619 23413 6619 23414 6725 23414 6620 23414 6065 23415 6726 23415 6727 23415 6051 23416 6065 23416 6727 23416 6729 23417 6728 23417 6730 23417 6731 23418 6730 23418 6732 23418 6733 23419 6732 23419 6734 23419 6735 23420 6734 23420 6736 23420 6681 23421 6737 23421 6682 23421 6729 23422 6730 23422 6731 23422 6377 23423 6739 23423 6624 23423 6739 23424 6377 23424 6376 23424 6740 23425 6677 23425 6741 23425 6741 23426 6383 23426 6740 23426 6740 23427 6383 23427 6384 23427 6021 23428 6014 23428 6742 23428 6743 23429 6742 23429 6013 23429 6744 23430 6743 23430 6745 23430 6010 23431 6743 23431 6013 23431 6753 23432 6752 23432 6755 23432 6756 23433 6755 23433 6752 23433 6757 23434 6758 23434 6759 23434 6754 23435 6751 23435 6752 23435 6748 23436 6024 23436 6020 23436 6746 23437 6760 23437 6761 23437 6746 23438 6749 23438 6760 23438 6020 23439 6024 23439 6762 23439 6759 23440 6749 23440 6745 23440 6754 23441 6745 23441 6743 23441 6043 23442 6046 23442 6763 23442 6767 23443 6768 23443 6769 23443 6771 23444 6773 23444 6772 23444 6037 23445 6036 23445 6774 23445 6047 23446 6780 23446 6764 23446 6047 23447 6764 23447 6046 23447 6783 23448 6764 23448 6784 23448 6781 23449 6769 23449 6768 23449 6782 23450 6768 23450 6052 23450 6769 23451 6784 23451 6770 23451 6770 23452 6784 23452 6778 23452 6784 23453 6780 23453 6047 23453 6764 23454 6783 23454 6032 23454 6032 23455 6783 23455 6785 23455 6032 23456 6785 23456 6779 23456 6779 23457 6785 23457 6787 23457 6790 23458 6789 23458 6791 23458 6792 23459 6791 23459 6793 23459 6790 23460 6791 23460 6792 23460 6792 23461 6793 23461 6794 23461 6632 23462 6746 23462 6761 23462 6762 23463 6634 23463 6761 23463 6025 23464 6024 23464 6796 23464 6019 23465 6018 23465 6023 23465 6022 23466 6019 23466 6023 23466 6019 23467 6748 23467 6020 23467 6028 23468 6667 23468 6029 23468 6029 23469 6667 23469 6774 23469 6027 23470 6765 23470 6797 23470 6039 23471 6766 23471 6036 23471 6766 23472 6763 23472 6765 23472 6042 23473 6771 23473 6040 23473 6042 23474 6673 23474 6771 23474 6015 23475 6014 23475 6798 23475 6037 23476 6773 23476 6035 23476 6036 23477 6029 23477 6774 23477 6776 23478 6779 23478 6777 23478 6677 23479 6799 23479 6659 23479 6677 23480 6041 23480 6800 23480 6041 23481 6674 23481 6672 23481 6672 23482 6042 23482 6041 23482 6766 23483 6045 23483 6033 23483 6044 23484 6034 23484 6033 23484 6039 23485 6027 23485 6766 23485 6027 23486 6039 23486 6028 23486 6797 23487 6766 23487 6027 23487 6801 23488 6031 23488 6665 23488 6658 23489 6659 23489 6802 23489 6014 23490 6021 23490 6023 23490 6798 23491 6023 23491 6016 23491 6647 23492 6804 23492 6803 23492 6012 23493 6645 23493 6643 23493 6643 23494 6017 23494 6012 23494 6804 23495 6012 23495 6011 23495 6796 23496 6021 23496 6748 23496 6805 23497 6632 23497 6631 23497 6626 23498 6624 23498 6806 23498 6806 23499 6624 23499 6803 23499 6807 23500 6808 23500 6805 23500 6805 23501 6808 23501 6804 23501 6804 23502 6808 23502 6809 23502 6803 23503 6809 23503 6810 23503 6627 23504 6811 23504 6812 23504 6806 23505 6811 23505 6627 23505 6808 23506 6813 23506 6814 23506 6807 23507 6817 23507 6813 23507 6811 23508 6817 23508 6812 23508 6818 23509 6819 23509 6802 23509 6661 23510 6819 23510 6820 23510 6800 23511 6822 23511 6823 23511 6799 23512 6823 23512 6818 23512 6802 23513 6799 23513 6818 23513 6802 23514 6819 23514 6661 23514 6663 23515 6821 23515 6801 23515 6819 23516 6824 23516 6826 23516 6821 23517 6827 23517 6822 23517 6822 23518 6827 23518 6828 23518 6823 23519 6825 23519 6818 23519 6756 23520 6752 23520 6750 23520 6752 23521 6751 23521 6750 23521 6756 23522 6016 23522 6755 23522 6829 23523 6016 23523 6023 23523 6758 23524 6762 23524 6760 23524 6829 23525 6023 23525 6018 23525 6048 23526 6830 23526 6052 23526 6048 23527 6831 23527 6830 23527 6833 23528 6758 23528 6757 23528 6759 23529 6754 23529 6834 23529 6834 23530 6754 23530 6835 23530 6835 23531 6754 23531 6836 23531 6837 23532 6836 23532 6753 23532 6837 23533 6755 23533 6838 23533 6838 23534 6755 23534 6788 23534 6788 23535 6793 23535 6838 23535 6838 23536 6793 23536 6839 23536 6840 23537 6699 23537 6841 23537 6841 23538 6699 23538 6701 23538 6839 23539 6843 23539 6844 23539 6775 23540 6787 23540 6701 23540 6845 23541 6785 23541 6842 23541 6844 23542 6782 23542 6846 23542 6830 23543 6847 23543 6052 23543 6817 23544 6833 23544 6757 23544 6835 23545 6815 23545 6814 23545 6835 23546 6814 23546 6834 23546 6834 23547 6813 23547 6757 23547 6825 23548 6842 23548 6843 23548 6825 23549 6828 23549 6842 23549 6843 23550 6824 23550 6825 23550 6841 23551 6826 23551 6840 23551 6646 23552 6373 23552 6625 23552 6062 23553 6066 23553 6625 23553 6060 23554 6676 23554 6072 23554 6072 23555 6676 23555 6656 23555 6655 23556 6072 23556 6656 23556 6370 23557 6380 23557 6656 23557 6058 23217 6495 23217 6622 23217 6622 23558 6495 23558 6848 23558 6496 23559 6849 23559 6495 23559 5906 23560 6603 23560 6605 23560 6614 23561 5906 23561 6605 23561 6614 23562 6616 23562 5906 23562 5906 23563 6616 23563 6850 23563 6597 23564 6603 23564 5906 23564 6595 23565 5906 23565 6589 23565 5908 23566 6555 23566 5906 23566 5908 23567 6549 23567 6555 23567 5908 23568 6547 23568 6549 23568 5908 23569 6541 23569 6547 23569 5908 23570 6531 23570 6533 23570 5908 23571 6525 23571 6531 23571 5908 23572 6523 23572 6525 23572 5908 23573 6515 23573 6517 23573 5908 23574 6509 23574 6515 23574 5908 23575 6848 23575 6507 23575 5908 23576 6622 23576 6848 23576 5908 23577 5910 23577 6622 23577 6555 23578 6557 23578 5906 23578 5906 23579 6557 23579 6563 23579 6565 23580 5906 23580 6563 23580 6565 23581 6571 23581 5906 23581 5906 23582 6573 23582 6579 23582 6581 23583 5906 23583 6579 23583 6581 23584 6587 23584 5906 23584 6595 23585 6597 23585 5906 23585 6615 23586 6851 23586 6610 23586 6610 23587 6851 23587 6076 23587 6008 23588 6502 23588 6623 23588 6007 23589 6008 23589 6623 23589 6586 23590 6584 23590 6580 23590 6580 23591 6584 23591 6582 23591 6570 23592 6568 23592 6564 23592 6564 23593 6568 23593 6566 23593 6558 23594 6556 23594 6560 23594 6542 23595 6540 23595 6544 23595 6538 23596 6536 23596 6532 23596 6532 23597 6536 23597 6534 23597 6528 23598 6524 23598 6530 23598 6522 23599 6520 23599 6516 23599 6512 23600 6508 23600 6514 23600 6501 23601 6504 23601 6503 23601 6606 23602 6604 23602 6608 23602 6622 23603 5910 23603 5993 23603 6589 23604 6593 23604 6595 23604 6571 23605 6565 23605 6569 23605 6569 23606 6565 23606 6567 23606 6539 23607 6533 23607 6537 23607 6537 23608 6533 23608 6535 23608 6525 23609 6529 23609 6531 23609 6523 23610 6517 23610 6521 23610 6521 23611 6517 23611 6519 23611 6511 23612 6513 23612 6509 23612 6506 23613 6848 23613 6849 23613 6607 23614 6609 23614 6605 23614 6605 23615 6609 23615 6614 23615 6064 23616 6061 23616 6007 23616 6623 23617 6064 23617 6007 23617 6496 23618 6506 23618 6849 23618 6000 23619 5997 23619 6852 23619 5981 23620 6855 23620 5999 23620 5981 23621 6856 23621 6855 23621 6856 23622 6857 23622 6858 23622 6860 23623 6857 23623 6859 23623 6854 23624 6859 23624 6857 23624 6858 23625 6857 23625 6860 23625 6865 23626 6283 23626 6866 23626 5990 23627 6866 23627 6283 23627 5992 23628 6868 23628 6192 23628 6192 23629 6869 23629 6193 23629 5990 23630 5991 23630 6867 23630 6194 23631 6280 23631 5778 23631 6280 23632 6870 23632 5778 23632 5967 23633 5964 23633 5957 23633 5965 23634 5964 23634 6869 23634 6873 23635 6879 23635 6871 23635 6871 23636 6879 23636 6880 23636 6875 23637 6882 23637 6881 23637 6882 23638 6874 23638 6877 23638 6882 23639 6884 23639 6883 23639 6883 23640 6884 23640 6885 23640 6878 23641 6886 23641 6877 23641 6877 23642 6886 23642 6885 23642 6878 23643 6887 23643 6886 23643 6887 23644 6889 23644 6888 23644 6872 23645 6871 23645 6876 23645 6889 23646 6876 23646 6871 23646 6891 23647 6892 23647 6893 23647 6892 23648 6891 23648 6894 23648 6895 23649 6894 23649 6896 23649 6891 23650 6897 23650 6894 23650 6897 23651 6891 23651 6898 23651 6891 23652 6893 23652 6898 23652 6897 23653 6899 23653 6902 23653 6901 23654 6904 23654 6899 23654 6909 23655 6910 23655 6911 23655 6912 23656 6909 23656 6913 23656 6914 23657 6913 23657 6911 23657 6914 23658 6915 23658 6913 23658 6916 23659 6909 23659 6917 23659 6912 23660 6919 23660 6918 23660 6918 23661 6919 23661 6920 23661 6919 23662 6915 23662 6921 23662 6921 23663 6922 23663 6919 23663 6919 23664 6922 23664 6920 23664 6915 23665 6923 23665 6921 23665 6921 23666 6923 23666 6922 23666 6924 23667 6925 23667 6926 23667 6925 23668 6914 23668 6911 23668 6925 23669 6911 23669 6926 23669 6910 23670 6916 23670 6911 23670 6911 23671 6916 23671 6927 23671 6932 23672 6928 23672 6931 23672 6928 23673 6932 23673 6933 23673 6935 23674 6931 23674 6934 23674 6935 23675 6932 23675 6931 23675 6929 23676 6928 23676 6937 23676 6937 23677 6928 23677 6938 23677 6939 23678 6933 23678 6932 23678 6936 23679 6941 23679 6940 23679 6940 23680 6941 23680 6942 23680 6941 23681 6935 23681 6943 23681 6943 23682 6935 23682 6934 23682 6943 23683 6934 23683 6944 23683 6946 23684 6929 23684 6947 23684 6947 23685 6929 23685 6937 23685 6948 23686 6949 23686 6950 23686 6952 23687 6948 23687 6951 23687 6948 23688 6952 23688 6953 23688 6955 23689 6952 23689 6951 23689 6952 23690 6955 23690 6956 23690 6949 23691 6948 23691 6957 23691 6958 23692 6953 23692 6959 23692 6959 23693 6953 23693 6952 23693 6956 23694 6960 23694 6952 23694 6952 23695 6960 23695 6959 23695 6960 23696 6961 23696 6962 23696 6961 23697 6963 23697 6962 23697 6962 23698 6963 23698 6964 23698 6963 23699 6954 23699 6964 23699 6964 23700 6954 23700 6965 23700 6966 23701 6967 23701 6954 23701 6954 23702 6967 23702 6965 23702 6966 23703 6949 23703 6967 23703 6967 23704 6949 23704 6957 23704 6968 23705 6969 23705 6970 23705 6971 23706 6968 23706 6970 23706 6970 23707 6974 23707 6971 23707 6975 23708 6972 23708 6971 23708 6972 23709 6975 23709 6976 23709 6980 23710 6981 23710 6982 23710 6984 23711 6974 23711 6985 23711 6970 23712 6969 23712 6986 23712 6987 23713 6969 23713 6977 23713 6988 23714 6989 23714 6990 23714 6990 23715 6994 23715 6991 23715 6995 23716 6991 23716 6994 23716 6988 23717 6993 23717 6998 23717 6998 23718 6993 23718 6999 23718 6996 23719 7000 23719 6992 23719 6995 23720 7001 23720 6996 23720 6996 23721 7001 23721 7000 23721 7000 23722 7001 23722 7002 23722 7001 23723 6995 23723 7003 23723 7002 23724 7003 23724 7004 23724 7003 23725 6995 23725 6994 23725 7004 23726 6994 23726 7005 23726 6990 23727 6989 23727 7006 23727 7007 23728 6989 23728 6997 23728 7011 23729 7008 23729 7010 23729 7012 23730 7008 23730 7011 23730 7008 23731 7012 23731 7013 23731 7010 23732 7014 23732 7011 23732 7015 23733 7011 23733 7014 23733 7015 23734 7012 23734 7011 23734 7017 23735 7008 23735 7018 23735 7018 23736 7013 23736 7019 23736 7016 23737 7021 23737 7020 23737 7020 23738 7021 23738 7022 23738 7021 23739 7023 23739 7022 23739 7023 23740 7014 23740 7024 23740 7024 23741 7014 23741 7025 23741 7026 23742 7027 23742 7014 23742 7014 23743 7010 23743 7026 23743 7010 23744 7009 23744 7026 23744 7026 23745 7009 23745 7027 23745 7028 23746 7032 23746 7033 23746 7035 23747 7031 23747 7034 23747 7028 23748 7033 23748 7038 23748 7038 23749 7033 23749 7039 23749 7036 23750 7040 23750 7032 23750 7032 23751 7040 23751 7039 23751 7035 23752 7041 23752 7036 23752 7036 23753 7041 23753 7040 23753 7040 23754 7041 23754 7042 23754 7041 23755 7035 23755 7043 23755 7041 23756 7043 23756 7042 23756 7042 23757 7043 23757 7044 23757 7034 23758 7047 23758 7045 23758 7030 23759 7029 23759 7046 23759 7046 23760 7029 23760 7047 23760 7047 23761 7029 23761 7037 23761 7048 23762 7049 23762 7050 23762 7051 23763 7048 23763 7050 23763 7048 23764 7052 23764 7053 23764 7055 23765 7052 23765 7051 23765 7049 23766 7048 23766 7057 23766 7059 23767 7053 23767 7052 23767 7056 23768 7060 23768 7052 23768 7052 23769 7060 23769 7059 23769 7060 23770 7061 23770 7062 23770 7061 23771 7055 23771 7063 23771 7061 23772 7063 23772 7062 23772 7062 23773 7063 23773 7064 23773 7063 23774 7055 23774 7054 23774 7064 23775 7054 23775 7065 23775 7054 23776 7050 23776 7066 23776 7050 23777 7049 23777 7066 23777 7067 23778 7049 23778 7057 23778 7071 23779 7068 23779 7072 23779 7073 23780 7072 23780 7070 23780 7073 23781 7074 23781 7072 23781 7069 23782 7068 23782 7075 23782 7075 23783 7068 23783 6286 23783 7068 23784 7071 23784 6286 23784 7077 23785 7071 23785 7074 23785 7071 23786 7077 23786 7076 23786 7073 23787 7081 23787 7074 23787 7081 23788 7073 23788 7083 23788 7081 23789 7083 23789 7082 23789 7069 23790 7075 23790 7070 23790 7089 23791 7086 23791 7088 23791 7087 23792 7086 23792 6865 23792 7093 23793 7089 23793 7092 23793 7089 23794 7093 23794 7091 23794 7094 23795 6284 23795 7090 23795 7091 23796 7095 23796 7090 23796 7091 23797 7096 23797 7095 23797 7095 23798 7096 23798 7097 23798 7096 23799 7093 23799 7098 23799 7096 23800 7098 23800 7097 23800 7099 23801 7098 23801 6296 23801 6296 23802 7098 23802 7092 23802 7092 23803 6862 23803 6296 23803 5983 23804 5984 23804 6289 23804 6218 23805 5923 23805 7103 23805 7106 23806 5924 23806 6353 23806 7107 23807 7105 23807 7108 23807 7103 23808 7105 23808 7109 23808 7111 23809 6345 23809 7109 23809 7109 23810 6345 23810 7113 23810 7113 23811 6345 23811 7114 23811 7115 23812 7113 23812 7114 23812 7115 23813 7116 23813 7113 23813 7113 23814 7116 23814 7117 23814 7118 23815 7119 23815 7117 23815 7119 23816 7118 23816 6332 23816 7120 23817 7116 23817 6338 23817 7120 23818 6338 23818 6337 23818 7119 23819 7121 23819 7117 23819 7122 23820 7121 23820 6321 23820 7117 23821 7122 23821 7123 23821 6315 23822 7124 23822 6316 23822 7128 23823 7126 23823 6305 23823 7128 23824 6305 23824 6304 23824 7129 23825 6307 23825 7130 23825 6855 23826 7132 23826 6853 23826 5801 23827 6289 23827 7101 23827 6000 23828 5801 23828 7101 23828 6852 23829 6853 23829 7132 23829 7102 23830 7135 23830 6154 23830 6154 23831 7135 23831 6155 23831 6155 23832 7135 23832 6221 23832 6283 23833 6194 23833 5968 23833 6280 23834 6194 23834 6283 23834 6283 23835 5968 23835 5969 23835 6283 23836 5969 23836 5970 23836 6283 23837 6865 23837 6284 23837 6863 23838 6862 23838 7136 23838 7094 23839 7095 23839 6285 23839 6288 23840 6285 23840 7097 23840 7097 23841 7099 23841 6288 23841 6288 23842 7099 23842 6289 23842 5989 23843 5985 23843 6006 23843 7137 23844 5985 23844 5988 23844 7141 23845 7142 23845 7143 23845 7148 23846 7147 23846 7149 23846 7150 23847 7149 23847 7151 23847 7152 23848 7151 23848 7153 23848 6867 23849 7154 23849 7155 23849 6863 23850 7155 23850 6864 23850 6860 23851 7157 23851 7158 23851 7139 23852 6861 23852 7140 23852 5982 23853 6864 23853 7156 23853 6863 23854 6866 23854 7155 23854 6866 23855 6867 23855 7155 23855 7152 23856 7159 23856 7151 23856 7161 23857 7150 23857 7151 23857 7162 23858 7148 23858 7149 23858 7148 23859 7163 23859 7147 23859 7163 23860 7164 23860 7147 23860 7146 23861 7144 23861 7145 23861 7144 23862 7165 23862 7142 23862 7165 23863 7143 23863 7142 23863 7166 23864 6664 23864 7167 23864 7166 23865 6662 23865 6664 23865 6662 23866 7166 23866 6660 23866 6660 23867 7166 23867 7168 23867 6657 23868 7168 23868 7169 23868 6652 23869 7169 23869 7170 23869 6644 23870 7171 23870 7172 23870 6639 23871 7173 23871 7174 23871 7174 23872 7175 23872 6638 23872 6635 23873 7160 23873 7159 23873 6652 23874 7171 23874 6649 23874 6641 23875 7173 23875 6639 23875 6639 23876 7174 23876 6638 23876 7160 23877 7175 23877 7161 23877 7161 23878 7175 23878 7176 23878 7179 23879 7162 23879 7178 23879 7148 23880 7179 23880 7180 23880 7180 23881 7164 23881 7163 23881 7164 23882 7180 23882 7181 23882 7181 23883 7146 23883 7164 23883 7181 23884 7182 23884 7146 23884 7183 23885 7144 23885 7146 23885 7144 23886 7183 23886 7184 23886 7184 23887 7185 23887 7165 23887 7186 23888 7187 23888 7143 23888 7141 23889 7187 23889 7188 23889 6668 23890 7139 23890 7138 23890 6668 23891 6669 23891 7139 23891 7161 23892 7176 23892 7150 23892 7141 23893 7188 23893 7138 23893 7160 23894 6635 23894 6637 23894 6858 23895 6861 23895 7139 23895 7154 23896 6732 23896 6730 23896 7154 23897 6730 23897 6728 23897 7155 23898 6728 23898 6726 23898 6864 23899 7155 23899 6724 23899 7154 23900 6728 23900 7155 23900 6724 23901 6723 23901 6864 23901 6864 23902 6723 23902 7156 23902 7156 23903 6723 23903 6722 23903 7158 23904 6716 23904 6714 23904 7158 23905 6714 23905 6712 23905 7140 23906 6712 23906 6710 23906 7142 23907 6708 23907 6706 23907 7142 23908 6706 23908 6704 23908 7142 23909 6704 23909 6702 23909 7145 6 6700 6 6698 6 7147 23910 7145 23910 6696 23910 7140 23911 6708 23911 7142 23911 6696 23912 6694 23912 7147 23912 7147 23913 6694 23913 6692 23913 7149 23914 6690 23914 6688 23914 7149 23915 6688 23915 6686 23915 7151 23916 6686 23916 6684 23916 7151 23917 6680 23917 6682 23917 7147 23918 6690 23918 7149 23918 6669 23919 6858 23919 7190 23919 7125 23920 7191 23920 7192 23920 7113 23921 7194 23921 7195 23921 7103 23922 7196 23922 7197 23922 7102 23923 7197 23923 7198 23923 7102 23924 7103 23924 7197 23924 6855 23925 5911 23925 7132 23925 7132 23926 7191 23926 7125 23926 7125 23927 7192 23927 7123 23927 7117 23928 7194 23928 7113 23928 7109 23929 7196 23929 7103 23929 5995 23930 6855 23930 6005 23930 6005 23931 6669 23931 6671 23931 6679 23932 7199 23932 7137 23932 6679 23933 7200 23933 7199 23933 6679 23934 6635 23934 7200 23934 6635 23935 6679 23935 6633 23935 6635 23936 7152 23936 7200 23936 7200 23937 7189 23937 7199 23937 7199 23938 6191 23938 7137 23938 5986 23939 6191 23939 5804 23939 5804 23940 6191 23940 6190 23940 5805 23941 6190 23941 6186 23941 5807 23942 6173 23942 6168 23942 5810 23943 6164 23943 6160 23943 5812 23944 5810 23944 6160 23944 5804 23945 6190 23945 5805 23945 5805 23946 6186 23946 5816 23946 5807 23947 6168 23947 5808 23947 5808 23948 6164 23948 5810 23948 7201 23949 7199 23949 7189 23949 7201 23950 7189 23950 7153 23950 5797 23951 5799 23951 5911 23951 5911 23952 5799 23952 7202 23952 5799 23953 7203 23953 7202 23953 7205 23954 7206 23954 7202 23954 7206 23955 7209 23955 7207 23955 7192 23956 7208 23956 7210 23956 7211 23957 7192 23957 7210 23957 7193 23958 7213 23958 7194 23958 7212 23959 7214 23959 7213 23959 7215 23960 7216 23960 7213 23960 7219 23961 7220 23961 7194 23961 7194 23962 7221 23962 7195 23962 7224 23963 7225 23963 7196 23963 7225 23964 7226 23964 7196 23964 7196 23965 7226 23965 7197 23965 7227 23966 7198 23966 7197 23966 7198 23967 7228 23967 7229 23967 7230 23968 7198 23968 7229 23968 7218 23969 7232 23969 7233 23969 7233 23970 7232 23970 6337 23970 7216 23971 7236 23971 7237 23971 7214 23972 7212 23972 7238 23972 7240 23973 7212 23973 6316 23973 7242 23974 7210 23974 7243 23974 7244 23975 6304 23975 7245 23975 7244 23976 7207 23976 7246 23976 7209 23977 6310 23977 7246 23977 7209 23978 7246 23978 7207 23978 7206 23979 7205 23979 7247 23979 7247 23980 7205 23980 7248 23980 7205 23981 7249 23981 7248 23981 7204 23982 7203 23982 7250 23982 7250 23983 7203 23983 7253 23983 5800 23984 5907 23984 7255 23984 5800 23985 7255 23985 5798 23985 5909 23986 7256 23986 5907 23986 5909 23987 7257 23987 7256 23987 5909 23988 7258 23988 7257 23988 5909 23989 7259 23989 7258 23989 5909 23990 7260 23990 7259 23990 5909 23991 7261 23991 7260 23991 5909 23992 7263 23992 7262 23992 5909 23993 7264 23993 7263 23993 5909 23994 7266 23994 7265 23994 7267 23995 7268 23995 7269 23995 7269 23996 7268 23996 7228 23996 7229 23997 7228 23997 7268 23997 7271 23998 7270 23998 7227 23998 7263 23999 7264 23999 7272 23999 7273 24000 7272 24000 7274 24000 7273 24001 7274 24001 7224 24001 7275 24002 7262 24002 7276 24002 7276 24003 7277 24003 7275 24003 7277 24004 7276 24004 7223 24004 7261 24005 7262 24005 7275 24005 7223 24006 7222 24006 7277 24006 7278 24007 7280 24007 7279 24007 7280 24008 7221 24008 7220 24008 7218 24009 7281 24009 7219 24009 7233 24010 7281 24010 7218 24010 5907 24011 7256 24011 7282 24011 7283 24012 5907 24012 7282 24012 7286 24013 7287 24013 7282 24013 7287 24014 7235 24014 7217 24014 7285 24015 7215 24015 7214 24015 7284 24016 7288 24016 5907 24016 7291 24017 7290 24017 7292 24017 7245 24018 7292 24018 7210 24018 7289 24019 7288 24019 7241 24019 7289 24020 7241 24020 7293 24020 7291 24021 7292 24021 7245 24021 5907 24022 7294 24022 7295 24022 7296 24023 7297 24023 5907 24023 7297 24024 7296 24024 7298 24024 7251 24025 7298 24025 7205 24025 7251 24026 7205 24026 7204 24026 7295 24027 7294 24027 7299 24027 7300 24028 7299 24028 7209 24028 7300 24029 7209 24029 7206 24029 7297 24030 7255 24030 5907 24030 5798 24031 7254 24031 5799 24031 5799 24032 7254 24032 7203 24032 7302 24033 5829 24033 6203 24033 5828 24034 5843 24034 7303 24034 7305 24035 6206 24035 5842 24035 5842 24036 5830 24036 7305 24036 7305 24037 5830 24037 7306 24037 5832 24038 7307 24038 6208 24038 5832 24039 6208 24039 7306 24039 7308 24040 5835 24040 7309 24040 5833 24041 7310 24041 5887 24041 7310 24042 6210 24042 5887 24042 5833 24043 5834 24043 7310 24043 5834 24044 5838 24044 7313 24044 7313 24045 5838 24045 6170 24045 5836 24046 7314 24046 5893 24046 7314 24047 6171 24047 5893 24047 5836 24048 5837 24048 7314 24048 7314 24049 5837 24049 7315 24049 5905 24050 6214 24050 7315 24050 5992 24051 6191 24051 7199 24051 5992 24052 6192 24052 6191 24052 7199 24053 5991 24053 5992 24053 7320 24054 7321 24054 7322 24054 7322 24055 7323 24055 6079 24055 6079 24056 5900 24056 7322 24056 7322 24057 5900 24057 5841 24057 5814 24058 7318 24058 5813 24058 5814 24059 7316 24059 7318 24059 5812 24060 6160 24060 5814 24060 7325 24061 5814 24061 7324 24061 7325 24062 7316 24062 5814 24062 7327 24063 6091 24063 6089 24063 7328 24064 6089 24064 6090 24064 7329 24065 6090 24065 6093 24065 7330 24066 7329 24066 6093 24066 7327 24067 6089 24067 7328 24067 7328 24068 7229 24068 7327 24068 6080 24069 6087 24069 6083 24069 6612 24070 7326 24070 6850 24070 6612 24071 6083 24071 7326 24071 7326 24072 7268 24072 6850 24072 6850 24073 7268 24073 5909 24073 6113 24074 6112 24074 6140 24074 6140 24075 6112 24075 6109 24075 7332 24076 6073 24076 6077 24076 7333 53 7332 53 6077 53 6077 24077 6078 24077 7333 24077 7321 24078 7334 24078 7323 24078 7321 53 7335 53 7334 53 7321 24079 7319 24079 7335 24079 7336 53 7337 53 7335 53 7336 24080 7338 24080 7337 24080 6604 24081 7343 24081 6613 24081 6586 24082 6580 24082 7343 24082 6570 24083 6564 24083 7343 24083 6564 24084 6562 24084 7343 24084 6554 24085 6548 24085 6009 24085 7343 24086 6554 24086 6009 24086 6538 24087 6532 24087 6009 24087 6532 24088 6530 24088 6009 24088 6522 24089 6516 24089 6009 24089 6514 24090 6508 24090 6009 24090 6502 24091 6008 24091 6009 24091 6501 24092 6502 24092 6009 24092 6615 24093 7343 24093 6851 24093 6604 24094 6602 24094 7343 24094 6602 24095 6600 24095 6596 24095 6596 24096 6600 24096 6598 24096 6865 24097 7136 24097 7087 24097 7344 24098 7167 24098 7188 24098 7167 24099 7345 24099 7166 24099 7166 24100 7346 24100 7347 24100 7169 24101 7349 24101 7350 24101 7170 24102 7350 24102 7351 24102 7351 24103 7171 24103 7170 24103 7351 24104 7352 24104 7171 24104 7353 24105 7173 24105 7172 24105 7353 24106 7354 24106 7173 24106 7166 24107 7347 24107 7168 24107 7175 24108 7357 24108 7174 24108 7359 24109 7177 24109 7358 24109 7177 24110 7360 24110 7178 24110 7361 24111 7179 24111 7178 24111 7361 24112 7362 24112 7179 24112 7179 24113 7362 24113 7180 24113 7363 24114 7364 24114 7180 24114 7366 24115 7367 24115 7368 24115 7370 24116 7371 24116 7373 24116 7372 24117 7375 24117 7371 24117 7375 24118 7378 24118 7371 24118 7366 24119 7379 24119 7367 24119 7368 24120 7367 24120 7383 24120 7384 24121 7379 24121 7385 24121 7386 24122 7376 24122 7380 24122 7386 24123 7377 24123 7376 24123 7378 24124 7377 24124 7387 24124 7375 24125 7377 24125 7378 24125 7373 24126 7371 24126 7378 24126 7393 24127 7391 24127 7394 24127 7392 24128 7395 24128 7390 24128 7385 24129 7396 24129 7397 24129 7396 24130 7398 24130 7397 24130 7397 24131 7398 24131 7399 24131 7395 24132 7400 24132 7401 24132 7401 24133 7400 24133 7396 24133 7344 24134 7405 24134 7345 24134 7345 24135 7406 24135 7346 24135 7373 24136 7408 24136 7365 24136 7365 24137 7364 24137 7409 24137 7363 24138 7399 24138 7364 24138 7399 24139 7363 24139 7362 24139 7384 24140 7361 24140 7354 24140 7384 24141 7353 24141 7379 24141 7355 24142 7360 24142 7359 24142 7356 24143 7359 24143 7358 24143 7174 24144 7358 24144 7357 24144 7174 24145 7356 24145 7358 24145 7354 24146 7360 24146 7355 24146 7355 24147 7359 24147 7356 24147 7352 24148 7351 24148 7367 24148 7351 24149 7350 24149 7383 24149 7382 24150 7350 24150 7381 24150 7380 24151 7348 24151 7386 24151 7367 24152 7379 24152 7352 24152 7402 24153 7384 24153 7403 24153 7385 24154 7389 24154 7401 24154 7395 24155 7401 24155 7390 24155 7389 24156 7394 24156 7391 24156 7389 24157 7388 24157 7394 24157 7409 24158 7393 24158 7373 24158 7347 24159 7387 24159 7386 24159 7395 24160 7409 24160 7399 24160 7393 24161 7409 24161 7395 24161 7404 24162 7397 24162 7402 24162 7405 24163 7186 24163 7406 24163 7405 24164 7344 24164 7187 24164 7406 24165 7185 24165 7387 24165 7408 24166 7183 24166 7182 24166 7365 24167 7182 24167 7181 24167 7410 24168 7102 24168 7411 24168 7410 24169 7412 24169 7102 24169 7413 24170 7414 24170 7415 24170 7413 24171 7416 24171 7417 24171 7419 24172 7420 24172 7417 24172 7424 24173 7423 24173 7425 24173 7426 6 7425 6 7427 6 7426 24174 7427 24174 7428 24174 7430 24175 7431 24175 7429 24175 7430 6 7432 6 7431 6 7428 6 7427 6 7434 6 7135 24176 7441 24176 7439 24176 7135 24177 7442 24177 7441 24177 7135 6 7412 6 7442 6 7443 24178 7444 24178 7445 24178 7446 24179 7443 24179 7447 24179 7450 24180 6161 24180 7440 24180 7443 6 7452 6 7447 6 7429 6 7426 6 7428 6 7437 6 7435 6 7436 6 7439 24181 7437 24181 7438 24181 7410 24182 7453 24182 7433 24182 7451 24183 7448 24183 6159 24183 6160 24184 6159 24184 7324 24184 7324 24185 7448 24185 7325 24185 7325 24186 7448 24186 7447 24186 7421 24187 7454 24187 7455 24187 7413 24188 7417 24188 6138 24188 6138 24189 7417 24189 6137 24189 7457 24190 7458 24190 7414 24190 7456 24191 7414 24191 7458 24191 7451 24192 6159 24192 6161 24192 7455 24193 6099 24193 6137 24193 7455 24194 6095 24194 6099 24194 7455 24195 7454 24195 6095 24195 6095 24196 7454 24196 6100 24196 6100 24197 7454 24197 7421 24197 6093 24198 7421 24198 7453 24198 6093 24199 6100 24199 7421 24199 7330 24200 6093 24200 7453 24200 7453 24201 7411 24201 7231 24201 7231 24202 7411 24202 7102 24202 6138 24203 6139 24203 7339 24203 7457 24204 7339 24204 7338 24204 7456 24205 7336 24205 7317 24205 7325 24206 7456 24206 7317 24206 7457 24207 7338 24207 7458 24207 6084 24208 7460 24208 6086 24208 6088 24209 7460 24209 7461 24209 6092 24210 7461 24210 7462 24210 6094 24211 7462 24211 7463 24211 6096 24212 7463 24212 7464 24212 6101 24213 7464 24213 7465 24213 6084 24214 6085 24214 7459 24214 6086 24215 7460 24215 6088 24215 6092 24216 7462 24216 6094 24216 6101 24217 7465 24217 6085 24217 7461 24218 7468 24218 7469 24218 7463 24219 7470 24219 7471 24219 7463 24220 7471 24220 7472 24220 7465 24221 7472 24221 7467 24221 7459 24222 7465 24222 7467 24222 7463 24223 7472 24223 7464 24223 7473 24224 7334 24224 7335 24224 7473 24225 7474 24225 7334 24225 7332 24226 7475 24226 7476 24226 7337 24227 7479 24227 7480 24227 7335 24228 7480 24228 7473 24228 7333 24229 7475 24229 7332 24229 7332 24230 7476 24230 7342 24230 7342 24231 7477 24231 7341 24231 7340 24232 7479 24232 7337 24232 7481 24233 7474 24233 7473 24233 7474 24234 7481 24234 7475 24234 7477 24235 7484 24235 7485 24235 7478 24236 7485 24236 7486 24236 7478 24237 7486 24237 7487 24237 7475 24238 7483 24238 7476 24238 7476 24239 7484 24239 7477 24239 7477 24240 7485 24240 7478 24240 7444 24241 7489 24241 7490 24241 7450 24242 7493 24242 7494 24242 7449 24243 7494 24243 7488 24243 7446 24244 7449 24244 7488 24244 7434 24245 7491 24245 7436 24245 7436 24246 7492 24246 7438 24246 7440 24247 7493 24247 7450 24247 7493 24248 7495 24248 7494 24248 7490 24249 7489 24249 7491 24249 7491 24250 7495 24250 7492 24250 7428 24251 7496 24251 7430 24251 7430 24252 7496 24252 7498 24252 7432 24253 7498 24253 7499 24253 7437 24254 7503 24254 7497 24254 7435 24255 7437 24255 7497 24255 7442 24256 7501 24256 7441 24256 7441 24257 7502 24257 7439 24257 7498 24258 7496 24258 7499 24258 7500 24259 7499 24259 7502 24259 7503 24260 7502 24260 7496 24260 7497 24261 7503 24261 7496 24261 7504 24262 7505 24262 7418 24262 7418 24263 7505 24263 7419 24263 7429 24264 7508 24264 7509 24264 7426 24265 7509 24265 7510 24265 7424 24266 7510 24266 7504 24266 7420 24267 7506 24267 7422 24267 7431 24268 7508 24268 7429 24268 7426 24269 7510 24269 7424 24269 7507 24270 7513 24270 7514 24270 7508 24271 7514 24271 7515 24271 7508 24272 7515 24272 7516 24272 7509 24273 7516 24273 7517 24273 7507 24274 7514 24274 7508 24274 7508 24275 7516 24275 7509 24275 7518 24276 7414 24276 7519 24276 7518 24277 7520 24277 7414 24277 7416 24278 7520 24278 7521 24278 7452 24279 7525 24279 7519 24279 7415 24280 7520 24280 7416 24280 7423 24281 7521 24281 7425 24281 7425 24282 7522 24282 7427 24282 7445 24283 7524 24283 7443 24283 7526 24284 7520 24284 7518 24284 7519 24285 7526 24285 7518 24285 7521 24286 7528 24286 7522 24286 7523 24287 7531 24287 7524 24287 7525 24288 7532 24288 7519 24288 7489 24289 7494 24289 7495 24289 7502 24290 7499 24290 7533 24290 7527 24291 7534 24291 7487 24291 7527 24292 7526 24292 7534 24292 7534 24293 7526 24293 7482 24293 7536 24294 7532 24294 7531 24294 7487 24295 7538 24295 7527 24295 7528 24296 7538 24296 7486 24296 7486 24297 7485 24297 7529 24297 7528 24298 7486 24298 7529 24298 7536 24299 7483 24299 7481 24299 7535 24300 7481 24300 7482 24300 7482 24301 7526 24301 7535 24301 7537 24302 7484 24302 7530 24302 7530 24303 7483 24303 7531 24303 7531 24304 7483 24304 7536 24304 7532 24305 7536 24305 7481 24305 7532 24306 7481 24306 7535 24306 7467 24307 7472 24307 7539 24307 7512 24308 7511 24308 7539 24308 7539 24309 7511 24309 7467 24309 7472 24310 7543 24310 7512 24310 7514 24311 7470 24311 7542 24311 7470 24312 7469 24312 7542 24312 7540 24313 7466 24313 7467 24313 7542 24314 7469 24314 7515 24314 7515 24315 7468 24315 7516 24315 7541 24316 7466 24316 7517 24316 7517 24317 7466 24317 7540 24317 7544 24318 7299 24318 7294 24318 7294 24319 7291 24319 7544 24319 7546 24320 5820 24320 7547 24320 5852 24321 5851 24321 7547 24321 7547 24322 5851 24322 7548 24322 7550 24323 7549 24323 5867 24323 7551 24324 5855 24324 5856 24324 6332 24325 7235 24325 7286 24325 7552 24326 7286 24326 7256 24326 7553 24327 7257 24327 7233 24327 7554 24328 7280 24328 6344 24328 6344 24329 7278 24329 7260 24329 7260 24330 7261 24330 7555 24330 7556 24331 7261 24331 7275 24331 6348 24332 7274 24332 7272 24332 7307 24333 5881 24333 5879 24333 7559 24334 5872 24334 5873 24334 5838 24335 5892 24335 6170 24335 6170 24336 5892 24336 7560 24336 7560 24337 5892 24337 7561 24337 5890 24338 5889 24338 7561 24338 6214 24339 5905 24339 7563 24339 7563 24340 5905 24340 5902 24340 7563 24341 5902 24341 5897 24341 5897 24342 5891 24342 7563 24342 6213 24343 7564 24343 5891 24343 7312 24344 5896 24344 7565 24344 7567 24345 5898 24345 5903 24345 7569 24346 7568 24346 5904 24346 5839 24347 7570 24347 5904 24347 5835 24348 5886 24348 7309 24348 7309 24349 5886 24349 7571 24349 7304 24350 5874 24350 6207 24350 7573 24351 5863 24351 5864 24351 7573 24352 5864 24352 6184 24352 6184 24353 5864 24353 5866 24353 7216 24354 7237 24354 7287 24354 7220 24355 7574 24355 7575 24355 7219 24356 7281 24356 7574 24356 7223 24357 7576 24357 7224 24357 7224 24358 7576 24358 7577 24358 7223 24359 7276 24359 7576 24359 7576 24360 7276 24360 6346 24360 7227 24361 7270 24361 7579 24361 7579 24362 7270 24362 7580 24362 5930 24363 7581 24363 5926 24363 5930 24364 5932 24364 7581 24364 6892 24365 6895 24365 6893 24365 6893 24366 6895 24366 6908 24366 5817 24367 7585 24367 7586 24367 5818 24368 5857 24368 7585 24368 7585 24369 5857 24369 7587 24369 7589 24370 5865 24370 7588 24370 7590 24371 5868 24371 7591 24371 5821 24372 7592 24372 5868 24372 7593 24373 7239 24373 6320 24373 7594 24374 7292 24374 7290 24374 6305 24375 7292 24375 7594 24375 7290 24376 7289 24376 7594 24376 6315 24377 7596 24377 7293 24377 7293 24378 7242 24378 6315 24378 6309 24379 7597 24379 7300 24379 5789 24380 5802 24380 5787 24380 5794 24381 5795 24381 6292 24381 6292 24382 6291 24382 5793 24382 6291 24383 5801 24383 5793 24383 7599 24384 7134 24384 7131 24384 7253 24385 7599 24385 7250 24385 7252 24386 7130 24386 6307 24386 6297 24387 7598 24387 6298 24387 6297 24388 6298 24388 6292 24388 7255 24389 7297 24389 6297 24389 6306 24390 6307 24390 7249 24390 7125 24391 6310 24391 7247 24391 6300 24392 6298 24392 7600 24392 6300 24393 7600 24393 7597 24393 7296 24394 7295 24394 7600 24394 7600 24395 7295 24395 7597 24395 7600 24396 7298 24396 7296 24396 6306 24397 7298 24397 7600 24397 6310 24398 7127 24398 7246 24398 7125 24399 7126 24399 7127 24399 7128 24400 7127 24400 7126 24400 7127 24401 7128 24401 7244 24401 7545 24402 7291 24402 6304 24402 6304 24403 7291 24403 7245 24403 6305 24404 7126 24404 7243 24404 7126 24405 7123 24405 7242 24405 7243 24406 7126 24406 7242 24406 7123 24407 6315 24407 7242 24407 7601 24408 7593 24408 6318 24408 7124 24409 7240 24409 6316 24409 7238 24410 7240 24410 7122 24410 7240 24411 7124 24411 7122 24411 6320 24412 7238 24412 7122 24412 7584 24413 7602 24413 7603 24413 5785 24414 6194 24414 5778 24414 7547 24415 7548 24415 6274 24415 7547 24416 6274 24416 6272 24416 7603 24417 6274 24417 7548 24417 7547 24418 6196 24418 7546 24418 6189 24419 6188 24419 7604 24419 7604 24420 6188 24420 7584 24420 7605 24421 7584 24421 7603 24421 7605 24422 7603 24422 5858 24422 7606 24423 6278 24423 6272 24423 6272 24424 6270 24424 7607 24424 6272 24425 7607 24425 7606 24425 7607 24426 6270 24426 6197 24426 6186 24427 6189 24427 7585 24427 5859 24428 7586 24428 6278 24428 7606 24429 5853 24429 5859 24429 7606 24430 5859 24430 6278 24430 7550 24431 7551 24431 6270 24431 6197 24432 6270 24432 7551 24432 6200 24433 6199 24433 7549 24433 6198 24434 6187 24434 7609 24434 6199 24435 6198 24435 7609 24435 6197 24436 7609 24436 6187 24436 7609 24437 6197 24437 7608 24437 7551 24438 5856 24438 7608 24438 7591 24439 6265 24439 7590 24439 6198 24440 6201 24440 7592 24440 6265 24441 7591 24441 6201 24441 6265 24442 7588 24442 7590 24442 7611 24443 6331 24443 6325 24443 6325 24444 6318 24444 7612 24444 6325 24445 7612 24445 7611 24445 6318 24446 6319 24446 7612 24446 6321 24447 7121 24447 7236 24447 7237 24448 7236 24448 7121 24448 7121 24449 7119 24449 7237 24449 7237 24450 7119 24450 6331 24450 7119 24451 6332 24451 6331 24451 7552 24452 6333 24452 6325 24452 6337 24453 6333 24453 7553 24453 6332 24454 7118 24454 7234 24454 6337 24455 7232 24455 7120 24455 7615 24456 6333 24456 6338 24456 7575 24457 7574 24457 7115 24457 7115 24458 6343 24458 7575 24458 7613 24459 7259 24459 7279 24459 6345 24460 6245 24460 7556 24460 6344 24461 6343 24461 7554 24461 6343 24462 7115 24462 7616 24462 7617 24463 7115 24463 7114 24463 7114 24464 6345 24464 7617 24464 7556 24465 7275 24465 6345 24465 7618 24466 6245 24466 7619 24466 6345 24467 7111 24467 7576 24467 7620 24468 7577 24468 7111 24468 6347 24469 7620 24469 7111 24469 7273 24470 7577 24470 7620 24470 7618 24471 7263 24471 6347 24471 7620 24472 6347 24472 7273 24472 7112 24473 7621 24473 7622 24473 7112 24474 7110 24474 7621 24474 7110 24475 7105 24475 7623 24475 7622 24476 7621 24476 7623 24476 7623 24477 7105 24477 7107 24477 7558 24478 7107 24478 7108 24478 7557 24479 7558 24479 6350 24479 7557 24480 6350 24480 6246 24480 7108 24481 6350 24481 7558 24481 7107 24482 7558 24482 7271 24482 6257 24483 6204 24483 7572 24483 7572 24484 7573 24484 6260 24484 7572 24485 6260 24485 6257 24485 6185 24486 6260 24486 7573 24486 6181 24487 6183 24487 7624 24487 7301 24488 7302 24488 7624 24488 7572 24489 6204 24489 5869 24489 6204 24490 6257 24490 7625 24490 6257 24491 6253 24491 7626 24491 6257 24492 7626 24492 7625 24492 7626 24493 6253 24493 6207 24493 6207 24494 6180 24494 7304 24494 5828 24495 7303 24495 5877 24495 5877 24496 7303 24496 6205 24496 7625 24497 5870 24497 5877 24497 7625 24498 5877 24498 6205 24498 6206 24499 6253 24499 7559 24499 7306 24500 6208 24500 6179 24500 6208 24501 6178 24501 6179 24501 7559 24502 5873 24502 6206 24502 6206 24503 5873 24503 5875 24503 7627 24504 6209 24504 6251 24504 6210 24505 7571 24505 7629 24505 7629 24506 6249 24506 6210 24506 6210 24507 7309 24507 7571 24507 6174 24508 6178 24508 7308 24508 6178 24509 6209 24509 7308 24509 7628 24510 7308 24510 6209 24510 5882 24511 7308 24511 7628 24511 7627 24512 5880 24512 5882 24512 7630 24513 6175 24513 6236 24513 6171 24514 6170 24514 6212 24514 7313 24515 6170 24515 6172 24515 6172 24516 6175 24516 7313 24516 7562 24517 6236 24517 7561 24517 7561 24518 6236 24518 6212 24518 6212 24519 7560 24519 7561 24519 7562 24520 5895 24520 7630 24520 6215 24521 6214 24521 7563 24521 7315 24522 6214 24522 6167 24522 7315 24523 6167 24523 6169 24523 7563 24524 7564 24524 6231 24524 6213 24525 6231 24525 7564 24525 6213 24526 5891 24526 5893 24526 6171 24527 6213 24527 5893 24527 7631 24528 6353 24528 6219 24528 6219 24529 6350 24529 7632 24529 6219 24530 7632 24530 7631 24530 7108 24531 7105 24531 7579 24531 7108 24532 7579 24532 7580 24532 7228 24533 7578 24533 7269 24533 6353 24534 7267 24534 7269 24534 6166 24535 6167 24535 7570 24535 6167 24536 6215 24536 7570 24536 7567 24537 6228 24537 7634 24537 5899 24538 5898 24538 7634 24538 7634 24539 5898 24539 7567 24539 7312 24540 6175 24540 6176 24540 6176 24541 7311 24541 7312 24541 6176 24542 6211 24542 7310 24542 7311 24543 6176 24543 7310 24543 6236 24544 6175 24544 7565 24544 7565 24545 7566 24545 6249 24545 7565 24546 6249 24546 6236 24546 6210 24547 6249 24547 7566 24547 6210 24548 7566 24548 5887 24548 5942 24549 5943 24549 6227 24549 5943 24550 6217 24550 6224 24550 6217 24551 7581 24551 6223 24551 5944 24552 7581 24552 6217 24552 6223 24553 7581 24553 6222 24553 6222 24554 7581 24554 7582 24554 6222 24555 7582 24555 6157 24555 7583 24556 5941 24556 6352 24556 7583 24557 6352 24557 6157 24557 5941 24558 5940 24558 6352 24558 6888 24559 6358 24559 6356 24559 6888 24560 6890 24560 6358 24560 6358 24561 6890 24561 6230 24561 6226 24562 6881 24562 6359 24562 6226 24563 6879 24563 6881 24563 6359 24564 6883 24564 6354 24564 6883 24565 6885 24565 6351 24565 6883 24566 6351 24566 6354 24566 6885 24567 6356 24567 6351 24567 6905 24568 6907 24568 6235 24568 6907 24569 6908 24569 6229 24569 6907 24570 6229 24570 6232 24570 6908 24571 6357 24571 6229 24571 6902 24572 6903 24572 6247 24572 6917 24573 6239 24573 6242 24573 6917 24574 6918 24574 6239 24574 6239 24575 6918 24575 6237 24575 6234 24576 6924 24576 6360 24576 6234 24577 6922 24577 6924 24577 6926 24578 6336 24578 6244 24578 6916 24579 6336 24579 6927 24579 6937 24580 6341 24580 6947 24580 6937 24581 6250 24581 6341 24581 6938 24582 6238 24582 6250 24582 6939 24583 6940 24583 6240 24583 6942 24584 6944 24584 6241 24584 6944 24585 6945 24585 6334 24585 6945 24586 6947 24586 6340 24586 6958 24587 6256 24587 6252 24587 6959 24588 6960 24588 6342 24588 6959 24589 6342 24589 6256 24589 6342 24590 6960 24590 6962 24590 6339 24591 6342 24591 6962 24591 6962 24592 6964 24592 6339 24592 6965 24593 6967 24593 6328 24593 6978 24594 6979 24594 6254 24594 6978 24595 6254 24595 6258 24595 6979 24596 6980 24596 6255 24596 6326 24597 6330 24597 6982 24597 6984 24598 6322 24598 6326 24598 6985 24599 6323 24599 6322 24599 6997 24600 6264 24600 7007 24600 6998 24601 6999 24601 6259 24601 6317 24602 6324 24602 7002 24602 7002 24603 7004 24603 6317 24603 7004 24604 7005 24604 6313 24604 7004 24605 6313 24605 6317 24605 7005 24606 7007 24606 6314 24606 7005 24607 6314 24607 6313 24607 7017 24608 6269 24608 7027 24608 7027 24609 6269 24609 6367 24609 7017 24610 7018 24610 6266 24610 7019 24611 6263 24611 6262 24611 6263 24612 7020 24612 7022 24612 6361 24613 7022 24613 6311 24613 7022 24614 7024 24614 6311 24614 7024 24615 7025 24615 6303 24615 7024 24616 6303 24616 6311 24616 7037 24617 6365 24617 7047 24617 7037 24618 7038 24618 6271 24618 7037 24619 6271 24619 6365 24619 7038 24620 7039 24620 6267 24620 7039 24621 6268 24621 6267 24621 6268 24622 7042 24622 6366 24622 7042 24623 7044 24623 6302 24623 7044 24624 7045 24624 6299 24624 7044 24625 6299 24625 6302 24625 7057 24626 7058 24626 6277 24626 7058 24627 7059 24627 6279 24627 7058 24628 6279 24628 6273 24628 7059 24629 6364 24629 6279 24629 6364 24630 7060 24630 7062 24630 7062 24631 7064 24631 6362 24631 7076 24632 7078 24632 6275 24632 7078 24633 6276 24633 6275 24633 7082 24634 7084 24634 6293 24634 7084 24635 7085 24635 6290 24635 7084 24636 6290 24636 6293 24636 6290 24637 7085 24637 6287 24637 7085 24638 7075 24638 6287 24638 6166 24639 5839 24639 5840 24639 5834 24640 7313 24640 5895 24640 5895 24641 7313 24641 7630 24641 7629 24642 5886 24642 5883 24642 7626 24643 5874 24643 5871 24643 7215 24644 7285 24644 6321 24644 6338 24645 7281 24645 7615 24645 7280 24646 7616 24646 7221 24646 7617 24647 7277 24647 7222 24647 7619 24648 7276 24648 7262 24648 6346 24649 7276 24649 7619 24649 7274 24650 7622 24650 7225 24650 7622 24651 7274 24651 7112 24651 7225 24652 7622 24652 7226 24652 7226 24653 7622 24653 7623 24653 7226 24654 7107 24654 7271 24654 5840 24655 5901 24655 6166 24655 7584 24656 5783 24656 5784 24656 7584 24657 5784 24657 7602 24657 7602 24658 5779 24658 6870 24658 5858 24659 7604 24659 7605 24659 7546 24660 6195 24660 5820 24660 5846 24661 6195 24661 7604 24661 7607 24662 5853 24662 7606 24662 5823 24663 5865 24663 7610 24663 5823 24664 7610 24664 5821 24664 5871 24665 5870 24665 7626 24665 5845 24666 7608 24666 5856 24666 6199 24667 5825 24667 7549 24667 5845 24668 6199 24668 7609 24668 6204 24669 5829 24669 5876 24669 6321 24670 7285 24670 6319 24670 6319 24671 7285 24671 7283 24671 7612 24672 6319 24672 7283 24672 7283 24673 7282 24673 7612 24673 7210 24674 7292 24674 7243 24674 7615 24675 7259 24675 7613 24675 7205 24676 7298 24676 7249 24676 7134 24677 7254 24677 6297 24677 6000 24678 7101 24678 5976 24678 6837 24679 6838 24679 7636 24679 7638 24680 6839 24680 6844 24680 6071 24681 6846 24681 6847 24681 6070 24682 6847 24682 6830 24682 6067 24683 6836 24683 6837 24683 6067 24684 6068 24684 6836 24684 6069 24685 6070 24685 6830 24685 6070 24686 6071 24686 6847 24686 6071 24687 6072 24687 6846 24687 6072 24688 7639 24688 6844 24688 7639 24689 7638 24689 6844 24689 7637 24690 7636 24690 6838 24690 6052 24691 6768 24691 6054 24691 6054 24692 6768 24692 6721 24692 6719 24693 6767 24693 6772 24693 6711 24694 6037 24694 6774 24694 6707 24695 6774 24695 6775 24695 6697 24696 6699 24696 6791 24696 6691 24697 6789 24697 6755 24697 6762 24698 6733 24698 6735 24698 6762 24699 6758 24699 6733 24699 6733 24700 6758 24700 6729 24700 6721 24701 6767 24701 6719 24701 6715 24702 6037 24702 6711 24702 6705 24703 6775 24703 6703 24703 6695 24704 6789 24704 6691 24704 6737 24705 6681 24705 6735 24705 6681 24706 6762 24706 6735 24706 6729 24707 6758 24707 6727 24707 6789 24708 6695 24708 6697 24708 6790 24709 6651 24709 6650 24709 6790 24710 6792 24710 6655 24710 6651 24711 6790 24711 6653 24711 7636 24712 6794 24712 6795 24712 6650 24713 7636 24713 6795 24713 6650 24714 7635 24714 7636 24714 6650 24715 6066 24715 7635 24715 7638 24716 6794 24716 7637 24716 7637 24717 6794 24717 7636 24717 7645 24718 7643 24718 7646 24718 7646 24719 7643 24719 7644 24719 7647 243 7645 243 7648 243 7652 24720 7649 24720 7650 24720 7642 24721 7641 24721 7652 24721 7641 24722 7651 24722 7652 24722 7656 24723 7653 24723 7655 24723 7657 24724 7654 24724 7658 24724 7658 24725 7654 24725 7653 24725 7658 24726 7642 24726 7657 24726 7642 24727 7659 24727 7657 24727 7656 24728 7660 24728 7659 24728 7661 243 7662 243 7663 243 7665 24729 7661 24729 7666 24729 7667 427 7665 427 7668 427 7668 427 7665 427 7666 427 7669 24730 7667 24730 7670 24730 7671 24731 7669 24731 7672 24731 7674 427 7671 427 7672 427 7675 24732 7673 24732 7676 24732 7677 7833 7678 7833 7679 7833 7679 24733 7678 24733 7680 24733 7681 243 7677 243 7682 243 7662 24734 7681 24734 7664 24734 7664 24735 7681 24735 7682 24735 7678 243 7683 243 7680 243 7685 243 7675 243 7686 243 7683 24736 7689 24736 7684 24736 7693 24737 7694 24737 7691 24737 7694 24738 7695 24738 7691 24738 7699 243 7697 243 7700 243 7700 243 7697 243 7698 243 7656 24739 7699 24739 7700 24739 7692 24740 7705 24740 7704 24740 7707 24741 7708 24741 7709 24741 7710 24742 7711 24742 7709 24742 7712 24743 7647 24743 7711 24743 7710 24744 7712 24744 7711 24744 7716 24745 7717 24745 7718 24745 7713 24746 7718 24746 7714 24746 7716 24747 7720 24747 7717 24747 7722 24748 7721 24748 7719 24748 7723 8265 7717 8265 7724 8265 7724 24749 7717 24749 7716 24749 7725 427 7723 427 7726 427 7726 427 7723 427 7724 427 7711 24750 7708 24750 7707 24750 7733 24751 7734 24751 7732 24751 7733 24752 7735 24752 7724 24752 7724 24753 7735 24753 7736 24753 7737 6 7724 6 7736 6 7737 24754 7738 24754 7666 24754 7666 6 7738 6 7668 6 7672 24755 7739 24755 7674 24755 7736 24756 7740 24756 7741 24756 7741 6 7743 6 7744 6 7742 6 7745 6 7746 6 7746 24757 7745 24757 7747 24757 7748 24758 7747 24758 7749 24758 7748 24759 7749 24759 7728 24759 7750 24760 7728 24760 7751 24760 7750 24761 7752 24761 7748 24761 7750 24762 7753 24762 7752 24762 7754 24763 7753 24763 7755 24763 7760 24764 7758 24764 7759 24764 7758 24765 7760 24765 7761 24765 7760 24766 7762 24766 7761 24766 7761 24767 7762 24767 7763 24767 7764 24768 7763 24768 7765 24768 7764 24769 7765 24769 7766 24769 7761 24770 7763 24770 7764 24770 7768 24771 7767 24771 7769 24771 7770 24772 7751 24772 7730 24772 7769 24773 7771 24773 7772 24773 7772 24774 7771 24774 7773 24774 7772 24775 7773 24775 7774 24775 7757 24776 7774 24776 7759 24776 7772 24777 7774 24777 7757 24777 7765 24778 7775 24778 7766 24778 7766 24779 7775 24779 7776 24779 7766 24780 7776 24780 7777 24780 7778 24781 7780 24781 7779 24781 7779 24782 7780 24782 7718 24782 7718 24783 7780 24783 7716 24783 7716 24784 7722 24784 7719 24784 7781 24785 7783 24785 7706 24785 7781 6 7784 6 7783 6 7781 6 7785 6 7784 6 7784 6 7785 6 7786 6 7784 24786 7786 24786 7787 24786 7788 24787 7784 24787 7787 24787 7785 6 7789 6 7786 6 7792 24788 7791 24788 7793 24788 7794 24789 7793 24789 7795 24789 7794 24790 7792 24790 7793 24790 7800 24791 7802 24791 7798 24791 7802 6 7804 6 7805 6 7805 24792 7804 24792 7806 24792 7806 24793 7807 24793 7808 24793 7806 6 7809 6 7807 6 7809 24794 7810 24794 7807 24794 7809 6 7811 6 7810 6 7810 24795 7811 24795 7812 24795 7813 24796 7810 24796 7812 24796 7813 24797 7815 24797 7698 24797 7815 24798 7816 24798 7817 24798 7817 24799 7816 24799 7818 24799 7821 24800 7819 24800 7820 24800 7821 24801 7822 24801 7819 24801 7825 24802 7826 24802 7824 24802 7826 6 7827 6 7828 6 7828 6 7827 6 7829 6 7830 24803 7833 24803 7832 24803 7830 6 7835 6 7834 6 7834 6 7835 6 7836 6 7838 6 7839 6 7837 6 7839 24804 7841 24804 7842 24804 7790 24805 7791 24805 7792 24805 7795 24806 7793 24806 7843 24806 7844 24807 7795 24807 7843 24807 7843 24808 7848 24808 7850 24808 7851 24809 7850 24809 7852 24809 7853 24810 7852 24810 7854 24810 7853 6 7856 6 7855 6 7843 24811 7850 24811 7851 24811 7857 24812 7854 24812 7674 24812 7858 24813 7859 24813 7860 24813 7861 24814 7862 24814 7863 24814 7863 24815 7862 24815 7864 24815 7870 24816 7872 24816 7871 24816 7871 6 7872 6 7873 6 7868 24817 7866 24817 7876 24817 7877 24818 7876 24818 7878 24818 7880 24819 7712 24819 7648 24819 7646 6 7653 6 7881 6 7646 24820 7644 24820 7658 24820 7684 24821 7642 24821 7680 24821 7684 24822 7688 24822 7686 24822 7882 24823 7884 24823 7883 24823 7894 24824 7895 24824 7893 24824 7894 24825 7896 24825 7895 24825 7894 24826 7897 24826 7896 24826 7896 24827 7897 24827 7898 24827 7867 24828 7865 24828 7866 24828 7861 24829 7896 24829 7898 24829 7901 24830 7902 24830 7903 24830 7901 24831 7904 24831 7902 24831 7904 24832 7905 24832 7906 24832 7907 24833 7906 24833 7905 24833 7910 24834 7911 24834 7912 24834 7914 24835 7913 24835 7915 24835 7916 24836 7917 24836 7914 24836 7917 24837 7916 24837 7918 24837 7913 24838 7903 24838 7915 24838 7919 24839 7903 24839 7902 24839 7818 24840 7921 24840 7820 24840 7818 24841 7920 24841 7921 24841 7824 24842 7822 24842 7823 24842 7698 6 7881 6 7700 6 7659 24843 7686 24843 7704 24843 7832 24844 7881 24844 7831 24844 7906 24845 7908 24845 7922 24845 7919 24846 7902 24846 7920 24846 7873 24847 7872 24847 7923 24847 7841 24848 7923 24848 7842 24848 7841 6 7873 6 7923 6 7806 6 7808 6 7805 6 7804 24849 7803 24849 7925 24849 7925 24850 7803 24850 7926 24850 7929 24851 7931 24851 7932 24851 7928 24852 7929 24852 7846 24852 7706 6 7783 6 7693 6 7829 6 7933 6 7934 6 7936 6 7835 6 7934 6 7936 6 7933 6 7937 6 7888 24853 7887 24853 7860 24853 7849 24854 7843 24854 7793 24854 7823 7968 7939 7968 7825 7968 7648 24855 7710 24855 7650 24855 7710 24856 7708 24856 7727 24856 7650 24857 7710 24857 7727 24857 7664 24858 7652 24858 7726 24858 7650 24859 7727 24859 7652 24859 7726 6 7724 6 7663 6 7663 6 7724 6 7666 6 7782 24860 7706 24860 7676 24860 7674 24861 7782 24861 7676 24861 7701 24862 7656 24862 7702 24862 7680 24863 7642 24863 7652 24863 7941 24864 7944 24864 7942 24864 7941 24865 7945 24865 7944 24865 7941 24866 7946 24866 7945 24866 7941 53 7947 53 7946 53 7949 24867 7947 24867 7948 24867 7950 24868 7947 24868 7949 24868 7950 24869 7951 24869 7947 24869 7950 53 1849 53 7951 53 7951 24870 1849 24870 7952 24870 7952 24871 1849 24871 7953 24871 7956 24872 7955 24872 7957 24872 7956 24873 7952 24873 7955 24873 7956 24874 7946 24874 7952 24874 1849 24875 1575 24875 7958 24875 7958 24876 1575 24876 7959 24876 7959 53 1575 53 7960 53 7959 24877 7961 24877 7962 24877 7963 24878 7961 24878 7964 24878 7963 24879 7962 24879 7961 24879 7966 24880 7953 24880 7962 24880 7966 24881 7954 24881 7953 24881 7960 24882 1575 24882 1889 24882 7967 24883 7960 24883 1889 24883 7967 24884 1886 24884 7968 24884 7968 24885 1886 24885 7969 24885 7969 24886 7970 24886 7964 24886 7970 24887 7971 24887 7972 24887 7972 24888 7973 24888 7970 24888 7973 24889 7972 24889 7974 24889 7968 24890 7969 24890 7964 24890 7968 24891 7964 24891 7961 24891 7973 24892 7974 24892 7983 24892 7984 53 7697 53 7973 53 7984 24893 7985 24893 7697 24893 7695 24894 7692 24894 7691 24894 7979 24895 7977 24895 7986 24895 7988 24896 7991 24896 7990 24896 7992 24897 7991 24897 7993 24897 5550 24898 7994 24898 5549 24898 5549 24899 7994 24899 7988 24899 7979 53 7986 53 7987 53 7986 24900 5549 24900 7988 24900 5550 24901 7995 24901 7992 24901 7992 24902 7995 24902 7996 24902 8000 24903 7998 24903 7999 24903 8000 53 8002 53 7989 53 7989 24904 8002 24904 8003 24904 7985 24905 7982 24905 8005 24905 7997 24906 8006 24906 8007 24906 8008 24907 7997 24907 8007 24907 8008 24908 8010 24908 8009 24908 8009 24909 8010 24909 8011 24909 8011 24910 8012 24910 8013 24910 8013 24911 8012 24911 8014 24911 8015 24912 8013 24912 8014 24912 7999 24913 8015 24913 8000 24913 8016 24914 8014 24914 8017 24914 8025 24915 8022 24915 8024 24915 8027 24916 8025 24916 8028 24916 8029 24917 8031 24917 8030 24917 8031 24918 8029 24918 8032 24918 8034 24919 8031 24919 8033 24919 7665 24920 8021 24920 8022 24920 7661 53 8022 53 7723 53 7725 24921 7662 24921 7661 24921 8026 24922 8024 24922 8035 24922 8036 24923 8035 24923 8032 24923 8038 24924 8033 24924 8032 24924 7451 53 8040 53 8039 53 8044 24925 8045 24925 8042 24925 8045 53 8046 53 8047 53 8040 24926 8048 24926 8039 24926 8041 24927 7448 24927 8042 24927 8050 24928 8051 24928 8044 24928 8051 24929 8050 24929 8052 24929 8053 24930 8051 24930 8052 24930 8053 24931 8054 24931 8051 24931 8054 24932 8053 24932 8055 24932 7717 53 8054 53 7714 53 7723 53 8022 53 8056 53 7714 24933 8055 24933 8057 24933 8058 53 8057 53 8059 53 8058 53 7714 53 8057 53 8058 24934 8061 24934 8060 24934 8058 24935 8062 24935 8061 24935 8064 24936 8066 24936 8067 24936 8072 24937 8060 24937 8070 24937 8072 53 7942 53 7944 53 8059 24938 8057 24938 8073 24938 8075 24939 8074 24939 8076 24939 8075 24940 8076 24940 8077 24940 8075 53 8077 53 8078 53 8079 24941 8065 24941 8078 24941 8077 24942 8076 24942 8080 24942 8080 24943 3701 24943 3702 24943 8081 24944 2465 24944 8082 24944 8083 24945 8082 24945 8079 24945 8077 24946 8083 24946 8079 24946 3742 24947 8084 24947 2465 24947 8084 24948 3742 24948 8068 24948 8088 24949 8086 24949 8087 24949 8089 24950 8088 24950 7943 24950 7943 24951 7942 24951 8090 24951 7996 24952 7997 24952 7998 24952 7999 24953 8013 24953 8015 24953 8091 24954 8089 24954 8090 24954 8091 24955 8090 24955 8071 24955 8048 24956 8045 24956 8047 24956 8003 24957 8004 24957 7982 24957 7705 24958 7692 24958 7675 24958 8081 24959 8082 24959 8083 24959 8092 24960 7699 24960 7654 24960 8092 24961 7697 24961 7699 24961 8092 53 8093 53 7697 53 7697 24962 8093 24962 7973 24962 8094 24963 7966 24963 7965 24963 7955 24964 8092 24964 7957 24964 7957 53 8092 53 8060 53 7990 24965 7991 24965 7992 24965 8033 24966 8039 24966 8034 24966 8095 24967 8096 24967 8054 24967 8056 24968 8095 24968 8054 24968 7990 24969 8001 24969 7989 24969 8064 24970 8063 24970 8062 24970 8030 24971 8046 24971 8095 24971 7717 24972 7720 24972 7721 24972 7711 24973 7707 24973 7709 24973 7714 53 8060 53 7647 53 7649 24974 7711 24974 7647 24974 7645 53 7647 53 8060 53 7655 24975 7701 24975 7703 24975 7660 24976 7703 24976 7685 24976 7703 24977 7705 24977 7685 24977 7687 53 7689 53 7685 53 7685 24978 7689 24978 7683 24978 7660 24979 7683 24979 7657 24979 7678 24980 7641 24980 7657 24980 7678 24981 7651 24981 7641 24981 7678 24982 7677 24982 7681 24982 7655 24983 7654 24983 7699 24983 8097 24984 8091 24984 8069 24984 8098 24985 8069 24985 8086 24985 8099 24986 8086 24986 8089 24986 8097 24987 8100 24987 8091 24987 8098 24988 8086 24988 8099 24988 8099 24989 8089 24989 8101 24989 8101 24990 8089 24990 8100 24990 8102 24991 8103 24991 7836 24991 7836 24992 8103 24992 7938 24992 7838 24993 8105 24993 8106 24993 7840 24994 8108 24994 8109 24994 7841 24995 8110 24995 8111 24995 7873 24996 8112 24996 8113 24996 7875 24997 8113 24997 8114 24997 7838 24998 8107 24998 7840 24998 7840 24999 8110 24999 7841 24999 7841 25000 8111 25000 7873 25000 7873 25001 8113 25001 7875 25001 8117 25002 8116 25002 8118 25002 8116 25003 8119 25003 8118 25003 8119 25004 8120 25004 8118 25004 8121 25005 8120 25005 8122 25005 8114 25006 8126 25006 7875 25006 7875 25007 8126 25007 7874 25007 7834 7838 8072 7838 7833 7838 7837 243 7942 243 7834 243 8071 25008 8090 25008 7839 25008 7833 427 8071 427 7839 427 7874 25009 8128 25009 7871 25009 3742 25010 8130 25010 8085 25010 8118 6 8121 6 8117 6 7946 25011 8133 25011 8134 25011 8133 25012 7946 25012 7947 25012 8135 25013 7951 25013 7952 25013 8133 25014 7947 25014 8137 25014 8137 25015 7947 25015 8135 25015 7957 8265 7944 8265 7830 8265 7830 8265 7944 8265 7835 8265 7835 25016 7945 25016 7934 25016 8138 25017 8139 25017 7937 25017 7940 25018 8141 25018 8142 25018 7825 25019 8143 25019 8144 25019 7827 25020 8144 25020 8145 25020 7933 25021 8149 25021 8150 25021 7937 25022 7933 25022 8138 25022 7940 25023 8142 25023 7825 25023 7827 25024 8145 25024 7935 25024 8153 25025 8152 25025 8154 25025 8157 25026 8158 25026 8159 25026 8159 25027 8158 25027 8160 25027 8156 25028 8160 25028 8161 25028 8155 25029 8156 25029 8161 25029 8162 25030 8157 25030 8159 25030 7939 25031 8140 25031 7940 25031 8154 25032 8152 25032 8164 25032 7948 25033 8166 25033 7949 25033 8166 25034 8167 25034 7949 25034 8167 25035 8168 25035 7950 25035 8162 25036 8159 25036 8154 25036 7810 25037 7983 25037 7975 25037 7784 25038 7982 25038 7985 25038 7814 25039 7983 25039 7810 25039 7807 25040 7978 25040 7808 25040 7808 25041 7980 25041 7788 25041 8013 25042 7999 25042 8169 25042 8169 25043 7999 25043 8170 25043 8171 25044 7999 25044 7997 25044 8172 25045 7997 25045 8009 25045 8173 25046 8009 25046 8011 25046 8174 25047 8011 25047 8013 25047 8170 25048 7999 25048 8171 25048 8172 25049 8009 25049 8173 25049 8173 25050 8011 25050 8174 25050 8177 25051 8028 25051 8025 25051 8178 25052 8025 25052 8026 25052 8179 25053 8036 25053 8032 25053 8177 25054 8025 25054 8178 25054 8178 25055 8036 25055 8179 25055 8095 25056 7728 25056 8030 25056 7732 25057 8095 25057 8056 25057 7732 25058 8056 25058 7733 25058 7735 25059 8022 25059 7740 25059 7740 25060 8022 25060 7745 25060 7745 25061 8022 25061 7747 25061 7747 25062 8027 25062 7749 25062 7749 25063 8030 25063 7728 25063 7772 25064 8049 25064 7769 25064 7756 25065 8034 25065 8039 25065 7769 25066 8047 25066 7770 25066 7770 25067 8047 25067 7751 25067 7753 25068 8031 25068 7755 25068 7755 25069 8034 25069 7756 25069 7756 25070 8039 25070 7757 25070 8001 25071 7794 25071 7998 25071 7797 25072 8001 25072 7799 25072 7847 25073 7992 25073 7996 25073 7795 25074 7996 25074 7998 25074 7794 25075 7795 25075 7998 25075 7932 25076 7990 25076 7929 25076 7847 25077 7996 25077 7845 25077 7845 25078 7996 25078 7795 25078 7803 25079 7988 25079 7994 25079 7927 25080 7994 25080 7993 25080 7800 25081 7991 25081 7988 25081 7926 25082 7994 25082 7927 25082 7927 25083 7993 25083 7930 25083 7801 25084 7991 25084 7800 25084 7787 25085 7981 25085 7924 25085 7924 25086 7981 25086 7979 25086 7802 25087 7979 25087 7987 25087 7798 25088 7987 25088 7989 25088 7924 25089 7979 25089 7805 25089 7798 25090 7989 25090 7796 25090 7796 25091 7989 25091 7792 25091 8081 25092 7894 25092 8080 25092 7894 25093 8081 25093 7897 25093 7898 25094 8081 25094 8083 25094 7894 25095 7892 25095 8080 25095 7859 25096 8077 25096 7889 25096 7832 25097 8070 25097 8060 25097 7878 25098 8060 25098 8061 25098 7877 25099 8061 25099 8063 25099 7868 25100 8063 25100 8064 25100 7870 25101 7868 25101 8064 25101 7923 25102 8070 25102 7842 25102 7832 25103 8060 25103 7880 25103 7880 25104 8060 25104 7878 25104 7877 25105 8063 25105 7868 25105 7920 25106 7965 25106 7963 25106 7919 25107 7963 25107 7964 25107 7812 25108 7970 25108 7973 25108 7816 25109 7973 25109 7965 25109 7920 25110 7963 25110 7919 25110 7918 25111 7970 25111 7812 25111 7812 25112 7973 25112 7813 25112 7813 25113 7973 25113 7816 25113 7953 25114 7922 25114 7821 25114 7953 25115 7958 25115 7922 25115 7906 25116 7958 25116 7959 25116 7902 25117 7959 25117 7962 25117 7922 25118 7958 25118 7906 25118 7906 25119 7959 25119 7904 25119 7955 25120 7828 25120 8092 25120 7955 25121 7826 25121 7828 25121 7826 25122 7955 25122 7824 25122 7819 25123 7954 25123 7966 25123 7815 25124 8094 25124 8093 25124 7828 25125 7831 25125 8092 25125 7824 25126 7954 25126 7822 25126 7815 25127 8093 25127 7881 25127 7881 25128 8092 25128 7831 25128 7961 25129 7905 25129 7901 25129 7907 25130 7960 25130 7967 25130 7910 25131 7967 25131 7968 25131 7903 25132 7968 25132 7961 25132 7905 25133 7960 25133 7907 25133 7910 25134 7968 25134 7913 25134 8084 25135 7899 25135 8082 25135 7869 25136 8084 25136 8068 25136 7863 25137 8066 25137 8079 25137 7861 25138 8079 25138 8082 25138 7899 25139 8084 25139 7900 25139 7900 25140 8084 25140 7869 25140 7869 25141 8066 25141 7867 25141 8078 25142 7858 25142 8075 25142 7864 25143 8078 25143 8065 25143 7876 25144 8065 25144 8062 25144 7879 25145 8062 25145 8058 25145 7882 25146 8058 25146 8059 25146 7858 25147 7860 25147 8075 25147 7882 25148 8059 25148 7886 25148 8005 25149 7781 25149 8014 25149 7785 25150 8004 25150 7789 25150 7791 25151 8004 25151 8002 25151 7848 25152 8000 25152 8015 25152 7852 25153 8015 25153 8014 25153 7789 25154 8004 25154 7791 25154 7793 25155 8000 25155 7849 25155 7849 25156 8000 25156 7848 25156 7848 25157 8015 25157 7850 25157 8044 25158 7775 25158 7765 25158 7729 25159 8054 25159 8096 25159 7730 25160 8096 25160 8046 25160 7765 25161 8046 25161 8044 25161 7776 25162 8051 25162 7778 25162 7730 25163 8046 25163 7768 25163 7768 25164 8046 25164 7765 25164 7767 25165 8042 25165 8045 25165 7759 25166 8048 25166 8040 25166 7762 25167 8041 25167 7763 25167 7763 25168 8042 25168 7767 25168 7771 25169 8048 25169 7773 25169 7773 25170 8048 25170 7774 25170 8182 25171 7743 25171 7742 25171 8183 25172 7742 25172 8184 25172 8183 25173 8182 25173 7742 25173 8184 25174 7746 25174 8189 25174 8185 25175 7748 25175 8190 25175 8128 25176 8192 25176 7871 25176 7871 25177 8192 25177 7895 25177 8192 25178 8193 25178 7895 25178 8193 25179 8194 25179 7895 25179 8194 25180 8195 25180 7893 25180 8197 25181 8198 25181 7885 25181 8198 25182 8199 25182 7884 25182 7884 25183 8199 25183 7883 25183 8199 25184 8200 25184 7779 25184 7779 25185 8200 25185 7777 25185 8200 25186 8201 25186 7777 25186 7777 25187 8201 25187 7766 25187 8204 25188 8205 25188 7761 25188 7761 25189 8205 25189 7758 25189 8205 25190 8206 25190 7758 25190 7758 25191 8206 25191 7754 25191 7754 25192 8206 25192 7752 25192 7752 25193 8206 25193 8187 25193 7743 7838 8180 7838 7744 7838 7744 7838 8180 7838 8207 7838 7741 25194 8207 25194 8208 25194 7736 25195 8208 25195 8209 25195 8210 8260 7737 8260 7736 8260 8210 25196 8211 25196 7737 25196 7738 243 8211 243 8212 243 7857 25197 8213 25197 8214 25197 7854 25198 8214 25198 8215 25198 7853 25199 8215 25199 8216 25199 7856 25200 7853 25200 8216 25200 7857 25197 8214 25197 7854 25197 7854 25198 8215 25198 7853 25198 8216 8265 8217 8265 7856 8265 8217 25201 8218 25201 7855 25201 7855 25202 8218 25202 8219 25202 7851 25203 8220 25203 8221 25203 7851 25204 8221 25204 8222 25204 7843 25205 8222 25205 8223 25205 7843 25206 8223 25206 8224 25206 7844 25207 8226 25207 8227 25207 7855 25208 8220 25208 7851 25208 8227 25209 8228 25209 7844 25209 7846 25210 8230 25210 7928 25210 8230 25211 8231 25211 7928 25211 7925 25212 8232 25212 7804 25212 7804 25213 8233 25213 7806 25213 8234 25214 8235 25214 7806 25214 7806 25215 8235 25215 7809 25215 8236 25216 8237 25216 7811 25216 7917 25217 8237 25217 7914 25217 8237 25218 8238 25218 7914 25218 7914 25219 8238 25219 7911 25219 8239 25220 8240 25220 7912 25220 8240 25221 8241 25221 7909 25221 7909 25222 8241 25222 7908 25222 8241 25223 8242 25223 7908 25223 8035 8287 8024 8287 8244 8287 8248 25224 8020 25224 8019 25224 8250 25225 8018 25225 8016 25225 8252 25226 8017 25226 8012 25226 8250 25227 8016 25227 8251 25227 8251 25228 8017 25228 8252 25228 8256 25229 8038 25229 8037 25229 8257 25230 8037 25230 8035 25230 8244 25231 8257 25231 8035 25231 8256 25232 8037 25232 8257 25232 8259 25233 7451 25233 8258 25233 8043 25234 7448 25234 8260 25234 8260 25235 7448 25235 8259 25235 8050 25236 8043 25236 8261 25236 8261 25237 8043 25237 8260 25237 8263 25238 8052 25238 8262 25238 8264 25239 8053 25239 8263 25239 8057 25240 8055 25240 8265 25240 8074 25241 8073 25241 8266 25241 8268 25242 8076 25242 8267 25242 8269 25243 3701 25243 8268 25243 3742 25244 2465 25244 8272 25244 8274 25245 1849 25245 8273 25245 1886 25246 1889 25246 8277 25246 8277 25247 1889 25247 8276 25247 7969 25248 1886 25248 8278 25248 8278 25249 1886 25249 8277 25249 7971 25250 7969 25250 8279 25250 8279 25251 7969 25251 8278 25251 8280 25252 7971 25252 8279 25252 7974 25253 7972 25253 8280 25253 7976 25254 7974 25254 8280 25254 8282 25255 7976 25255 8281 25255 7977 25256 7976 25256 8282 25256 5549 25257 7986 25257 8284 25257 8010 25258 8008 25258 8254 25258 8287 25259 8007 25259 8006 25259 8287 25260 8006 25260 7995 25260 8286 25261 8287 25261 7995 25261 8139 25262 8162 25262 8165 25262 8158 25263 8137 25263 8160 25263 8161 25264 8160 25264 8137 25264 8133 25265 8138 25265 8150 25265 8134 25266 8149 25266 8148 25266 8155 25267 8137 25267 8140 25267 8152 25268 8166 25268 8164 25268 8166 25269 8165 25269 8164 25269 8168 6 8163 6 8243 6 8242 25270 8241 25270 8273 25270 8276 25271 8240 25271 8277 25271 8277 25272 8239 25272 8238 25272 8237 6 8280 6 8279 6 8278 25273 8237 25273 8279 25273 8282 25274 8234 25274 8283 25274 8283 25275 8233 25275 8232 25275 8283 25276 8232 25276 8231 25276 8230 25277 8285 25277 8284 25277 8286 25278 8229 25278 8288 25278 8286 25279 8288 25279 8287 25279 8289 25280 8290 25280 8287 25280 8287 25281 8290 25281 8254 25281 8291 25282 8254 25282 8290 25282 8291 25283 8216 25283 8254 25283 8220 25284 8174 25284 8221 25284 8293 25285 8171 25285 8172 25285 8228 25286 8227 25286 8171 25286 8170 25287 8226 25287 8225 25287 8169 25288 8224 25288 8223 25288 8170 25289 8224 25289 8169 25289 8251 6 8214 6 8213 6 8250 25290 8213 25290 8212 25290 8248 6 8211 6 8210 6 8247 6 8210 6 8209 6 8246 25291 8209 25291 8208 25291 8244 6 8207 6 8294 6 8295 25292 8244 25292 8294 25292 8297 25293 8206 25293 8255 25293 8297 25294 8298 25294 8187 25294 8184 25295 8177 25295 8183 25295 8184 25296 8189 25296 8177 25296 8252 25297 8214 25297 8251 25297 8251 25298 8213 25298 8250 25298 8249 25299 8211 25299 8248 25299 8248 25300 8210 25300 8247 25300 8247 25301 8209 25301 8246 25301 8178 25302 8180 25302 8181 25302 8178 25303 8181 25303 8182 25303 8177 25304 8178 25304 8182 25304 8190 25305 8186 25305 8176 25305 8188 25306 8187 25306 8175 25306 8260 25307 8203 25307 8202 25307 8261 25308 8201 25308 8262 25308 8199 25309 8264 25309 8200 25309 8265 25310 8199 25310 8198 25310 8266 25311 8198 25311 8197 25311 8268 25312 8196 25312 8195 25312 8265 25313 8198 25313 8266 25313 8267 25314 8196 25314 8268 25314 8268 25315 8195 25315 8269 25315 8270 25316 8194 25316 8271 25316 8126 25317 8116 25317 8130 25317 8116 6 8114 6 8119 6 8101 25318 8104 25318 8103 25318 8101 25319 8103 25319 8124 25319 8127 25320 8132 25320 8131 25320 8300 25321 8288 25321 8301 25321 8293 25322 8292 25322 8301 25322 8303 25323 8292 25323 8291 25323 8291 25324 8290 25324 8303 25324 8303 25325 8290 25325 8304 25325 8289 25326 8288 25326 8304 25326 8304 25327 8288 25327 8300 25327 8295 25328 8294 25328 8305 25328 8294 25329 8299 25329 8305 25329 8305 25330 8299 25330 8306 25330 8307 25331 8298 25331 8308 25331 8308 25332 8298 25332 8297 25332 8297 25333 8296 25333 8308 25333 8308 25334 8296 25334 8309 25334 8309 25335 8295 25335 8305 25335 8305 6 8306 6 8307 6 8307 25336 8309 25336 8305 25336 8312 25337 8311 25337 8313 25337 8314 25338 8315 25338 8316 25338 8317 25339 8316 25339 8318 25339 8319 25340 8317 25340 8318 25340 8319 6 8322 6 8321 6 8324 25341 8323 25341 8322 25341 8323 25342 8325 25342 8326 25342 8327 25343 8325 25343 8328 25343 8329 6 8327 6 8328 6 8318 25344 8316 25344 8330 25344 8331 25345 8330 25345 8332 25345 8332 25346 8333 25346 8334 25346 8312 25347 8333 25347 8310 25347 8318 25348 8330 25348 8331 25348 8335 25349 8336 25349 8337 25349 8335 25350 8338 25350 8336 25350 8339 25351 8336 25351 8338 25351 8339 25352 8340 25352 8336 25352 8343 25353 8344 25353 8345 25353 8345 25354 8344 25354 8346 25354 8347 25355 8348 25355 8346 25355 8349 25356 8347 25356 8335 25356 8349 25357 8335 25357 8350 25357 8320 25358 8350 25358 8351 25358 8345 25359 8346 25359 8348 25359 8355 25360 8356 25360 8353 25360 8357 6 8359 6 8358 6 8355 25361 8362 25361 8363 25361 8363 25362 8362 25362 8364 25362 8364 25363 8366 25363 8365 25363 8368 25364 8367 25364 8369 25364 8370 25365 8368 25365 8369 25365 8369 25366 8371 25366 8372 25366 8375 25367 8376 25367 8356 25367 8356 25368 8376 25368 8353 25368 8369 25369 8377 25369 8370 25369 8370 25370 8377 25370 8378 25370 8380 6 8378 6 8379 6 8381 25371 8384 25371 8383 25371 8383 25372 8384 25372 8385 25372 8386 6 8387 6 8385 6 8386 6 8388 6 8387 6 8387 6 8388 6 8389 6 8390 25373 8391 25373 8392 25373 8393 25374 8390 25374 8392 25374 8383 25375 8387 25375 8351 25375 8350 6 8383 6 8351 6 8383 25376 8394 25376 8395 25376 8395 6 8394 6 8396 6 8396 25377 8394 25377 8397 25377 8377 25378 8382 25378 8379 25378 8398 25379 8396 25379 8397 25379 8402 6 8399 6 8403 6 8403 25380 8399 25380 8404 25380 8407 6 8408 6 8405 6 8407 25381 8409 25381 8408 25381 8408 6 8409 6 8410 6 8327 6 8326 6 8325 6 8403 25382 8404 25382 8405 25382 8321 25383 8411 25383 8320 25383 8412 25384 8411 25384 8401 25384 8412 25385 8401 25385 8413 25385 8414 25386 2398 25386 8412 25386 2398 25387 8414 25387 8415 25387 8415 25388 8414 25388 2396 25388 8413 25389 8401 25389 8400 25389 8351 6 8416 6 8352 6 8418 25390 8419 25390 2396 25390 8419 6 8418 6 8402 6 6087 25391 8420 25391 8422 25391 6078 25392 8423 25392 8424 25392 7319 25393 8424 25393 7317 25393 8425 25394 7317 25394 8424 25394 8425 6 8426 6 7317 6 8422 6 8426 6 8425 6 8427 6 8380 6 8379 6 8429 6 8427 6 8421 6 8430 6 8421 6 6087 6 8405 25395 8408 25395 8431 25395 8432 6 8419 6 8433 6 8432 25396 2396 25396 8419 25396 8408 6 8434 6 8431 6 8435 6 8431 6 8434 6 8435 6 8434 6 8329 6 8325 6 8436 6 8328 6 8436 25397 8437 25397 1755 25397 8438 6 8324 6 8322 6 1755 25398 8437 25398 8438 25398 8439 6 8440 6 8441 6 4230 25399 8442 25399 4231 25399 8440 25400 8439 25400 4232 25400 4218 25401 8446 25401 8447 25401 8389 6 8441 6 8391 6 8447 25402 8446 25402 8448 25402 8448 25403 8446 25403 8359 25403 8368 25404 8365 25404 8367 25404 8440 6 8391 6 8441 6 8317 25405 8314 25405 8316 25405 8320 25406 8349 25406 8350 25406 8337 25407 8350 25407 8335 25407 8430 25408 8450 25408 8429 25408 8451 25409 8429 25409 8450 25409 8451 25410 8428 25410 8429 25410 8447 25411 8448 25411 8452 25411 8452 25412 8448 25412 8453 25412 8448 25413 8361 25413 8454 25413 8449 25414 8430 25414 8455 25414 6087 25415 6078 25415 8455 25415 8455 25416 6078 25416 8456 25416 8447 25417 8452 25417 4218 25417 4218 25418 8452 25418 8457 25418 8458 25419 8459 25419 4218 25419 4218 25420 8459 25420 4231 25420 8380 25421 8460 25421 8461 25421 8460 25422 8380 25422 8428 25422 8378 25423 8462 25423 8370 25423 8462 25424 8368 25424 8370 25424 8462 25425 8463 25425 8368 25425 8368 25426 8463 25426 8365 25426 8463 25427 8464 25427 8365 25427 8363 25428 8365 25428 8464 25428 8360 25429 8465 25429 8361 25429 8466 25430 8465 25430 8360 25430 8454 25431 8361 25431 8465 25431 8357 25432 8469 25432 8360 25432 8355 25433 8468 25433 8357 25433 8470 25434 8310 25434 8471 25434 8311 25435 8472 25435 8473 25435 8315 25436 8473 25436 8474 25436 8316 25437 8474 25437 8475 25437 8332 25438 8471 25438 8310 25438 8315 25439 8474 25439 8316 25439 8346 25440 8483 25440 8484 25440 8339 25441 8481 25441 8341 25441 8346 25442 8484 25442 8347 25442 8317 8495 8485 8495 8486 8495 8314 25443 8486 25443 8487 25443 8487 25444 8488 25444 8314 25444 8314 25445 8488 25445 8313 25445 8319 25446 8318 25446 8490 25446 8491 25447 8492 25447 8319 25447 8350 8502 8494 8502 8495 8502 8394 25448 8495 25448 8496 25448 8394 25448 8350 25448 8495 25448 8336 25449 8493 25449 8337 25449 8496 25450 8497 25450 8394 25450 8394 25451 8497 25451 8397 25451 8498 25452 8340 25452 8342 25452 8343 25453 8501 25453 8500 25453 8449 25454 8455 25454 8502 25454 8505 25455 8455 25455 8506 25455 8508 25456 8509 25456 8510 25456 8510 25457 8512 25457 8511 25457 8510 25458 8497 25458 8512 25458 8512 25459 8497 25459 8513 25459 8513 25460 8496 25460 8514 25460 8456 25461 8515 25461 8455 25461 8456 25462 8516 25462 8515 25462 8517 25463 8516 25463 8456 25463 8517 25464 8518 25464 8516 25464 8517 25465 8520 25465 8519 25465 8521 25466 8520 25466 8509 25466 8495 53 8522 53 8496 53 8495 25467 8523 25467 8522 25467 8495 25468 8486 25468 8523 25468 8495 25469 8491 25469 8486 25469 8495 53 8524 53 8491 53 8495 53 8525 53 8524 53 8479 25470 8477 25470 8493 25470 8493 25471 8499 25471 8479 25471 8481 25472 8498 25472 8482 25472 8483 25473 8501 25473 8526 25473 8480 25474 8499 25474 8481 25474 8527 25475 8528 25475 8524 25475 8527 25476 8529 25476 8528 25476 8530 25477 8529 25477 8527 25477 8535 25478 8534 25478 8536 25478 8537 25479 8538 25479 8536 25479 8539 25480 8537 25480 8540 25480 8541 25481 8530 25481 8539 25481 8539 25482 8530 25482 8527 25482 8542 25483 8543 25483 8535 25483 8542 25484 8546 25484 8545 25484 8545 25485 8546 25485 8547 25485 8548 53 8545 53 8547 53 8548 25486 8528 25486 8550 25486 8528 53 8551 53 8524 53 8554 25487 8553 25487 8552 25487 8552 25488 8555 25488 8554 25488 8554 25489 8555 25489 8556 25489 8556 25490 8555 25490 8557 25490 8559 25491 8558 25491 8560 25491 8551 25492 8492 25492 8491 25492 8564 25493 8565 25493 8563 25493 8486 25494 8490 25494 8474 25494 8487 25495 8474 25495 8473 25495 8470 25496 8488 25496 8472 25496 8470 25497 8567 25497 8488 25497 8567 25498 8470 25498 8471 25498 8475 25499 8490 25499 8489 25499 8475 25500 8489 25500 8568 25500 8476 25501 8475 25501 8568 25501 8476 25502 8568 25502 8569 25502 8471 25503 8476 25503 8569 25503 8569 25504 8567 25504 8471 25504 8488 25505 8487 25505 8472 25505 8487 25506 8486 25506 8474 25506 8486 53 8485 53 8523 53 8573 53 8572 53 8574 53 8575 53 8574 53 8576 53 8577 25507 8575 25507 8576 25507 8580 25508 8579 25508 8581 25508 8580 53 8582 53 8511 53 8512 25509 8580 25509 8511 25509 8574 53 8572 53 8583 53 8588 25510 8587 25510 8458 25510 8589 25511 8458 25511 8590 25511 8593 25512 8459 25512 8594 25512 8594 25513 8458 25513 8587 25513 8592 25514 8591 25514 8593 25514 8458 25515 8457 25515 8590 25515 8590 25516 8457 25516 8595 25516 8595 25517 8457 25517 8452 25517 8453 25518 8595 25518 8452 25518 8453 25519 8596 25519 8595 25519 8465 25520 8596 25520 8454 25520 8465 53 8466 53 8597 53 8598 25521 8467 25521 8468 25521 8598 25522 8468 25522 8600 25522 8601 25523 8600 25523 8602 25523 8602 25524 8603 25524 8604 25524 8602 25525 8605 25525 8603 25525 8603 25526 8605 25526 8606 25526 8582 53 8606 53 8462 53 8582 53 8462 53 8461 53 8609 25527 8464 25527 8463 25527 8582 25528 8461 25528 8607 25528 8511 53 8582 53 8607 53 8598 25529 8600 25529 8601 25529 8601 25530 8602 25530 8604 25530 8523 25531 8580 25531 8522 25531 8582 25532 8603 25532 8606 25532 8612 25533 8610 25533 8532 25533 8611 25534 8610 25534 8612 25534 8612 25535 8532 25535 8533 25535 8559 25536 8613 25536 8558 25536 8614 25537 8613 25537 8549 25537 8547 25538 8615 25538 8549 25538 8535 25539 8533 25539 8534 25539 8455 25540 8515 25540 8507 25540 8557 25541 8558 25541 8613 25541 8546 25542 8553 25542 8547 25542 8320 25543 8524 25543 8349 25543 8349 25544 8525 25544 8348 25544 8331 25545 8334 25545 8489 25545 8313 25546 8488 25546 8312 25546 8524 25547 8412 25547 8527 25547 7317 25548 8517 25548 7319 25548 7317 25549 8426 25549 8517 25549 8426 25550 8510 25550 8520 25550 8440 25551 8584 25551 8391 25551 8391 25552 8584 25552 8572 25552 8392 25553 8391 25553 8572 25553 8352 25554 8392 25554 8485 25554 8584 25555 4232 25555 8591 25555 6078 25556 8517 25556 8456 25556 4230 25557 4231 25557 8459 25557 8552 25558 8546 25558 8431 25558 8431 25559 8542 25559 8432 25559 8542 25560 8538 25560 8432 25560 8432 25561 8538 25561 2396 25561 2398 25562 8415 25562 8539 25562 8527 25563 8412 25563 8539 25563 8336 25564 8340 25564 8493 25564 8333 25565 8312 25565 8569 25565 8415 25566 8538 25566 8539 25566 8354 25567 8599 25567 8362 25567 8353 25568 8376 25568 8600 25568 8366 25569 8606 25569 8367 25569 8600 25570 8599 25570 8354 25570 8375 25571 8604 25571 8603 25571 8372 25572 8603 25572 8582 25572 8384 25573 8581 25573 8579 25573 8385 25574 8579 25574 8578 25574 8388 25575 8576 25575 8358 25575 8356 25576 8601 25576 8375 25576 8369 25577 8582 25577 8377 25577 8377 25578 8581 25578 8381 25578 8381 25579 8581 25579 8384 25579 8385 25580 8577 25580 8386 25580 8576 25581 8598 25581 8358 25581 8514 25582 8383 25582 8395 25582 8512 25583 8398 25583 8580 25583 8610 25584 8406 25584 8404 25584 8532 25585 8404 25585 8399 25585 8610 25586 8404 25586 8532 25586 8532 25587 8399 25587 8529 25587 8321 25588 8551 25588 8407 25588 8549 25589 8326 25589 8409 25589 8548 25590 8409 25590 8407 25590 8551 25591 8548 25591 8407 25591 8559 25592 8323 25592 8613 25592 8613 25593 8326 25593 8549 25593 8387 25594 8573 25594 8575 25594 8571 25595 8390 25595 8393 25595 8571 25596 8393 25596 8417 25596 8570 25597 8417 25597 8416 25597 8523 25598 8416 25598 8351 25598 8575 8642 8351 8642 8387 8642 8573 25599 8390 25599 8571 25599 8571 25600 8417 25600 8570 25600 8570 25601 8416 25601 8523 25601 8434 25602 8553 25602 8329 25602 8329 25603 8554 25603 8556 25603 8327 25604 8556 25604 8557 25604 8408 25605 8615 25605 8547 25605 8434 25606 8408 25606 8547 25606 8329 25607 8556 25607 8327 25607 8410 25608 8615 25608 8408 25608 8558 25609 8325 25609 8560 25609 8436 25610 8558 25610 8562 25610 8437 25611 8563 25611 8565 25611 8437 25612 8565 25612 8566 25612 8325 25613 8324 25613 8560 25613 8436 25614 8563 25614 8437 25614 8585 25615 8586 25615 8439 25615 8442 25616 8586 25616 8592 25616 8442 25617 8592 25617 8593 25617 8443 25618 8593 25618 8594 25618 8441 25619 8594 25619 8587 25619 8439 25620 8441 25620 8585 25620 8439 25621 8586 25621 8442 25621 8442 25622 8593 25622 8443 25622 8389 25623 8583 25623 8444 25623 8446 25624 8590 25624 8595 25624 8359 25625 8595 25625 8596 25625 8359 25626 8596 25626 8597 25626 8389 25627 8359 25627 8597 25627 8379 25628 8506 25628 8508 25628 8379 25629 8508 25629 8511 25629 8379 25630 8511 25630 8607 25630 8379 25631 8607 25631 8427 25631 8518 25632 8424 25632 8516 25632 8425 25633 8518 25633 8519 25633 8422 25634 8521 25634 8509 25634 8422 25635 8509 25635 8507 25635 8423 25636 8507 25636 8515 25636 8422 25637 8507 25637 8423 25637 8423 25638 8515 25638 8424 25638 8433 25639 8543 25639 8544 25639 8405 25640 8544 25640 8545 25640 8402 25641 8612 25641 8533 25641 8419 25642 8533 25642 8535 25642 8433 25643 8544 25643 8405 25643 8402 25644 8533 25644 8419 25644 8536 25645 8414 25645 8537 25645 8536 25646 8418 25646 8414 25646 8413 25647 8531 25647 8530 25647 8414 25648 8541 25648 8540 25648 8418 25649 8534 25649 8400 25649 8400 25650 8531 25650 8413 25650 529 25651 8555 25651 8328 25651 8435 25652 8328 25652 8552 25652 8552 25653 8328 25653 8555 25653 8618 8265 8617 8265 8619 8265 8620 427 8616 427 8621 427 8621 427 8616 427 8618 427 8622 25654 8620 25654 8623 25654 8623 25654 8620 25654 8621 25654 8624 7838 8622 7838 8625 7838 8625 7838 8622 7838 8623 7838 8626 25655 8627 25655 8628 25655 8628 25656 8629 25656 8630 25656 8631 25657 8630 25657 8632 25657 8633 25658 8632 25658 8634 25658 8641 25659 8640 25659 8642 25659 8645 25660 8644 25660 8646 25660 8647 25661 8646 25661 8648 25661 8649 25662 8648 25662 8650 25662 8651 25663 8650 25663 8652 25663 8653 25664 8652 25664 8654 25664 8655 25665 8654 25665 8656 25665 8657 25666 8656 25666 8624 25666 8625 25667 8658 25667 8657 25667 8657 25668 8658 25668 8655 25668 8660 25669 8633 25669 8661 25669 8633 25670 8634 25670 8635 25670 8661 25671 8635 25671 8662 25671 8661 25672 8633 25672 8635 25672 8635 25673 8636 25673 8637 25673 8663 25674 8637 25674 8639 25674 8639 25675 8640 25675 8641 25675 8664 25676 8641 25676 8665 25676 8665 25677 8643 25677 8666 25677 8665 25678 8641 25678 8643 25678 8645 25679 8646 25679 8647 25679 8667 25680 8647 25680 8668 25680 8667 25681 8645 25681 8647 25681 8647 25682 8648 25682 8649 25682 8668 25683 8649 25683 8669 25683 8649 25684 8650 25684 8651 25684 8651 25685 8652 25685 8653 25685 8670 25686 8653 25686 8671 25686 8670 25687 8651 25687 8653 25687 8653 25688 8654 25688 8655 25688 8671 25689 8655 25689 8658 25689 8673 8265 8627 8265 8626 8265 8674 25690 8672 25690 8675 25690 8675 25691 8672 25691 8673 25691 8678 7838 8676 7838 8679 7838 8679 7838 8676 7838 8677 7838 8679 25692 8665 25692 8619 25692 8679 25693 8664 25693 8665 25693 8679 25694 8663 25694 8664 25694 8679 25695 8660 25695 8661 25695 8679 25696 8659 25696 8660 25696 8679 25697 8675 25697 8673 25697 8668 25698 8619 25698 8667 25698 8668 53 8669 53 8619 53 8619 53 8669 53 8670 53 8671 53 8619 53 8670 53 8671 25699 8658 25699 8623 25699 8617 25700 8642 25700 8678 25700 8617 25701 8644 25701 8642 25701 8617 6 8622 6 8654 6 8617 25702 8620 25702 8622 25702 8617 6 8616 6 8620 6 8642 6 8640 6 8678 6 8678 25703 8640 25703 8638 25703 8636 6 8678 6 8638 6 8630 25704 8672 25704 8678 25704 8672 6 8629 6 8627 6 8678 6 8674 6 8676 6 8682 25705 8681 25705 8683 25705 8684 25706 8685 25706 8686 25706 8680 25707 8684 25707 8681 25707 8686 25708 8687 25708 8681 25708 8688 25709 8690 25709 8684 25709 8692 25710 8690 25710 8693 25710 8694 25711 8692 25711 8693 25711 8694 25712 8693 25712 8695 25712 8695 25713 8680 25713 8682 25713 8695 25714 8689 25714 8680 25714 8680 25715 8689 25715 8684 25715 8697 25716 8695 25716 8693 25716 8698 25717 8697 25717 8693 25717 8693 25718 8690 25718 8698 25718 8698 25719 8690 25719 8699 25719 8699 25720 8690 25720 8700 25720 8695 25721 8697 25721 8689 25721 8703 25722 8704 25722 8685 25722 8685 25723 8704 25723 8686 25723 8704 25724 8702 25724 8686 25724 8707 25725 8706 25725 8708 25725 8702 25726 8707 25726 8708 25726 8706 25727 8709 25727 8708 25727 8710 25728 8711 25728 8712 25728 8713 25729 8705 25729 8715 25729 8717 25730 8691 25730 8692 25730 8720 25731 8719 25731 8721 25731 8718 25732 8722 25732 8719 25732 8724 25733 8725 25733 8723 25733 8723 25734 8725 25734 8726 25734 8709 25735 8721 25735 8711 25735 8723 25736 8713 25736 8719 25736 8723 25737 8726 25737 8713 25737 8713 25738 8726 25738 8705 25738 8727 25739 8730 25739 8728 25739 8727 25740 8731 25740 8730 25740 8733 25741 8732 25741 8734 25741 8074 25742 8076 25742 8733 25742 8730 25743 8736 25743 8728 25743 8730 25744 8732 25744 8733 25744 8731 25745 8737 25745 8732 25745 8734 25746 8738 25746 8739 25746 8737 25747 8741 25747 8738 25747 8739 25748 8742 25748 8743 25748 8740 25749 8743 25749 8744 25749 8740 25750 8739 25750 8743 25750 8741 25751 8745 25751 8742 25751 8743 25752 8746 25752 8747 25752 8746 25753 8749 25753 8750 25753 8752 25754 8712 25754 8714 25754 8753 25755 8714 25755 8754 25755 8755 25756 8753 25756 8754 25756 8756 25757 8757 25757 8758 25757 8759 25758 8758 25758 8760 25758 8761 25759 8759 25759 8760 25759 8761 25760 8762 25760 8759 25760 8765 25761 8766 25761 8762 25761 8767 25762 8766 25762 8768 25762 8767 25763 8769 25763 8762 25763 8758 25764 8759 25764 8756 25764 8710 25765 8712 25765 8750 25765 8771 25766 8752 25766 8772 25766 8055 25767 8772 25767 8053 25767 8055 25768 8773 25768 8771 25768 8771 25769 8773 25769 8747 25769 8752 25770 8714 25770 8753 25770 8052 25771 8053 25771 8772 25771 8769 25772 8775 25772 8770 25772 8770 25773 8775 25773 8050 25773 8736 25774 8778 25774 8728 25774 8762 25775 8770 25775 8759 25775 8747 25776 8751 25776 8771 25776 8771 25777 8751 25777 8752 25777 8739 25778 8738 25778 8742 25778 8734 25779 8732 25779 8738 25779 8727 25780 8780 25780 8731 25780 8758 25781 8757 25781 8760 25781 8757 25782 8781 25782 8760 25782 8757 25783 8755 25783 8754 25783 8783 25784 8698 25784 8784 25784 8783 25785 8784 25785 8785 25785 8786 25786 8787 25786 8783 25786 8783 25787 8787 25787 8788 25787 8789 25788 8790 25788 8791 25788 8792 25789 8790 25789 8793 25789 8791 25790 8794 25790 8795 25790 8796 25791 8697 25791 8783 25791 8784 25792 8699 25792 8797 25792 8800 25793 8798 25793 8799 25793 8802 25794 8803 25794 8804 25794 8805 25795 8804 25795 8806 25795 8801 25796 8808 25796 8785 25796 8801 25797 8802 25797 8805 25797 8810 25798 8797 25798 8809 25798 8814 25799 8813 25799 8811 25799 8815 25800 8814 25800 8816 25800 8809 25801 8700 25801 8817 25801 8821 25802 8814 25802 8822 25802 8823 25803 8818 25803 8701 25803 8820 25804 8823 25804 8701 25804 8701 25805 8818 25805 8819 25805 8813 25806 8814 25806 8815 25806 8825 25807 8826 25807 8827 25807 8828 25808 8825 25808 8827 25808 8828 25809 8830 25809 8829 25809 8832 25810 8834 25810 8835 25810 8836 25811 8837 25811 8834 25811 8836 25812 8838 25812 8837 25812 8836 25813 8786 25813 8838 25813 8838 25814 8786 25814 8785 25814 8783 25815 8788 25815 8839 25815 8790 25816 8840 25816 8793 25816 8840 25817 8833 25817 8841 25817 8847 25818 8848 25818 8845 25818 8847 25819 8849 25819 8848 25819 8847 25820 8850 25820 8849 25820 8849 25821 8850 25821 8851 25821 8851 25822 8852 25822 8849 25822 8856 25823 8855 25823 8857 25823 8858 25824 8844 25824 8859 25824 8860 25825 8859 25825 8861 25825 8862 25826 8860 25826 8861 25826 8862 25827 8856 25827 8860 25827 8862 25828 8863 25828 8856 25828 8867 25829 8864 25829 8866 25829 8867 25830 8869 25830 8806 25830 8871 25831 8861 25831 8859 25831 8872 25832 8859 25832 8844 25832 8846 25833 8872 25833 8844 25833 8868 25834 8870 25834 8871 25834 8874 25835 8804 25835 8803 25835 8874 25836 8873 25836 8804 25836 8875 25837 8706 25837 8689 25837 8875 25838 8709 25838 8706 25838 8689 25839 8705 25839 8688 25839 8688 25840 8726 25840 8876 25840 8820 25841 8688 25841 8876 25841 8877 25842 8879 25842 8878 25842 8878 25843 8879 25843 8880 25843 8725 25844 8876 25844 8726 25844 8883 25845 8826 25845 8882 25845 8882 25846 8826 25846 8825 25846 8831 25847 8830 25847 8884 25847 8784 25848 8797 25848 8798 25848 8858 25849 8860 25849 8856 25849 8885 25850 8852 25850 8886 25850 8885 25851 8886 25851 8887 25851 8849 25852 8852 25852 8885 25852 8888 25853 8889 25853 8849 25853 8872 25854 8871 25854 8859 25854 8864 25855 8806 25855 8804 25855 8893 25856 8894 25856 8892 25856 8837 25857 8892 25857 8894 25857 8895 25858 8837 25858 8894 25858 8896 25859 8897 25859 8898 25859 8841 25860 8793 25860 8840 25860 8899 25861 8900 25861 8901 25861 8901 25862 8795 25862 8899 25862 8899 25863 8795 25863 8794 25863 8696 25864 8717 25864 8910 25864 8911 25865 8910 25865 8717 25865 8716 25866 8912 25866 8717 25866 8716 25867 8913 25867 8912 25867 8716 25868 8914 25868 8913 25868 8914 25869 8716 25869 8683 25869 8685 25870 8916 25870 8917 25870 8685 25871 8696 25871 8916 25871 8921 25872 8922 25872 8920 25872 8754 25873 8921 25873 8923 25873 8921 25874 8715 25874 8922 25874 8922 25875 8715 25875 8707 25875 8919 25876 8918 25876 8924 25876 8920 25877 8919 25877 8924 25877 8918 25878 8908 25878 8907 25878 8925 25879 8681 25879 8926 25879 8929 25880 8928 25880 8930 25880 8929 25881 8932 25881 8931 25881 8929 25882 8933 25882 8932 25882 8935 25883 8933 25883 8936 25883 8928 25884 8710 25884 8750 25884 8741 25885 8937 25885 8745 25885 8937 25886 8741 25886 8938 25886 8928 25887 8750 25887 8930 25887 8930 25888 8749 25888 8745 25888 8937 25889 8930 25889 8745 25889 8933 25890 8939 25890 8936 25890 8941 25891 8943 25891 8942 25891 8945 25892 8946 25892 8947 25892 8948 25893 8945 25893 8947 25893 8948 25894 8949 25894 8945 25894 8948 25895 8950 25895 8949 25895 8949 25896 8950 25896 8951 25896 8952 25897 8953 25897 8949 25897 8945 25898 8944 25898 8946 25898 8959 25899 8960 25899 8961 25899 8962 25900 8964 25900 8963 25900 8962 25901 8965 25901 8964 25901 8975 25902 8976 25902 8970 25902 8975 25903 8977 25903 8976 25903 8970 25904 8976 25904 8971 25904 8971 25905 8976 25905 8978 25905 8971 25906 8978 25906 8979 25906 8971 25907 8979 25907 8973 25907 8978 25908 8982 25908 8979 25908 8965 25909 8985 25909 8964 25909 8986 25910 8987 25910 8946 25910 8946 25911 8987 25911 8947 25911 8940 25912 8913 25912 8990 25912 8991 25913 8992 25913 8990 25913 8992 25914 8991 25914 8993 25914 8932 25915 8995 25915 8931 25915 8911 25916 8717 25916 8912 25916 8754 25917 8923 25917 8996 25917 8997 25918 8763 25918 8761 25918 8997 25919 8998 25919 8763 25919 8764 25920 8998 25920 8999 25920 8757 25921 9000 25921 8781 25921 8919 25922 8707 25922 8703 25922 8946 25923 8988 25923 8986 25923 9001 25924 8951 25924 9002 25924 9001 25925 9002 25925 8939 25925 8927 25926 8931 25926 8926 25926 8781 25927 9000 25927 8997 25927 8989 25928 8911 25928 8912 25928 8912 25929 8940 25929 9002 25929 8951 25930 8912 25930 9002 25930 8944 25931 8957 25931 8946 25931 8718 25932 8875 25932 9003 25932 9004 25933 8722 25933 9005 25933 9004 25934 9006 25934 8722 25934 9006 25935 9007 25935 9008 25935 8725 25936 8724 25936 8877 25936 9011 25937 9010 25937 9012 25937 9011 25938 9005 25938 9003 25938 9009 25939 8903 25939 9010 25939 9013 25940 8900 25940 8906 25940 9016 25941 9019 25941 9018 25941 9012 25942 9010 25942 9013 25942 9024 25943 9013 25943 9014 25943 9025 25944 9014 25944 9015 25944 9021 25945 8898 25945 8897 25945 9026 25946 9021 25946 8897 25946 9022 25947 9026 25947 9027 25947 9007 25948 9028 25948 9008 25948 8877 25949 9029 25949 8879 25949 8877 25950 9008 25950 9029 25950 9028 25951 9030 25951 9029 25951 8880 25952 9031 25952 8881 25952 8880 25953 8879 25953 9029 25953 9030 25954 9032 25954 9031 25954 9035 25955 9036 25955 9033 25955 9033 25956 9036 25956 8828 25956 9036 25957 9037 25957 8830 25957 9031 25958 9032 25958 9038 25958 9005 25959 8718 25959 9003 25959 9005 25960 8722 25960 8718 25960 9041 25961 9042 25961 9039 25961 9043 25962 9044 25962 9040 25962 9046 25963 9043 25963 9040 25963 9047 25964 9041 25964 9048 25964 9043 25965 9046 25965 9044 25965 9050 25966 9048 25966 9051 25966 9044 25967 9051 25967 9048 25967 9055 25968 9058 25968 9060 25968 9063 25969 9064 25969 9059 25969 9040 25970 9065 25970 9045 25970 9053 25971 9066 25971 9056 25971 9052 25972 9054 25972 9055 25972 9060 25973 9067 25973 9055 25973 9060 25974 9068 25974 9067 25974 9069 25975 9070 25975 9071 25975 9071 25976 9070 25976 9072 25976 9073 25977 9065 25977 9039 25977 9065 25978 9040 25978 9039 25978 9077 25979 9078 25979 9076 25979 9076 25980 9078 25980 9079 25980 9082 427 9083 427 9077 427 9081 25981 9078 25981 9084 25981 9082 25982 9077 25982 9085 25982 9077 25983 9039 25983 9042 25983 9086 25984 9087 25984 9088 25984 9089 25985 9088 25985 9087 25985 9069 25986 9071 25986 9079 25986 9093 25987 9092 25987 9094 25987 9092 25988 9063 25988 9094 25988 9094 25989 9063 25989 9056 25989 9095 25990 9066 25990 9052 25990 9098 25991 9097 25991 9091 25991 9099 25992 9100 25992 9098 25992 9090 25993 9102 25993 9091 25993 9090 25994 9103 25994 9102 25994 9103 25995 9093 25995 9104 25995 9105 25996 9094 25996 9095 25996 9109 25997 9105 25997 9107 25997 9110 25998 9099 25998 9102 25998 9102 25999 9099 25999 9091 25999 9095 26000 9052 26000 9111 26000 9112 26001 9113 26001 9114 26001 9116 26002 9115 26002 9117 26002 9116 427 9114 427 9115 427 9113 26003 9064 26003 9115 26003 9115 26004 9064 26004 9097 26004 9097 26005 9064 26005 9096 26005 9098 26006 9117 26006 9097 26006 9097 26007 9117 26007 9115 26007 9114 26008 9118 26008 9112 26008 9118 26009 9120 26009 9112 26009 9112 26010 9120 26010 9121 26010 9114 26011 9116 26011 9119 26011 8933 26012 9117 26012 9122 26012 8939 26013 8933 26013 9122 26013 9117 26014 9098 26014 9123 26014 9118 26015 9119 26015 9117 26015 9130 26016 9131 26016 9128 26016 9130 26017 9132 26017 9131 26017 9129 26018 9134 26018 9135 26018 9129 26019 9137 26019 9136 26019 9138 26020 9141 26020 9136 26020 9148 26021 9147 26021 9149 26021 9150 26022 9151 26022 9152 26022 9154 26023 9155 26023 9156 26023 9144 26024 9146 26024 9145 26024 9155 26025 9145 26025 9160 26025 9156 26026 9155 26026 9160 26026 9145 26027 9147 26027 9160 26027 9156 26028 9148 26028 9164 26028 9166 26029 9167 26029 9168 26029 9179 26030 9177 26030 9178 26030 9177 26031 9181 26031 9174 26031 9185 26032 9184 26032 9186 26032 9187 26033 9186 26033 9188 26033 9189 26034 9188 26034 9190 26034 9172 26035 9193 26035 9194 26035 9166 26036 9150 26036 9167 26036 9150 26037 9152 26037 9173 26037 9195 26038 9196 26038 9197 26038 9176 26039 9198 26039 9199 26039 9180 26040 9178 26040 9200 26040 9152 26041 9201 26041 9173 26041 9173 26042 9201 26042 9196 26042 9202 26043 9197 26043 9203 26043 9200 26044 9199 26044 9207 26044 9207 26045 9199 26045 9208 26045 9209 26046 9212 26046 9210 26046 9213 26047 9210 26047 9212 26047 9211 26048 8462 26048 9212 26048 9223 26049 9224 26049 9225 26049 9223 26050 9225 26050 9226 26050 9229 26051 9230 26051 9231 26051 9232 26052 9223 26052 9226 26052 8462 26053 9220 26053 9221 26053 9235 26054 9236 26054 9237 26054 9235 26055 9237 26055 9224 26055 9237 26056 9225 26056 9224 26056 9226 26057 9238 26057 9228 26057 9241 26058 9239 26058 9238 26058 9243 26059 9241 26059 9244 26059 9244 26060 9245 26060 9246 26060 9247 26061 9244 26061 9241 26061 9151 26062 8469 26062 9171 26062 9248 26063 9167 26063 9249 26063 9234 26064 9222 26064 9250 26064 9251 26065 9248 26065 9249 26065 9258 26066 9259 26066 9260 26066 9264 26067 9263 26067 9265 26067 9164 26068 9169 26068 9165 26068 9266 26069 9268 26069 9156 26069 9162 26070 9267 26070 9266 26070 9157 26071 9154 26071 9158 26071 9276 26072 9269 26072 9275 26072 9274 26073 9273 26073 9277 26073 9278 26074 9280 26074 9139 26074 9139 26075 9282 26075 9140 26075 8851 26076 9140 26076 9282 26076 9245 26077 8851 26077 8856 26077 9283 26078 9284 26078 9285 26078 9223 26079 9288 26079 9289 26079 9289 26080 9224 26080 9223 26080 9250 26081 9292 26081 9293 26081 9289 26082 9291 26082 9224 26082 9233 26083 9288 26083 9223 26083 9216 26084 9214 26084 9295 26084 9174 26085 9297 26085 9298 26085 9299 26086 9302 26086 9301 26086 9306 26087 9307 26087 9301 26087 9304 26088 9306 26088 9301 26088 9301 26089 9302 26089 9308 26089 9257 26090 9305 26090 9259 26090 9305 26091 9308 26091 9309 26091 9260 26092 9305 26092 9309 26092 9265 26093 9310 26093 9311 26093 9258 26094 9311 26094 9255 26094 9311 26095 9310 26095 9312 26095 9135 26096 9315 26096 9242 26096 9241 26097 9315 26097 9247 26097 9241 26098 9242 26098 9315 26098 9227 26099 9228 26099 9286 26099 9278 26100 9153 26100 9281 26100 9261 26101 9316 26101 9258 26101 9317 26102 9307 26102 9184 26102 9184 26103 9182 26103 9317 26103 9197 26104 9196 26104 9209 26104 9155 26105 9144 26105 9145 26105 9254 26106 9192 26106 9190 26106 9195 26107 9193 26107 9172 26107 9194 26108 9249 26108 9172 26108 9172 26109 9249 26109 9150 26109 9150 26110 9249 26110 9167 26110 9191 26111 9192 26111 9193 26111 9305 26112 9257 26112 9303 26112 9189 26113 9190 26113 9191 26113 9188 26114 9186 26114 9303 26114 9303 26115 9186 26115 9306 26115 9195 26116 9202 26116 9191 26116 9195 26117 9197 26117 9202 26117 9307 26118 9306 26118 9186 26118 9203 26119 9197 26119 9209 26119 9175 26120 9318 26120 9198 26120 9307 26121 9186 26121 9184 26121 9185 26122 9319 26122 9184 26122 9183 26123 9184 26123 9319 26123 9237 26124 9236 26124 9222 26124 9206 26125 9214 26125 9216 26125 9218 26126 9215 26126 9217 26126 9318 26127 9205 26127 9206 26127 9175 26128 9183 26128 9318 26128 9157 26129 9142 26129 9155 26129 9276 26130 9143 26130 9142 26130 9151 26131 9169 26131 9170 26131 9156 26132 9160 26132 9148 26132 9255 26133 9253 26133 9254 26133 9259 26134 9258 26134 9255 26134 9316 26135 9311 26135 9258 26135 9253 26136 9251 26136 9252 26136 9270 26137 9142 26137 9157 26137 9291 26138 9235 26138 9224 26138 9293 26139 9213 26139 9250 26139 9318 26140 9218 26140 9198 26140 9206 26141 9215 26141 9218 26141 9206 26142 9216 26142 9215 26142 9175 26143 9198 26143 9176 26143 9162 26144 9266 26144 9164 26144 9229 26145 9228 26145 9238 26145 9231 26146 9285 26146 9229 26146 9320 26147 9128 26147 9242 26147 9323 26148 9322 26148 9324 26148 9327 26149 9328 26149 9238 26149 9326 26150 9328 26150 9330 26150 9328 26151 9326 26151 9238 26151 9331 26152 9332 26152 9329 26152 9331 26153 9226 26153 9225 26153 8463 26154 9333 26154 9211 26154 9220 26155 9211 26155 9336 26155 9335 26156 9337 26156 9222 26156 9337 26157 9332 26157 9331 26157 9220 26158 8462 26158 9211 26158 9196 26159 9201 26159 8463 26159 9211 26160 9209 26160 8463 26160 9209 26161 9196 26161 8463 26161 9201 26162 9152 26162 8463 26162 9339 26163 9149 26163 9147 26163 9340 26164 9339 26164 9147 26164 9151 26165 9342 26165 9343 26165 9343 26166 9338 26166 9152 26166 9343 26167 9152 26167 8467 26167 9339 26168 9170 26168 9149 26168 9151 26169 9170 26169 9339 26169 9344 26170 9345 26170 9340 26170 9147 26171 9344 26171 9340 26171 9345 26172 9344 26172 9346 26172 9143 26173 9346 26173 9144 26173 9347 26174 9348 26174 9137 26174 9346 26175 9349 26175 9345 26175 9346 26176 9143 26176 9349 26176 9143 26177 9137 26177 9349 26177 9137 26178 9129 26178 9350 26178 9137 26179 9350 26179 9347 26179 9357 26180 9354 26180 9356 26180 9358 26181 9357 26181 9356 26181 9359 26182 9360 26182 9361 26182 9360 26183 9362 26183 9363 26183 9352 26184 9364 26184 9353 26184 9359 26185 9361 26185 9353 26185 9374 26186 9373 26186 9372 26186 9375 26187 9376 26187 9377 26187 9379 26188 9380 26188 9375 26188 9362 26189 9383 26189 9363 26189 9362 26190 9364 26190 9384 26190 9384 26191 9364 26191 9385 26191 9386 26192 9387 26192 9382 26192 9386 26193 9388 26193 9387 26193 9392 26194 9393 26194 9390 26194 9390 26195 9393 26195 9394 26195 9390 26196 9396 26196 9395 26196 9395 26197 9396 26197 9397 26197 9399 26198 9400 26198 9398 26198 9399 26199 9401 26199 9400 26199 9401 26200 9399 26200 9402 26200 9406 26201 9408 26201 9358 26201 9358 26202 9408 26202 9409 26202 9357 26203 9358 26203 9409 26203 9411 26204 9413 26204 9412 26204 9415 26205 9412 26205 9414 26205 9415 26206 9418 26206 9417 26206 9417 26207 9418 26207 9410 26207 9397 26208 9396 26208 9410 26208 9419 26209 9414 26209 9413 26209 9420 26210 9419 26210 9421 26210 9422 26211 9423 26211 9420 26211 9425 26212 9421 26212 9426 26212 9427 26213 9424 26213 9422 26213 9433 26214 9432 26214 9434 26214 9433 26215 9434 26215 9426 26215 9434 26216 9425 26216 9426 26216 9431 26217 9433 26217 9435 26217 9438 26218 9436 26218 9437 26218 9280 26219 9438 26219 9439 26219 9435 26220 9441 26220 9437 26220 9442 26221 9441 26221 9443 26221 9442 26222 9443 26222 9444 26222 8890 26223 9447 26223 9448 26223 9448 26224 9447 26224 9445 26224 9443 26225 9448 26225 9445 26225 9447 26226 9450 26226 9445 26226 8854 26227 9282 26227 9450 26227 8853 26228 9282 26228 8854 26228 9440 26229 9445 26229 9282 26229 9431 26230 9428 26230 9430 26230 9429 26231 9424 26231 9427 26231 9423 26232 9416 26232 9420 26232 9451 26233 9398 26233 9452 26233 9451 26234 9453 26234 9398 26234 9451 26235 9454 26235 9453 26235 9461 26236 9370 26236 9460 26236 9366 26237 9464 26237 9465 26237 9467 26238 9466 26238 9468 26238 9368 26239 9460 26239 9369 26239 9368 26240 9469 26240 9460 26240 9368 26241 9378 26241 9469 26241 9471 26242 9378 26242 9472 26242 9471 26243 9470 26243 9378 26243 9374 26244 9480 26244 9479 26244 9374 26245 9376 26245 9480 26245 9481 26246 9376 26246 9375 26246 9479 26247 9482 26247 9478 26247 9478 26248 9476 26248 9477 26248 9477 26249 9476 26249 9373 26249 9378 26250 9373 26250 9475 26250 9473 26251 9483 26251 9474 26251 9474 26252 9483 26252 9453 26252 9398 26253 9453 26253 9483 26253 9484 26254 9398 26254 9400 26254 9485 26255 9484 26255 9400 26255 9402 26256 9403 26256 9354 26256 9361 26257 9402 26257 9354 26257 9361 26258 9381 26258 9402 26258 9354 26259 9404 26259 9355 26259 9406 26260 9358 26260 9356 26260 9446 26261 9444 26261 9445 26261 9452 26262 9398 26262 9397 26262 9452 26263 9397 26263 9418 26263 9418 26264 9397 26264 9410 26264 9351 26265 9357 26265 9486 26265 9486 26266 9357 26266 9409 26266 9501 26267 9380 26267 9367 26267 9502 26268 9367 26268 9503 26268 9409 26269 9408 26269 9504 26269 9504 26270 9408 26270 9505 26270 9505 26271 9408 26271 9406 26271 9488 26272 9406 26272 9407 26272 9492 26273 9482 26273 9479 26273 9480 26274 9494 26274 9479 26274 9480 26275 9496 26275 9494 26275 9496 26276 9480 26276 9498 26276 9498 26277 9480 26277 9481 26277 9375 26278 9500 26278 9481 26278 9488 26279 9407 26279 9489 26279 9492 26280 9479 26280 9494 26280 9498 26281 9481 26281 9500 26281 9497 26282 9507 26282 9495 26282 9496 26283 9497 26283 9495 26283 9366 26284 9465 26284 9367 26284 9508 26285 9467 26285 9509 26285 9510 26286 9508 26286 9503 26286 9508 26287 9510 26287 9465 26287 9508 26288 9511 26288 9503 26288 9507 26289 9512 26289 9495 26289 9495 26290 9512 26290 9493 26290 9494 26291 9495 26291 9493 26291 9493 26292 9513 26292 9491 26292 9491 26293 9513 26293 9490 26293 9514 26294 9487 26294 9515 26294 9514 26295 9516 26295 9487 26295 9514 26296 9517 26296 9516 26296 9505 26297 9518 26297 9504 26297 9409 26298 9504 26298 9486 26298 9519 26299 9520 26299 9486 26299 9486 26300 9520 26300 9521 26300 9351 26301 9486 26301 9521 26301 9523 26302 9521 26302 9524 26302 9523 26303 9525 26303 9526 26303 9522 26304 9523 26304 9526 26304 9482 26305 9491 26305 9490 26305 9487 26306 9516 26306 9488 26306 9488 26307 9516 26307 9505 26307 9513 26308 9515 26308 9490 26308 9490 26309 9515 26309 9487 26309 9038 26310 9528 26310 9527 26310 9527 26311 8878 26311 8881 26311 8876 26312 8878 26312 8820 26312 9530 26313 9034 26313 8826 26313 9016 26314 8904 26314 9531 26314 9534 26315 9019 26315 9016 26315 8793 26316 8841 26316 8843 26316 9532 26317 8904 26317 8902 26317 9533 26318 9532 26318 8902 26318 9535 26319 8902 26319 8899 26319 8794 26320 9535 26320 8899 26320 9536 26321 9368 26321 9370 26321 9379 26322 9536 26322 9365 26322 9367 26323 9379 26323 9365 26323 9367 26324 9380 26324 9379 26324 9536 26325 9371 26325 9378 26325 9379 26326 9377 26326 9537 26326 9538 26327 9539 26327 9540 26327 9543 26328 9544 26328 9545 26328 9546 26329 9545 26329 9547 26329 9548 26330 9546 26330 9547 26330 9548 26331 9550 26331 9549 26331 9550 26332 9551 26332 9552 26332 9553 26333 9552 26333 9554 26333 9555 26334 9554 26334 9556 26334 9553 26335 9555 26335 9557 26335 9558 26336 9557 26336 9559 26336 9550 26337 9560 26337 9549 26337 9550 26338 9553 26338 9560 26338 9550 26339 9552 26339 9553 26339 9545 26340 9561 26340 9562 26340 9565 26341 9563 26341 9564 26341 9567 26342 9566 26342 9540 26342 9567 26343 9540 26343 9568 26343 9569 26344 9539 26344 9570 26344 9568 26345 9569 26345 8975 26345 9562 26346 9566 26346 9567 26346 9571 26347 9572 26347 9573 26347 9574 26348 9573 26348 9575 26348 9574 26349 9559 26349 9571 26349 9576 26350 9557 26350 9577 26350 9576 26351 9571 26351 9557 26351 9571 26352 9576 26352 9578 26352 9572 26353 9571 26353 9578 26353 9581 26354 9579 26354 9556 26354 9554 26355 9581 26355 9556 26355 9555 26356 9577 26356 9557 26356 9582 26357 9583 26357 9584 26357 9582 26358 9585 26358 9583 26358 9585 26359 9582 26359 9586 26359 9587 26360 9588 26360 9589 26360 9585 26361 9592 26361 9591 26361 9586 26362 9582 26362 9593 26362 9586 26363 9594 26363 9592 26363 9596 26364 9597 26364 9588 26364 9596 26365 9598 26365 9597 26365 9596 26366 9599 26366 9598 26366 9598 26367 9599 26367 9600 26367 9604 26368 9603 26368 9605 26368 9607 26369 9606 26369 9608 26369 9609 26370 9610 26370 9608 26370 9612 26371 9609 26371 9613 26371 9612 26372 9613 26372 9584 26372 9607 26373 9608 26373 9610 26373 9616 26374 9619 26374 9617 26374 9580 26375 9572 26375 9578 26375 9625 26376 9624 26376 9586 26376 9595 26377 9626 26377 9623 26377 9611 26378 9615 26378 9610 26378 9554 26379 9552 26379 9627 26379 9627 26380 9552 26380 9628 26380 9627 26381 9628 26381 9564 26381 9602 26382 9600 26382 9601 26382 9597 26383 9589 26383 9588 26383 9594 26384 9588 26384 9592 26384 9590 26385 9587 26385 9629 26385 9630 26386 9631 26386 9632 26386 9633 26387 9634 26387 9632 26387 9636 26388 9635 26388 9633 26388 9636 26389 9637 26389 9635 26389 9629 26390 9631 26390 9630 26390 9632 26391 9634 26391 9630 26391 9638 26392 8982 26392 9570 26392 8981 26393 9639 26393 9640 26393 9591 26394 9588 26394 9590 26394 9572 26395 9611 26395 9573 26395 8878 26396 9527 26396 9641 26396 9642 26397 9641 26397 9528 26397 9530 26398 9642 26398 9528 26398 9642 26399 8823 26399 9641 26399 9530 26400 8826 26400 8883 26400 9642 26401 8883 26401 8821 26401 9357 26402 9351 26402 9354 26402 9600 26403 9602 26403 9645 26403 9629 26404 9587 26404 9647 26404 9534 26405 9531 26405 9533 26405 9534 26406 9533 26406 9535 26406 8793 26407 9534 26407 8792 26407 8979 26408 9649 26408 8980 26408 8854 26409 9639 26409 8980 26409 8980 26410 8852 26410 8854 26410 9650 26411 9651 26411 9547 26411 9652 26412 9551 26412 9548 26412 9653 26413 9628 26413 9552 26413 9430 26414 9429 26414 9548 26414 9651 26415 9650 26415 9430 26415 9538 26416 9540 26416 9654 26416 9656 26417 9544 26417 9542 26417 9656 26418 9657 26418 9544 26418 9438 26419 9656 26419 9542 26419 9446 26420 9439 26420 9542 26420 9654 26421 9655 26421 9446 26421 8976 26422 9659 26422 8978 26422 8976 26423 9658 26423 9659 26423 9449 26424 9660 26424 8887 26424 8887 26425 8982 26425 9659 26425 9659 26426 9658 26426 8885 26426 9662 26427 8984 26427 8967 26427 8969 26428 9664 26428 9665 26428 9665 26429 8968 26429 8969 26429 9664 26430 8974 26430 8850 26430 8855 26431 8984 26431 8857 26431 8958 26432 8963 26432 9666 26432 8956 26433 9668 26433 8988 26433 8956 26434 8958 26434 9666 26434 8985 26435 9668 26435 9669 26435 8985 26436 8988 26436 9668 26436 9666 26437 9667 26437 8861 26437 8861 26438 9667 26438 8862 26438 9670 26439 9671 26439 9672 26439 9673 26440 9674 26440 9671 26440 9230 26441 9673 26441 9231 26441 9670 26442 9672 26442 9679 26442 9681 26443 9682 26443 9683 26443 9679 26444 9676 26444 9680 26444 9684 26445 9685 26445 9686 26445 9687 26446 9684 26446 9688 26446 9692 26447 9691 26447 9693 26447 9695 26448 9696 26448 9697 26448 9698 26449 9697 26449 9699 26449 9700 26450 9701 26450 9699 26450 9702 26451 9703 26451 9704 26451 9685 26452 9680 26452 9686 26452 9686 26453 9705 26453 9684 26453 9707 26454 9708 26454 8983 26454 8983 26455 9708 26455 9678 26455 9709 26456 9712 26456 9710 26456 9710 26457 9712 26457 9713 26457 9714 26458 9712 26458 9715 26458 9716 26459 9713 26459 9714 26459 9716 26460 9717 26460 9713 26460 9715 26461 9712 26461 9718 26461 9715 26462 9718 26462 9719 26462 9715 26463 9719 26463 9720 26463 9721 26464 9722 26464 9723 26464 9724 26465 9723 26465 9725 26465 9724 26466 9726 26466 9723 26466 9726 26467 9724 26467 9727 26467 9732 26468 9733 26468 9731 26468 9726 26469 9721 26469 9723 26469 9543 26470 9736 26470 9711 26470 9707 26471 9737 26471 9738 26471 9707 26472 8973 26472 9640 26472 9736 26473 9549 26473 9739 26473 9543 26474 9711 26474 9737 26474 9543 26475 9737 26475 9640 26475 9741 26476 9742 26476 9743 26476 9748 26477 9747 26477 9749 26477 9755 26478 9754 26478 9756 26478 9757 26479 9759 26479 9756 26479 9755 26480 9760 26480 9761 26480 9766 26481 9769 26481 9741 26481 9745 26482 9770 26482 9726 26482 9726 26483 9771 26483 9721 26483 9713 26484 9131 26484 9683 26484 9683 26485 9131 26485 9774 26485 9321 26486 9683 26486 9774 26486 9683 26487 9321 26487 9681 26487 9688 26488 9705 26488 9690 26488 9688 26489 9690 26489 9689 26489 9775 26490 9689 26490 9691 26490 9776 26491 9694 26491 9777 26491 9776 26492 9777 26492 9764 26492 9747 26493 9748 26493 9741 26493 9699 26494 9701 26494 9698 26494 9698 26495 9701 26495 9775 26495 9695 26496 9694 26496 9776 26496 9687 26497 9702 26497 9783 26497 9784 26498 9673 26498 9685 26498 9784 26499 9787 26499 9673 26499 9674 26500 9673 26500 9787 26500 9790 26501 9791 26501 9549 26501 9790 26502 9549 26502 9792 26502 9793 26503 9794 26503 9720 26503 9794 26504 9796 26504 9795 26504 9798 26505 9729 26505 9731 26505 9793 26506 9720 26506 9799 26506 9800 26507 9801 26507 9802 26507 9804 26508 9800 26508 9803 26508 9807 26509 9808 26509 9809 26509 9806 26510 9812 26510 9800 26510 9806 26511 9807 26511 9812 26511 9802 26512 9813 26512 9803 26512 9805 26513 9814 26513 9815 26513 9816 26514 9817 26514 9818 26514 8017 26515 9821 26515 8012 26515 8017 26516 9822 26516 9821 26516 8017 26517 8016 26517 9822 26517 9819 26518 9823 26518 9824 26518 9808 26519 9806 26519 9825 26519 9826 26520 9825 26520 9816 26520 9828 26521 9817 26521 9814 26521 9820 26522 9831 26522 8012 26522 9830 26523 8010 26523 9831 26523 9831 26524 8010 26524 8012 26524 9823 26525 8016 26525 9832 26525 9752 26526 9843 26526 9754 26526 9848 26527 9847 26527 9824 26527 9823 26528 9832 26528 9848 26528 8019 26529 9850 26529 9849 26529 9851 26530 8020 26530 9852 26530 9838 26531 9854 26531 9840 26531 9853 26532 9836 26532 9850 26532 9851 26533 9853 26533 9850 26533 9852 26534 8021 26534 9855 26534 9756 26535 9859 26535 9861 26535 9756 26536 9754 26536 9859 26536 9860 26537 9859 26537 9842 26537 9854 26538 9855 26538 9840 26538 9855 26539 8021 26539 9862 26539 9858 26540 9862 26540 9863 26540 9865 26541 9860 26541 9858 26541 9863 26542 9865 26542 9858 26542 8024 26543 8035 26543 9866 26543 9866 26544 8035 26544 9867 26544 9868 26545 9865 26545 9866 26545 9869 26546 9870 26546 9757 26546 9757 26547 9870 26547 9760 26547 9765 26548 9764 26548 9777 26548 9707 26549 9738 26549 9706 26549 9674 26550 9677 26550 9671 26550 9673 26551 9675 26551 9685 26551 9680 26552 9685 26552 9679 26552 9679 26553 9675 26553 9670 26553 8021 26554 8023 26554 9862 26554 9748 26555 9871 26555 9766 26555 9748 26556 9749 26556 9871 26556 9862 26557 9858 26557 9857 26557 9842 26558 9856 26558 9860 26558 9761 26559 9753 26559 9755 26559 9753 26560 9761 26560 9762 26560 9871 26561 9767 26561 9766 26561 9871 26562 9750 26562 9767 26562 9753 26563 9754 26563 9755 26563 9761 26564 9763 26564 9762 26564 9781 26565 9692 26565 9698 26565 9775 26566 9781 26566 9698 26566 9698 26567 9692 26567 9695 26567 9703 26568 9687 26568 9782 26568 9784 26569 9684 26569 9783 26569 9840 26570 9856 26570 9842 26570 9767 26571 9762 26571 9765 26571 9844 26572 9751 26572 9749 26572 9872 26573 9747 26573 9809 26573 9846 26574 9845 26574 9873 26574 9873 26575 9845 26575 9874 26575 9872 26576 9809 26576 9873 26576 9841 26577 9842 26577 9843 26577 9844 26578 9841 26578 9843 26578 9864 26579 9860 26579 9865 26579 9866 26580 9865 26580 9863 26580 9779 26581 9761 26581 9760 26581 9784 26582 9685 26582 9684 26582 9772 26583 9875 26583 9715 26583 9720 26584 9735 26584 9772 26584 9743 26585 9745 26585 9741 26585 9876 26586 9809 26586 9808 26586 9847 26587 9826 26587 9824 26587 9873 26588 9809 26588 9876 26588 9827 26589 9873 26589 9876 26589 9827 26590 9846 26590 9873 26590 9827 26591 9847 26591 9846 26591 9835 26592 9833 26592 9834 26592 9833 26593 9848 26593 9832 26593 9722 26594 9728 26594 9729 26594 9726 26595 9770 26595 9771 26595 9746 26596 9745 26596 9810 26596 9845 26597 9839 26597 9841 26597 9849 26598 9850 26598 9834 26598 9832 26599 9849 26599 9834 26599 9834 26600 9850 26600 9836 26600 9786 26601 9784 26601 9783 26601 9791 26602 9740 26602 9739 26602 9549 26603 9791 26603 9739 26603 9817 26604 9829 26604 9818 26604 9804 26605 9814 26605 9805 26605 9825 26606 9805 26606 9815 26606 9731 26607 9797 26607 9798 26607 9733 26608 9795 26608 9797 26608 9735 26609 9720 26609 9795 26609 9816 26610 9815 26610 9817 26610 9726 26611 9727 26611 9745 26611 9681 26612 9676 26612 9877 26612 9241 26613 9878 26613 9681 26613 9879 26614 9708 26614 9707 26614 9676 26615 9678 26615 9880 26615 9244 26616 9878 26616 9243 26616 9877 26617 9880 26617 9239 26617 9239 26618 9880 26618 9246 26618 9881 26619 9135 26619 9683 26619 9713 26620 9135 26620 9882 26620 9884 26621 9881 26621 9706 26621 9706 26622 9881 26622 9683 26622 9140 26623 9883 26623 9141 26623 9135 26624 9881 26624 9315 26624 9315 26625 9881 26625 9247 26625 9881 26626 9884 26626 9247 26626 9245 26627 9247 26627 9884 26627 9888 26628 9709 26628 9887 26628 9885 26629 9718 26629 9153 26629 9888 26630 9138 26630 9136 26630 9138 26631 9887 26631 9139 26631 8862 26632 8964 26632 8863 26632 8863 26633 8964 26633 8865 26633 9661 26634 9660 26634 9447 26634 9658 26635 8977 26635 8888 26635 9661 26636 8891 26636 8977 26636 9657 26637 9656 26637 9437 26637 9655 427 9540 427 9444 427 9444 26638 9540 26638 9442 26638 9442 26639 9566 26639 9437 26639 9886 26640 9278 26640 9736 26640 9281 26641 9275 26641 9719 26641 9275 26642 9272 26642 9799 26642 9799 26643 9719 26643 9275 26643 9799 26644 9272 26644 9274 26644 9790 26645 9799 26645 9274 26645 9670 26646 9240 26646 9671 26646 9671 26647 9283 26647 9673 26647 9708 26648 9244 26648 9246 26648 9708 26649 9246 26649 9880 26649 9140 26650 9245 26650 9737 26650 9432 26651 9565 26651 9434 26651 9434 26652 9628 26652 9425 26652 9653 26653 9652 26653 9425 26653 9665 26654 9664 26654 8847 26654 8847 26655 9664 26655 8850 26655 8844 26656 9662 26656 8968 26656 9889 26657 9890 26657 9891 26657 9892 26658 8907 26658 9889 26658 9893 26659 9699 26659 9697 26659 9892 26660 9891 26660 9894 26660 9899 26661 9898 26661 9900 26661 9903 26662 9902 26662 9904 26662 8033 26663 9904 26663 8038 26663 9897 26664 9757 26664 9898 26664 9758 26665 9868 26665 9906 26665 9906 26666 9905 26666 9758 26666 9908 26667 9869 26667 9757 26667 9906 26668 9867 26668 8037 26668 9867 26669 8035 26669 8037 26669 9899 26670 9896 26670 9898 26670 9898 26671 9757 26671 9905 26671 9900 26672 9898 26672 9905 26672 9892 26673 9889 26673 9891 26673 8037 26674 8038 26674 9907 26674 9701 26675 9913 26675 9782 26675 9782 26676 9913 26676 9703 26676 9703 26677 9915 26677 9704 26677 9704 26678 9916 26678 9890 26678 9890 26679 9916 26679 9910 26679 9917 26680 9798 26680 9797 26680 9921 26681 9918 26681 9922 26681 9923 26682 9789 26682 9924 26682 9922 26683 9923 26683 9925 26683 9922 26684 9723 26684 9923 26684 9919 26685 9927 26685 9928 26685 9814 26686 9929 26686 9828 26686 9929 26687 9804 26687 9803 26687 9930 26688 9803 26688 9920 26688 9930 26689 9931 26689 9932 26689 8008 26690 9933 26690 8007 26690 8008 26691 8010 26691 9830 26691 9828 26692 9929 26692 9933 26692 9933 26693 9830 26693 9828 26693 9932 26694 9931 26694 9934 26694 9931 26695 9935 26695 9934 26695 9934 26696 9935 26696 9936 26696 8006 26697 9936 26697 7995 26697 9934 26698 9936 26698 8006 26698 9937 26699 9803 26699 9813 26699 9918 26700 9725 26700 9922 26700 9923 26701 9924 26701 9796 26701 9725 26702 9723 26702 9922 26702 9930 26703 9920 26703 9928 26703 9803 26704 9930 26704 9929 26704 9932 26705 9929 26705 9930 26705 9940 26706 9941 26706 9917 26706 9788 26707 9798 26707 9942 26707 9788 26708 9942 26708 9943 26708 9788 26709 9943 26709 9789 26709 9943 26710 9938 26710 9789 26710 9948 26711 9947 26711 9949 26711 9953 26712 9952 26712 9957 26712 9958 26713 9959 26713 9952 26713 9957 26714 9952 26714 9960 26714 9961 26715 9962 26715 9963 26715 9965 26716 9964 26716 9966 26716 9965 26717 9966 26717 9967 26717 9968 26718 9089 26718 9965 26718 9969 26719 9970 26719 9967 26719 9088 26720 9968 26720 9972 26720 9972 26721 9968 26721 9973 26721 9593 26722 9974 26722 9586 26722 9611 26723 9975 26723 9615 26723 9607 26724 9615 26724 9976 26724 9974 26725 9977 26725 9625 26725 9625 26726 9977 26726 9616 26726 9978 26727 9979 26727 9615 26727 9975 26728 9978 26728 9615 26728 9616 26729 9977 26729 9975 26729 8914 26730 9981 26730 9982 26730 8991 26731 9982 26731 9983 26731 8993 26732 8991 26732 9983 26732 8913 26733 9982 26733 8991 26733 9986 26734 9985 26734 9983 26734 8925 26735 9988 26735 9987 26735 9982 26736 9986 26736 9983 26736 9981 26737 9986 26737 9982 26737 9989 26738 9990 26738 9991 26738 9009 26739 8901 26739 8903 26739 9009 26740 9991 26740 8901 26740 9009 26741 8875 26741 9992 26741 9996 26742 9997 26742 8796 26742 9994 26743 8839 26743 8791 26743 8782 26744 8796 26744 9999 26744 9992 26745 9989 26745 9991 26745 9996 26746 8783 26746 8839 26746 10001 26747 9995 26747 10002 26747 10007 26748 10006 26748 10008 26748 10003 26749 10004 26749 10005 26749 10000 26750 10006 26750 8480 26750 10008 26751 10006 26751 10000 26751 10002 26752 9990 26752 10001 26752 10010 26753 10011 26753 10012 26753 10010 26754 10013 26754 10011 26754 10013 26755 10014 26755 10015 26755 10013 26756 10015 26756 10016 26756 10011 26757 10017 26757 10012 26757 10018 26758 10012 26758 10017 26758 10020 26759 10018 26759 10019 26759 10024 26760 10023 26760 10026 26760 10029 26761 10030 26761 10018 26761 10012 26762 10018 26762 10030 26762 10030 26763 10031 26763 10010 26763 10010 26764 10031 26764 10014 26764 10016 26765 10032 26765 10024 26765 10032 26766 10033 26766 10024 26766 10021 26767 10033 26767 10028 26767 10027 26768 10021 26768 10028 26768 9993 26769 9991 26769 9990 26769 9993 26770 9990 26770 10002 26770 9993 26771 10002 26771 9994 26771 8839 26772 9995 26772 10003 26772 9996 26773 8839 26773 10003 26773 9996 26774 10005 26774 9997 26774 9992 26775 9999 26775 10000 26775 10034 26776 9404 26776 10022 26776 9404 26777 10034 26777 9489 26777 10022 26778 9399 26778 10023 26778 10023 26779 9399 26779 9398 26779 10023 26780 9398 26780 10013 26780 9483 26781 10011 26781 10013 26781 9473 26782 9471 26782 10011 26782 9489 26783 10034 26783 10019 26783 10034 26784 10020 26784 10019 26784 9472 26785 9476 26785 9478 26785 10017 26786 9478 26786 9489 26786 9985 26787 10037 26787 10038 26787 9985 26788 10038 26788 9984 26788 9984 26789 10038 26789 10039 26789 9988 26790 9984 26790 10039 26790 9988 26791 10039 26791 10036 26791 9978 26792 10044 26792 9979 26792 10036 26793 10039 26793 8480 26793 8480 26794 10039 26794 10009 26794 10004 26795 10037 26795 10035 26795 10006 26796 10035 26796 10036 26796 10044 26797 10031 26797 10040 26797 10031 26798 10044 26798 10032 26798 10029 26799 10042 26799 10041 26799 10032 26800 10043 26800 10033 26800 10028 26801 10042 26801 10029 26801 10046 26802 10048 26802 10047 26802 10049 26803 10048 26803 8556 26803 8556 26804 10050 26804 10049 26804 10054 26805 10053 26805 8615 26805 8556 26806 10048 26806 8554 26806 8554 26807 10048 26807 10055 26807 8554 26808 10057 26808 8553 26808 10053 26809 10052 26809 8614 26809 10046 26810 10059 26810 10048 26810 9051 26811 10045 26811 9050 26811 10047 26812 9393 26812 9050 26812 10060 26813 10047 26813 10049 26813 9393 26814 10060 26814 9394 26814 10062 26815 10063 26815 9055 26815 9055 26816 10063 26816 9052 26816 9052 26817 10063 26817 9111 26817 10061 26818 10065 26818 10062 26818 9044 26819 9046 26819 10046 26819 10066 26820 10046 26820 9046 26820 10059 26821 10067 26821 10048 26821 10056 26822 10068 26822 10069 26822 10072 26823 10071 26823 10073 26823 10074 26824 10072 26824 10073 26824 10074 26825 10058 26825 10072 26825 10058 26826 9419 26826 10054 26826 10053 26827 10077 26827 9413 26827 10078 26828 9413 26828 10079 26828 9411 26829 10078 26829 10079 26829 9411 26830 9396 26830 10052 26830 10055 26831 10068 26831 10056 26831 10057 26832 10071 26832 10072 26832 10054 26833 10075 26833 10076 26833 10076 26834 10077 26834 10053 26834 10051 26835 10081 26835 10050 26835 9419 26836 9413 26836 10077 26836 10071 26837 10070 26837 10069 26837 10073 26838 10082 26838 9419 26838 10066 26839 9046 26839 10068 26839 10083 26840 10068 26840 9074 26840 10084 26841 10068 26841 10083 26841 10084 26842 10071 26842 10068 26842 8553 26843 10087 26843 8554 26843 8556 26844 10088 26844 10089 26844 8556 26845 10089 26845 10090 26845 8557 26846 10090 26846 10091 26846 8614 26847 10091 26847 10092 26847 8615 26848 10092 26848 10093 26848 8553 26849 8547 26849 10086 26849 8554 26850 10088 26850 8556 26850 8557 26851 10091 26851 8614 26851 8614 26852 10092 26852 8615 26852 10095 26853 9623 26853 9580 26853 10095 26854 10096 26854 9081 26854 10092 26855 10098 26855 10099 26855 10099 26856 10100 26856 10092 26856 10098 26857 10090 26857 10103 26857 10093 26858 10100 26858 10086 26858 10104 26859 9556 26859 9579 26859 10099 26860 10108 26860 10109 26860 10101 26861 10104 26861 9579 26861 10102 26862 9579 26862 10106 26862 10106 26863 9578 26863 10107 26863 10108 26864 10107 26864 9576 26864 10109 26865 9555 26865 9556 26865 9579 26866 9578 26866 10106 26866 9047 26867 9050 26867 9393 26867 9392 26868 9047 26868 9393 26868 10081 26869 10080 26869 9394 26869 10076 26870 10053 26870 10054 26870 10061 26871 9068 26871 10065 26871 10111 26872 10114 26872 10113 26872 10113 26873 10114 26873 10115 26873 10115 26874 10114 26874 8807 26874 10118 26875 10119 26875 10120 26875 10120 26876 10119 26876 10121 26876 10122 26877 10121 26877 10123 26877 10125 26878 8806 26878 10126 26878 10127 26879 10125 26879 10126 26879 10127 26880 10128 26880 10125 26880 10122 26881 10123 26881 10124 26881 10124 26882 8806 26882 10125 26882 10112 26883 10135 26883 8892 26883 8892 26884 10110 26884 10136 26884 10134 26885 10137 26885 9111 26885 10121 26886 10119 26886 8805 26886 8805 26887 10117 26887 8807 26887 8838 26888 8808 26888 8892 26888 8808 26889 10111 26889 8892 26889 8807 26890 10114 26890 10111 26890 10126 26891 8869 26891 10127 26891 8544 26892 10138 26892 8545 26892 10139 26893 8544 26893 10140 26893 10141 26894 8543 26894 8535 26894 10143 26895 8533 26895 8612 26895 10144 26896 8612 26896 8611 26896 10145 26897 8611 26897 8545 26897 10138 26898 10145 26898 8545 26898 10141 26899 8535 26899 10147 26899 10147 26900 8535 26900 10142 26900 10148 26901 8533 26901 10143 26901 10143 26902 8612 26902 10149 26902 10140 26903 10151 26903 10152 26903 10152 26904 10139 26904 10140 26904 10139 26905 10152 26905 10138 26905 10145 26906 10152 26906 10153 26906 10147 26907 10142 26907 10150 26907 9636 26908 10156 26908 9637 26908 9636 26909 9643 26909 10156 26909 9636 26910 9633 26910 9643 26910 10157 26911 9643 26911 9644 26911 9646 26912 10158 26912 10157 26912 10160 26913 9647 26913 9587 26913 10161 26914 9587 26914 9648 26914 9589 26915 10162 26915 10161 26915 9589 26916 9597 26916 10162 26916 10162 26917 9597 26917 10163 26917 10166 26918 10164 26918 10165 26918 10164 26919 7972 26919 7974 26919 10168 26920 7974 26920 7976 26920 10173 26921 10171 26921 10172 26921 10173 26922 10174 26922 10171 26922 10174 26923 10175 26923 10176 26923 10158 26924 9629 26924 10159 26924 10178 26925 10177 26925 10176 26925 9643 26926 10181 26926 10182 26926 10156 26927 9643 26927 10182 26927 10159 26928 9647 26928 10160 26928 10170 26929 10171 26929 10169 26929 10169 26930 10161 26930 10168 26930 10163 26931 9598 26931 9600 26931 10184 26932 9645 26932 9602 26932 10185 26933 9602 26933 9604 26933 9605 26934 10186 26934 10185 26934 10167 26935 10187 26935 10188 26935 10167 26936 10165 26936 10187 26936 10183 26937 9645 26937 10184 26937 10188 26938 10189 26938 7969 26938 10185 26939 10192 26939 10190 26939 10190 26940 10194 26940 10191 26940 10162 26941 10168 26941 10161 26941 10162 26942 10163 26942 10164 26942 10175 26943 10179 26943 10176 26943 10180 26944 10196 26944 10181 26944 10163 26945 10183 26945 10165 26945 10160 26946 10161 26946 10169 26946 10174 26947 10159 26947 10171 26947 9643 26948 10157 26948 10177 26948 8894 26949 9068 26949 10197 26949 9095 26950 10137 26950 9108 26950 8869 26951 9108 26951 10137 26951 8892 26952 10136 26952 8893 26952 10122 26953 10124 26953 10120 26953 8533 26954 10113 26954 10115 26954 8612 26955 10115 26955 10116 26955 8612 26956 10116 26956 10120 26956 10124 26957 8611 26957 10120 26957 8544 26958 10125 26958 10128 26958 8544 26959 10128 26959 10129 26959 8543 26960 10129 26960 10131 26960 8543 26961 10131 26961 10133 26961 10064 26962 8543 26962 10133 26962 10064 26963 10110 26963 8535 26963 10064 26964 10065 26964 10110 26964 10064 26965 10062 26965 10065 26965 8612 26966 10120 26966 8611 26966 8544 26967 10129 26967 8543 26967 8942 26968 10198 26968 9001 26968 8954 26969 8953 26969 10199 26969 10199 26970 8944 26970 8954 26970 8952 26971 9001 26971 10198 26971 10200 26972 10201 26972 10202 26972 10205 26973 10201 26973 10200 26973 10206 26974 10207 26974 10205 26974 10206 26975 10208 26975 10207 26975 10200 26976 10206 26976 10205 26976 10211 26977 10200 26977 10202 26977 10202 26978 10212 26978 10213 26978 10204 26979 10214 26979 10212 26979 10211 26980 10202 26980 10213 26980 10216 26981 10219 26981 10220 26981 10221 26982 10217 26982 10220 26982 10220 26983 10217 26983 10216 26983 10222 26984 10223 26984 10219 26984 10220 26985 10219 26985 10223 26985 10222 26986 10225 26986 10226 26986 10225 26987 10216 26987 10228 26987 10225 26988 10228 26988 10231 26988 10232 26989 10233 26989 10228 26989 10231 26990 10229 26990 10226 26990 10225 26991 10231 26991 10226 26991 10226 26992 10224 26992 10222 26992 10229 26993 10231 26993 10228 26993 10227 26994 10226 26994 10229 26994 10234 26995 10235 26995 9168 26995 9168 26996 10236 26996 9165 26996 9163 26997 9165 26997 10240 26997 10236 26998 10238 26998 9165 26998 10241 26999 10242 26999 9313 26999 9313 27000 10242 27000 10234 27000 9251 27001 10234 27001 9248 27001 10243 27002 10244 27002 10245 27002 10246 27003 10244 27003 10243 27003 10246 27004 10243 27004 10247 27004 10248 27005 10243 27005 9161 27005 9310 27006 9265 27006 9263 27006 10253 27007 10247 27007 10248 27007 9161 27008 10253 27008 10248 27008 10254 27009 9161 27009 10239 27009 10255 27010 10239 27010 9163 27010 10240 27011 10255 27011 9163 27011 10240 27012 9165 27012 10256 27012 10257 27013 9165 27013 10238 27013 10237 27014 10257 27014 10238 27014 10237 27015 10258 27015 10257 27015 10237 27016 10236 27016 10258 27016 9168 27017 10258 27017 10236 27017 9168 27018 10259 27018 10258 27018 9168 27019 10235 27019 10259 27019 10259 27020 10235 27020 10260 27020 10261 27021 10234 27021 10242 27021 10241 27022 10261 27022 10242 27022 10260 27023 10234 27023 10261 27023 10263 27024 9208 27024 9219 27024 10263 27025 9180 27025 9207 27025 10268 27026 10267 27026 10269 27026 10270 27027 10268 27027 10267 27027 9292 27028 9294 27028 10275 27028 10276 27029 10277 27029 9293 27029 9219 27030 9217 27030 9296 27030 9295 27031 9293 27031 10279 27031 9292 27032 10276 27032 9293 27032 10274 27033 9292 27033 10273 27033 10263 27034 10264 27034 10280 27034 10282 27035 9959 27035 10283 27035 10284 27036 10282 27036 10283 27036 9959 27037 10285 27037 10283 27037 10283 27038 10285 27038 10286 27038 10286 27039 10285 27039 10287 27039 10287 27040 10288 27040 10286 27040 10286 27041 10288 27041 10289 27041 10290 27042 9955 27042 10291 27042 10290 27043 10292 27043 10289 27043 10288 27044 9956 27044 9955 27044 9955 27045 9954 27045 10291 27045 9962 27046 10291 27046 9950 27046 10282 27047 10281 27047 9959 27047 8837 27048 10294 27048 10293 27048 10293 27049 10295 27049 10296 27049 10300 27050 10301 27050 10299 27050 10302 27051 10300 27051 9390 27051 9390 27052 10300 27052 9392 27052 10303 27053 10304 27053 8834 27053 8834 27054 10304 27054 8835 27054 10294 27055 8895 27055 10197 27055 10304 27056 10197 27056 8835 27056 8842 27057 10305 27057 8896 27057 8897 27058 8896 27058 10305 27058 10306 27059 8815 27059 10307 27059 10310 27060 10307 27060 10309 27060 8816 27061 10311 27061 10312 27061 10316 27062 10317 27062 6610 27062 6611 27063 10318 27063 10316 27063 6611 27064 10319 27064 10318 27064 10325 27065 10307 27065 10326 27065 10314 27066 10311 27066 8829 27066 10316 27067 10315 27067 10317 27067 10316 27068 10328 27068 10315 27068 10330 27069 6610 27069 10329 27069 10327 27070 10331 27070 10314 27070 10311 27071 10314 27071 10312 27071 10312 27072 10326 27072 8816 27072 10325 27073 10309 27073 10307 27073 10316 27074 10320 27074 10328 27074 8813 27075 10310 27075 8812 27075 10318 27076 10320 27076 10316 27076 10315 27077 8829 27077 8831 27077 8882 27078 8829 27078 10311 27078 10315 27079 8884 27079 10317 27079 9213 27080 9212 27080 10332 27080 8461 27081 9234 27081 9213 27081 8670 27082 10333 27082 9213 27082 10333 27083 8380 27083 9213 27083 9212 27084 9221 27084 10332 27084 10333 27085 8670 27085 8380 27085 10332 27086 8670 27086 9213 27086 8461 27087 8380 27087 9234 27087 10332 27088 8461 27088 8380 27088 8461 27089 10332 27089 9221 27089 9234 27090 8461 27090 9221 27090 10334 27091 10335 27091 10336 27091 10337 27092 10336 27092 10335 27092 10335 27093 8813 27093 10337 27093 10335 27094 10310 27094 8813 27094 10295 27095 10304 27095 10296 27095 9150 27096 9166 27096 8660 27096 9166 27097 9169 27097 8466 27097 8466 27098 10338 27098 8360 27098 9169 27099 9171 27099 10338 27099 10339 27100 10340 27100 10341 27100 9388 27101 10340 27101 10339 27101 10341 27102 10300 27102 10339 27102 10339 27103 10300 27103 10343 27103 9390 27104 9388 27104 10302 27104 10340 27105 10301 27105 10341 27105 9392 27106 10299 27106 10342 27106 10347 27107 10344 27107 10348 27107 10298 27108 10348 27108 10349 27108 10298 27109 9458 27109 9457 27109 9457 27110 10350 27110 10347 27110 10348 27111 9462 27111 10349 27111 10347 27112 10350 27112 10344 27112 8466 27113 8360 27113 9166 27113 10339 27114 10343 27114 9388 27114 9612 27115 9923 27115 9796 27115 9926 27116 10352 27116 10353 27116 10356 27117 10355 27117 10357 27117 10361 27118 10363 27118 10360 27118 9925 27119 10351 27119 9922 27119 9921 27120 10352 27120 9926 27120 9926 27121 10353 27121 10354 27121 10367 27122 10366 27122 9935 27122 10354 27123 10355 27123 10368 27123 9936 27124 9935 27124 10366 27124 9927 27125 10354 27125 10368 27125 9927 27126 9919 27126 10354 27126 10354 27127 9919 27127 9926 27127 9931 27128 10358 27128 10367 27128 10356 27129 9927 27129 10368 27129 10355 27130 10356 27130 10368 27130 10359 27131 10358 27131 10364 27131 9585 27132 10351 27132 9583 27132 9585 27133 10352 27133 10351 27133 9630 27134 9634 27134 10353 27134 10355 27135 9635 27135 10357 27135 9637 27136 10371 27136 10370 27136 10360 27137 10370 27137 10362 27137 10350 27138 9457 27138 9455 27138 10350 27139 10372 27139 10344 27139 10377 27140 10378 27140 10379 27140 4751 27141 10380 27141 10381 27141 9158 27142 9455 27142 9271 27142 9455 27143 9158 27143 10350 27143 10372 27144 10373 27144 10344 27144 10382 27145 10376 27145 10375 27145 10382 27146 10383 27146 10378 27146 10381 27147 10380 27147 10386 27147 10380 27148 10385 27148 10386 27148 10389 27149 10388 27149 10390 27149 4752 27150 10392 27150 4751 27150 4752 27151 10394 27151 10393 27151 10377 27152 10379 27152 10396 27152 9462 27153 10346 27153 10345 27153 10383 27154 10379 27154 10378 27154 10392 27155 10384 27155 10380 27155 10384 27156 10387 27156 10385 27156 10379 27157 10383 27157 10387 27157 10392 27158 10380 27158 4751 27158 10374 27159 10376 27159 10378 27159 9461 27160 10374 27160 9463 27160 9464 27161 10377 27161 9466 27161 9466 27162 10377 27162 10396 27162 10393 27163 10395 27163 9468 27163 9449 27164 9638 27164 9450 27164 9918 27165 10401 27165 9725 27165 9725 27166 10401 27166 10397 27166 10403 27167 10405 27167 9920 27167 10406 27168 10407 27168 9725 27168 9725 27169 10398 27169 10406 27169 9724 27170 10408 27170 9744 27170 10408 27171 10409 27171 9744 27171 10410 27172 9801 27172 10409 27172 9801 27173 10411 27173 9802 27173 10412 27174 10413 27174 10414 27174 10412 27175 10415 27175 10413 27175 10412 27176 10416 27176 10415 27176 10400 27177 10415 27177 10399 27177 10400 27178 10413 27178 10415 27178 10413 27179 10402 27179 10405 27179 10419 27180 10418 27180 10404 27180 10420 27181 10404 27181 9813 27181 9813 27182 10421 27182 10420 27182 9813 27183 9802 27183 10421 27183 10423 27184 10411 27184 10410 27184 10410 27185 10424 27185 10423 27185 10410 27186 10425 27186 10424 27186 9724 27187 10427 27187 10408 27187 9724 27188 10428 27188 10427 27188 10428 27189 9724 27189 10407 27189 10416 27190 10432 27190 10399 27190 10398 27191 10431 27191 10430 27191 10429 27192 10435 27192 10428 27192 10426 27193 10436 27193 10437 27193 10425 27194 10409 27194 10426 27194 10408 27195 10427 27195 10426 27195 10424 27196 10422 27196 10423 27196 10423 27197 10422 27197 10411 27197 10419 27198 10417 27198 10418 27198 10403 27199 10417 27199 10405 27199 10405 27200 10417 27200 10414 27200 9802 27201 10411 27201 10421 27201 10403 27202 9937 27202 10418 27202 10418 27203 9937 27203 10404 27203 10386 27204 10249 27204 10388 27204 10386 27205 10385 27205 10249 27205 10249 27206 10251 27206 10388 27206 10438 27207 10232 27207 10218 27207 10218 27208 10232 27208 10216 27208 10438 27209 10230 27209 10233 27209 9338 27210 9343 27210 10440 27210 10440 27211 9343 27211 10441 27211 10442 27212 9342 27212 9341 27212 10439 27213 10444 27213 9340 27213 10441 27214 9342 27214 10442 27214 10447 27215 9338 27215 10448 27215 10449 27216 10448 27216 10450 27216 10453 27217 10452 27217 10454 27217 10453 27218 10454 27218 10440 27218 10455 27219 10448 27219 10440 27219 10440 27220 10448 27220 9338 27220 10451 27221 10449 27221 10450 27221 10449 27222 10447 27222 10448 27222 10456 27223 9332 27223 10457 27223 10457 27224 9332 27224 9337 27224 9335 27225 10458 27225 10457 27225 10458 27226 9334 27226 9220 27226 10459 27227 9220 27227 9336 27227 10453 27228 9211 27228 9333 27228 10459 27229 9336 27229 10460 27229 10445 27230 10446 27230 10461 27230 10462 27231 10446 27231 10447 27231 10463 27232 10449 27232 10451 27232 10464 27233 10451 27233 10445 27233 10461 27234 10464 27234 10445 27234 10462 27235 10447 27235 10463 27235 10463 27236 10451 27236 10464 27236 10465 27237 10467 27237 10468 27237 10469 27238 10468 27238 9705 27238 9705 27239 10467 27239 9690 27239 9691 27240 9690 27240 9693 27240 10467 27241 10466 27241 9693 27241 9693 27242 10466 27242 9694 27242 9690 27243 10467 27243 9693 27243 9705 27244 10468 27244 10467 27244 10265 27245 10470 27245 9294 27245 10471 27246 10265 27246 10266 27246 10267 27247 10471 27247 10266 27247 10472 27248 10269 27248 10473 27248 9294 27249 10475 27249 10275 27249 10273 27250 10274 27250 10476 27250 10276 27251 10477 27251 10277 27251 10277 27252 10477 27252 9293 27252 9293 27253 10477 27253 10478 27253 10279 27254 10478 27254 9295 27254 10279 27255 9293 27255 10478 27255 10272 27256 10278 27256 10480 27256 10480 27257 10280 27257 10272 27257 9697 27258 10481 27258 9893 27258 10482 27259 9893 27259 10483 27259 10484 27260 10485 27260 9893 27260 9893 27261 10485 27261 9897 27261 10485 27262 10486 27262 9897 27262 9786 27263 9889 27263 8909 27263 10488 27264 9894 27264 9895 27264 10488 27265 9895 27265 10489 27265 10491 27266 9909 27266 9899 27266 10495 27267 10496 27267 10494 27267 10498 27268 10495 27268 10497 27268 10494 27269 10496 27269 10500 27269 10500 27270 10496 27270 10501 27270 9899 27271 10492 27271 10491 27271 10491 27272 10490 27272 9909 27272 9618 27273 10503 27273 9624 27273 10503 27274 10504 27274 9624 27274 9622 27275 10505 27275 9621 27275 10505 27276 9620 27276 9621 27276 10507 27277 10504 27277 10503 27277 9626 27278 10504 27278 10508 27278 10506 27279 10507 27279 10503 27279 10511 27280 10505 27280 9622 27280 10510 27281 9620 27281 10505 27281 10514 27282 10510 27282 10511 27282 10520 27283 10504 27283 10507 27283 10517 27284 10509 27284 10518 27284 8558 27285 10515 27285 8562 27285 8563 27286 10518 27286 10519 27286 8563 27287 10519 27287 10520 27287 8565 27288 10520 27288 10522 27288 8565 27289 10522 27289 10521 27289 8566 27290 10521 27290 10513 27290 8560 27291 10512 27291 10523 27291 8560 27292 10523 27292 10514 27292 8558 27293 8560 27293 10514 27293 8562 27294 10518 27294 8563 27294 8566 27295 10512 27295 8560 27295 8558 27296 10524 27296 8560 27296 8558 27297 10525 27297 10524 27297 10526 27298 8558 27298 10527 27298 10527 27299 8558 27299 8562 27299 10527 27300 8562 27300 10528 27300 8563 27301 8565 27301 10529 27301 10531 27302 8566 27302 10532 27302 10532 27303 8560 27303 10533 27303 10524 27304 10533 27304 8560 27304 9073 27305 10534 27305 9074 27305 9073 27306 10535 27306 10534 27306 9073 27307 9072 27307 10535 27307 10535 27308 9072 27308 10536 27308 10536 27309 9072 27309 9070 27309 9972 27310 9069 27310 9086 27310 10536 27311 9070 27311 10537 27311 9973 27312 10537 27312 9972 27312 9971 27313 9970 27313 10534 27313 10534 27314 9970 27314 9074 27314 9074 27315 9970 27315 9969 27315 9381 27316 10529 27316 10530 27316 9381 27317 10530 27317 10541 27317 10540 27318 10531 27318 9485 27318 10543 27319 10533 27319 10524 27319 10524 27320 10525 27320 9391 27320 10544 27321 10525 27321 10526 27321 10544 27322 10526 27322 9389 27322 10526 27323 10527 27323 9389 27323 10545 27324 10527 27324 10528 27324 10545 27325 9387 27325 9389 27325 10541 27326 9402 27326 9381 27326 9402 27327 10540 27327 9401 27327 10539 27328 9381 27328 9382 27328 10538 27329 9382 27329 9387 27329 10543 27330 9391 27330 9395 27330 10542 27331 10543 27331 9395 27331 9485 27332 9484 27332 9395 27332 8574 6 10546 6 8597 6 8574 27333 10547 27333 10546 27333 8574 6 8583 6 10547 6 10547 6 8583 6 10548 6 10548 27334 8583 27334 10549 27334 10549 27335 8583 27335 8588 27335 10551 27336 8589 27336 8590 27336 10552 27337 8590 27337 8595 27337 10546 27338 10555 27338 8597 27338 10557 27339 10552 27339 10556 27339 10552 27340 10557 27340 10372 27340 9159 27341 10553 27341 10559 27341 9159 27342 10549 27342 10553 27342 10560 27343 10546 27343 10547 27343 10546 27344 10560 27344 10561 27344 9156 27345 10555 27345 10561 27345 10554 27346 10562 27346 10556 27346 10549 27347 9154 27347 10548 27347 10555 27348 9268 27348 10554 27348 10550 27349 10558 27349 10559 27349 10558 27350 10551 27350 10372 27350 10558 27351 10372 27351 10559 27351 9584 27352 9613 27352 10563 27352 10563 27353 9582 27353 9584 27353 9582 27354 10566 27354 10564 27354 9606 27355 10564 27355 10567 27355 10565 27356 9613 27356 10568 27356 10568 27357 9613 27357 9609 27357 10569 27358 9608 27358 10567 27358 10569 27359 9609 27359 9608 27359 10569 27360 10568 27360 9609 27360 10574 27361 10570 27361 10567 27361 10575 27362 10567 27362 10576 27362 10576 27363 10567 27363 10566 27363 10579 27364 10566 27364 10563 27364 10580 27365 10565 27365 10572 27365 10581 27366 10568 27366 10573 27366 10573 27367 10570 27367 10582 27367 10582 27368 10570 27368 10574 27368 10576 27369 10566 27369 10578 27369 10582 27370 8585 27370 10573 27370 10582 27371 10574 27371 8586 27371 8592 27372 10575 27372 10576 27372 8592 27373 10576 27373 10578 27373 8592 27374 10578 27374 8593 27374 8594 27375 10572 27375 8587 27375 8587 27376 10581 27376 8585 27376 10218 27377 10215 27377 10583 27377 10217 27378 10585 27378 10584 27378 10223 27379 10585 27379 10220 27379 8585 27380 10586 27380 10587 27380 10588 27381 8586 27381 10589 27381 10589 27382 8592 27382 10590 27382 10594 27383 8587 27383 10595 27383 10587 27384 10595 27384 8585 27384 9162 27385 9161 27385 10373 27385 10382 27386 10375 27386 10243 27386 10382 27387 10245 27387 10383 27387 9159 27388 10559 27388 9158 27388 10559 27389 10350 27389 9158 27389 10373 27390 10243 27390 10375 27390 9456 27391 10592 27391 10593 27391 10597 27392 9456 27392 10593 27392 10597 27393 10593 27393 10594 27393 10594 27394 10595 27394 9454 27394 9474 27395 10586 27395 10588 27395 10588 27396 10589 27396 9470 27396 9469 27397 10590 27397 10600 27397 9474 27398 9453 27398 10599 27398 9459 27399 9460 27399 10596 27399 10600 27400 10596 27400 9460 27400 9454 27401 10598 27401 9453 27401 10597 27402 9454 27402 9456 27402 10416 6 10252 6 10433 6 10433 6 10252 6 10253 6 10256 27403 10434 27403 10255 27403 10256 27404 10429 27404 10434 27404 10429 27405 10257 27405 10435 27405 10435 6 10257 6 10258 6 10437 6 10259 6 10424 6 10253 27406 10254 27406 10255 27406 10259 27407 10260 27407 10424 27407 10424 6 10260 6 10422 6 10422 6 10260 6 10261 6 10583 27408 10261 27408 10262 27408 10421 27409 10583 27409 10584 27409 10417 27410 10585 27410 10223 27410 8010 27411 9263 27411 8012 27411 8017 27412 9261 27412 9262 27412 8018 27413 9309 27413 9302 27413 8021 27414 9297 27414 9181 27414 8023 27415 9181 27415 9179 27415 10213 27416 10602 27416 10603 27416 10474 27417 10605 27417 10606 27417 10470 6 10471 6 10609 6 8017 27418 9262 27418 8016 27418 8018 27419 9302 27419 8019 27419 8019 27420 9299 27420 8020 27420 8020 27421 9297 27421 8021 27421 8021 27422 9181 27422 8023 27422 8023 27423 9179 27423 8024 27423 8035 27424 9180 27424 10601 27424 10610 27425 10611 27425 8037 27425 8037 27426 10611 27426 8038 27426 10474 27427 10209 27427 10605 27427 10601 27428 10280 27428 10214 27428 10602 27429 10280 27429 10612 27429 10613 6 10480 6 10479 6 10614 27430 10479 27430 10478 27430 10617 27431 10616 27431 10476 27431 10614 27432 10478 27432 10615 27432 10615 27433 10477 27433 10616 27433 10476 27434 10475 27434 10609 27434 10471 6 10472 6 10608 6 10472 27435 10473 27435 10607 27435 10322 27436 10499 27436 10324 27436 10324 27437 10499 27437 10210 27437 8033 27438 8038 27438 10611 27438 10230 27439 8008 27439 10229 27439 10229 27440 8008 27440 8007 27440 10224 27441 7995 27441 10369 27441 10223 27442 10391 27442 10251 27442 10223 27443 10224 27443 10391 27443 10227 27444 7995 27444 10224 27444 10422 27445 10583 27445 10421 27445 10421 27446 10584 27446 10419 27446 10419 27447 10585 27447 10417 27447 10213 6 10603 6 10211 6 10434 27448 10433 27448 10253 27448 10620 27449 9778 27449 9779 27449 10621 27450 9870 27450 10622 27450 10621 27451 10623 27451 9870 27451 9870 27452 10623 27452 9779 27452 10622 27453 9870 27453 10624 27453 10624 27454 9870 27454 9869 27454 10604 27455 10626 27455 10625 27455 10604 27456 10603 27456 10626 27456 10626 27457 10603 27457 10627 27457 9908 27458 10627 27458 9869 27458 9908 27459 10626 27459 10627 27459 9908 27460 9897 27460 10487 27460 10603 27461 10602 27461 10627 27461 10627 27462 10602 27462 9869 27462 10612 27463 10621 27463 10622 27463 9697 27464 10617 27464 10632 27464 9696 27465 10619 27465 10630 27465 10629 27466 10615 27466 10630 27466 10619 27467 10629 27467 10630 27467 10630 27468 10616 27468 10631 27468 10617 27469 10609 27469 10632 27469 10632 27470 10609 27470 10633 27470 10609 27471 10608 27471 10633 27471 10633 27472 10608 27472 10634 27472 10634 27473 10607 27473 10484 27473 10482 27474 10634 27474 10484 27474 10486 27475 10636 27475 10626 27475 10487 27476 10486 27476 10626 27476 10635 27477 10606 27477 10605 27477 10626 27478 10636 27478 10625 27478 10486 27479 10485 27479 10636 27479 10485 27480 10484 27480 10635 27480 10620 27481 10623 27481 10628 27481 10622 27482 10624 27482 10612 27482 10612 27483 10624 27483 10602 27483 10602 27484 10624 27484 9869 27484 10614 27485 10628 27485 10613 27485 10323 27486 10271 27486 10320 27486 10474 27487 10323 27487 10324 27487 10637 27488 10204 27488 10203 27488 10318 27489 10497 27489 10321 27489 9332 27490 10456 27490 9329 27490 10640 27491 10639 27491 9742 27491 9743 27492 10638 27492 10641 27492 10639 27493 10638 27493 9743 27493 10642 27494 10645 27494 10643 27494 10642 53 10647 53 10646 53 10646 27495 10647 27495 10648 27495 10648 27496 10647 27496 9742 27496 10643 27497 10463 27497 10464 27497 10462 27498 9742 27498 9769 27498 8990 27499 10650 27499 10651 27499 8936 27500 10651 27500 8935 27500 10652 27501 8932 27501 8934 27501 8990 27502 8992 27502 10650 27502 8992 27503 8994 27503 10650 27503 10655 27504 10651 27504 10656 27504 8934 27505 10658 27505 10652 27505 10652 27506 10653 27506 10650 27506 10655 27507 10657 27507 8935 27507 10651 27508 10655 27508 8935 27508 10658 27509 10660 27509 10659 27509 10661 27510 10658 27510 10657 27510 10662 27511 10655 27511 10664 27511 10656 27512 10666 27512 10665 27512 10656 27513 10654 27513 10666 27513 10666 27514 10654 27514 10667 27514 10653 27515 10668 27515 10654 27515 10660 27516 10658 27516 10670 27516 10661 27517 10657 27517 10663 27517 10667 27518 8541 27518 8530 27518 10667 27519 10668 27519 8541 27519 8541 27520 10668 27520 10669 27520 8540 27521 10669 27521 10659 27521 8537 27522 10660 27522 10670 27522 8536 27523 10670 27523 10661 27523 8531 27524 10662 27524 10664 27524 8531 27525 10664 27525 10665 27525 8534 27526 10662 27526 8531 27526 8530 27527 10671 27527 10672 27527 10675 27528 8540 27528 8537 27528 10676 27529 8537 27529 10677 27529 10676 27530 10675 27530 8537 27530 10674 27531 8540 27531 10675 27531 8537 27532 8536 27532 10677 27532 10678 27533 8534 27533 8531 27533 10679 27534 10678 27534 8531 27534 10677 27535 8536 27535 10678 27535 10494 27536 8998 27536 10502 27536 10502 27537 8998 27537 10491 27537 8998 27538 8997 27538 10491 27538 10491 27539 9000 27539 10490 27539 8923 27540 8921 27540 10490 27540 10490 27541 8921 27541 10488 27541 10489 27542 10490 27542 10488 27542 10488 27543 8920 27543 8924 27543 8909 27544 8911 27544 9786 27544 10683 27545 8941 27545 10682 27545 10684 27546 10686 27546 10687 27546 9123 27547 10684 27547 10687 27547 9125 27548 10685 27548 10684 27548 9125 27549 9124 27549 10688 27549 10690 27550 10601 27550 10637 27550 10691 27551 10675 27551 10676 27551 10693 27552 10673 27552 8790 27552 10693 27553 10694 27553 10672 27553 10681 27554 10694 27554 10695 27554 10679 27555 8836 27555 10696 27555 10696 27556 10697 27556 10678 27556 10691 27557 10676 27557 10677 27557 10675 27558 8840 27558 10674 27558 10680 27559 8836 27559 10679 27559 10270 27560 10331 27560 10327 27560 10270 27561 10267 27561 10331 27561 10331 27562 10267 27562 10325 27562 10309 27563 10325 27563 9290 27563 10266 27564 10325 27564 10267 27564 10325 27565 10265 27565 9290 27565 9294 27566 9290 27566 10266 27566 10265 27567 10266 27567 9290 27567 9286 27568 8812 27568 10309 27568 10611 27569 10610 27569 10699 27569 10701 27570 10700 27570 10207 27570 10207 27571 10700 27571 10205 27571 10208 27572 10210 27572 10701 27572 10701 27573 10210 27573 10611 27573 10201 27574 10690 27574 10637 27574 8833 27575 10698 27575 8834 27575 10693 27576 8788 27576 8787 27576 8833 27577 8840 27577 10691 27577 8790 27578 8839 27578 8788 27578 10694 27579 8836 27579 10695 27579 8834 27580 10696 27580 8836 27580 8834 27581 10697 27581 10696 27581 8809 27582 10707 27582 8810 27582 10708 27583 10709 27583 10710 27583 10710 27584 10709 27584 10711 27584 10711 27585 10709 27585 10712 27585 10712 27586 10709 27586 10713 27586 10714 27587 10716 27587 10715 27587 10717 27588 10718 27588 10714 27588 10719 27589 10718 27589 10720 27589 10721 27590 10720 27590 10710 27590 10719 27591 10720 27591 10722 27591 10722 27592 10720 27592 10721 27592 10708 27593 10710 27593 10723 27593 10723 27594 10717 27594 10708 27594 10720 27595 10289 27595 10710 27595 10720 27596 10286 27596 10289 27596 10718 27597 10283 27597 10720 27597 10724 27598 9961 27598 10708 27598 10537 27599 10725 27599 10726 27599 10726 27600 10535 27600 10536 27600 10726 27601 10727 27601 10535 27601 10535 27602 10727 27602 10534 27602 10728 27603 10534 27603 10727 27603 10288 27604 10711 27604 9956 27604 9951 27605 10713 27605 9952 27605 10715 27606 9952 27606 10713 27606 10721 27607 10288 27607 10722 27607 10722 27608 10288 27608 10287 27608 10287 27609 10285 27609 10722 27609 10722 27610 10285 27610 10719 27610 10716 27611 9958 27611 9952 27611 10283 27612 10718 27612 10284 27612 10718 27613 10723 27613 10729 27613 10730 27614 10723 27614 10710 27614 10710 27615 10292 27615 10730 27615 10095 27616 9580 27616 10728 27616 9962 27617 9961 27617 10730 27617 10730 27618 9961 27618 10729 27618 10724 27619 10281 27619 10729 27619 10284 27620 10729 27620 10282 27620 10292 27621 10290 27621 10730 27621 10730 27622 10290 27622 10291 27622 10714 27623 10709 27623 9949 27623 9953 27624 10714 27624 9949 27624 10714 27625 10732 27625 10717 27625 9957 27626 10714 27626 9953 27626 9949 27627 9961 27627 9948 27627 9948 27628 9961 27628 10733 27628 10683 27629 9948 27629 10733 27629 10734 27630 10733 27630 10735 27630 9965 27631 10731 27631 10733 27631 10736 27632 10731 27632 9965 27632 9965 27633 9089 27633 10736 27633 10736 27634 9089 27634 9087 27634 9965 27635 10733 27635 9961 27635 9945 27636 9944 27636 10738 27636 9106 27637 9945 27637 10738 27637 10738 27638 9944 27638 9101 27638 10739 27639 10738 27639 9101 27639 10537 27640 9973 27640 10725 27640 10725 27641 9973 27641 9968 27641 10725 27642 9968 27642 10740 27642 9967 27643 10741 27643 9968 27643 9967 27644 10742 27644 10741 27644 10740 27645 9968 27645 10741 27645 10742 27646 9967 27646 10728 27646 10728 27647 9967 27647 9971 27647 8966 27648 8960 27648 8970 27648 10735 27649 9568 27649 8970 27649 8970 27650 9568 27650 8975 27650 8955 27651 8957 27651 8944 27651 8955 27652 10683 27652 10734 27652 10735 27653 9562 27653 9568 27653 9554 27654 9627 27654 10743 27654 9627 27655 9564 27655 10743 27655 9567 27656 9568 27656 9562 27656 10735 27657 10733 27657 9562 27657 10725 27658 10736 27658 10737 27658 10727 27659 10096 27659 10095 27659 10728 27660 10727 27660 10095 27660 10731 27661 10741 27661 10742 27661 10740 27662 10736 27662 10725 27662 10731 27663 10742 27663 10728 27663 10688 27664 10689 27664 10744 27664 10744 27665 10689 27665 10745 27665 10745 27666 10683 27666 10682 27666 10744 27667 10739 27667 10688 27667 9102 27668 10688 27668 9110 27668 10738 27669 10682 27669 9109 27669 10738 27670 10745 27670 10682 27670 9102 27671 9103 27671 10686 27671 10686 27672 10688 27672 9102 27672 9104 27673 10686 27673 9103 27673 10749 27674 10748 27674 10747 27674 10082 27675 10084 27675 10747 27675 9441 27676 9433 27676 9448 27676 10082 27677 10746 27677 9433 27677 9426 27678 9421 27678 9433 27678 9962 27679 9950 27679 9947 27679 9963 27680 9947 27680 10747 27680 9108 27681 10751 27681 9945 27681 10749 27682 9946 27682 10751 27682 9946 27683 9945 27683 10751 27683 9964 27684 10747 27684 10084 27684 9964 27685 10084 27685 9966 27685 9969 27686 9966 27686 10083 27686 8872 27687 10751 27687 8868 27687 8871 27688 8872 27688 8868 27688 8872 27689 10750 27689 10748 27689 10751 27690 8869 27690 8867 27690 10751 27691 8867 27691 8868 27691 10750 27692 8846 27692 9448 27692 8848 27693 8889 27693 8846 27693 9087 27694 10097 27694 10737 27694 9096 6 9064 6 9063 6 9092 27695 9096 27695 9063 27695 9112 27696 9121 27696 9113 27696 10085 27697 9083 27697 10094 27697 10752 27698 9082 27698 9085 27698 10752 27699 10094 27699 9082 27699 9560 27700 9558 27700 10753 27700 9541 27701 9543 27701 9640 27701 9543 27702 9546 27702 9549 27702 10753 27703 9559 27703 10754 27703 10755 27704 10756 27704 9605 27704 9599 27705 9596 27705 10757 27705 10755 27706 10757 27706 10094 27706 9603 27707 10755 27707 9605 27707 9120 27708 10758 27708 8938 27708 10758 27709 9120 27709 9118 27709 8929 27710 8930 27710 8938 27710 8938 27711 8930 27711 8937 27711 8987 27712 8965 27712 10759 27712 10760 27713 9785 27713 9786 27713 8950 27714 8948 27714 10760 27714 9787 27715 10760 27715 10759 27715 8965 27716 8961 27716 9677 27716 8948 27717 8947 27717 10759 27717 10761 27718 8918 27718 8917 27718 10764 27719 10765 27719 8729 27719 10767 27720 9057 27720 10766 27720 10766 27721 9057 27721 9121 27721 10768 27722 9027 27722 9026 27722 9057 27723 10305 27723 9062 27723 9026 27724 8897 27724 10305 27724 10329 27725 8884 27725 9037 27725 8830 27726 9037 27726 8884 27726 9284 27727 10769 27727 9285 27727 9246 27728 8856 27728 9284 27728 8873 27729 8874 27729 10769 27729 9285 27730 10770 27730 9229 27730 9285 27731 10769 27731 10770 27731 8800 27732 8799 27732 10770 27732 8799 27733 8797 27733 10770 27733 10770 27734 8797 27734 9286 27734 9428 27735 9280 27735 9277 27735 9428 27736 9277 27736 9429 27736 10771 27737 9277 27737 9273 27737 10772 27738 9273 27738 9269 27738 9418 27739 10772 27739 9451 27739 9418 27740 9415 27740 10772 27740 9429 27741 9277 27741 9424 27741 9424 27742 9277 27742 9423 27742 9423 27743 10771 27743 9416 27743 9047 27744 9392 27744 9386 27744 10773 27745 9049 27745 9047 27745 10773 27746 9386 27746 9383 27746 9042 27747 10775 27747 9085 27747 9042 27748 9049 27748 10773 27748 10776 27749 9522 27749 10777 27749 10778 27750 10756 27750 10775 27750 10371 27751 10362 27751 10370 27751 10186 27752 9605 27752 10756 27752 8765 27753 10329 27753 9037 27753 10329 27754 10500 27754 10501 27754 10500 27755 10329 27755 8765 27755 8765 27756 8764 27756 10500 27756 10780 27757 10781 27757 8908 27757 10781 27758 10782 27758 8910 27758 8910 27759 10782 27759 10783 27759 8908 27760 8918 27760 10780 27760 10762 27761 8915 27761 10784 27761 8908 27762 10781 27762 8910 27762 8953 27763 10154 27763 10787 27763 8953 27764 10787 27764 10199 27764 10153 27765 10787 27765 10154 27765 10153 27766 10199 27766 10787 27766 10150 27767 10155 27767 10198 27767 10198 27768 8942 27768 10150 27768 8943 27769 10788 27769 8942 27769 10788 27770 8943 27770 10153 27770 10764 27771 8729 27771 8778 27771 10768 27772 10765 27772 9027 27772 10767 27773 10766 27773 10768 27773 9023 27774 8777 27774 8779 27774 9023 27775 8776 27775 9020 27775 9018 6 8076 6 8074 6 9017 6 8074 6 8735 6 9011 27776 8748 27776 8773 27776 9017 6 8735 6 9025 6 9025 6 8740 6 9024 6 9007 27777 8055 27777 8053 27777 9030 27778 8052 27778 8050 27778 9033 27779 8775 27779 8769 27779 9033 27780 8769 27780 8767 27780 9035 27781 9033 27781 8767 27781 9007 27782 8053 27782 9028 27782 9028 27783 8052 27783 9030 27783 8766 27784 9035 27784 8768 27784 8765 27785 9037 27785 9036 27785 8812 27786 9286 27786 8797 27786 10703 27787 10790 27787 10704 27787 10702 27788 10791 27788 8818 27788 10702 27789 8822 27789 10791 27789 10789 27790 10703 27790 10706 27790 10793 27791 10705 27791 8811 27791 10707 27792 8809 27792 10797 27792 10798 27793 8809 27793 8817 27793 10793 27794 8811 27794 10794 27794 10795 27795 8810 27795 10796 27795 8822 27796 10704 27796 10790 27796 10779 27797 10777 27797 10193 27797 10182 27798 10181 27798 9508 27798 9508 27799 10181 27799 9511 27799 9511 27800 10181 27800 10196 27800 9521 27801 7969 27801 10191 27801 7969 27802 9521 27802 10188 27802 10188 27803 9521 27803 9520 27803 10167 6 9520 6 9519 6 7972 27804 9517 27804 9514 27804 7976 27805 9515 27805 9513 27805 9512 27806 7976 27806 9513 27806 9512 27807 10170 27807 7976 27807 10170 6 9507 6 10172 6 10175 27808 9501 27808 9502 27808 10179 27809 9502 27809 9503 27809 10196 27810 10180 27810 9511 27810 10188 27811 9520 27811 10167 27811 10167 27812 9519 27812 10166 27812 10166 27813 9517 27813 7972 27813 7972 27814 9514 27814 7974 27814 10175 27815 9502 27815 10179 27815 10179 27816 9503 27816 10178 27816 10178 27817 9503 27817 10180 27817 9525 27818 9524 27818 10194 27818 10194 27819 9524 27819 10195 27819 10193 27820 9525 27820 10194 27820 10774 27821 10776 27821 10775 27821 10775 27822 10776 27822 10778 27822 10779 27823 10192 27823 10756 27823 4752 27824 4751 27824 10363 27824 10363 27825 4751 27825 10367 27825 4751 27826 10381 27826 10367 27826 10386 27827 10366 27827 10381 27827 10389 27828 10390 27828 9936 27828 9714 27829 9773 27829 9350 27829 9350 27830 9773 27830 10800 27830 9714 27831 9350 27831 9129 27831 9127 27832 9716 27832 9129 27832 10802 27833 10803 27833 10804 27833 9717 27834 10805 27834 9126 27834 9717 27835 9128 27835 9131 27835 9774 27836 10808 27836 9320 27836 10809 27837 10808 27837 9774 27837 9242 27838 9321 27838 9774 27838 9322 27839 9321 27839 9242 27839 10469 27840 9705 27840 9680 27840 9765 27841 9777 27841 10811 27841 9768 27842 9769 27842 9766 27842 10644 27843 9769 27843 9768 27843 9734 27844 9732 27844 10814 27844 10641 27845 10814 27845 9730 27845 9734 27846 10814 27846 10813 27846 10813 27847 9715 27847 9875 27847 10815 27848 9715 27848 10813 27848 10318 27849 10319 27849 10497 27849 10498 27850 10319 27850 10495 27850 10495 27851 10319 27851 6611 27851 6610 27852 10495 27852 6611 27852 10501 27853 10496 27853 10330 27853 10761 27854 10822 27854 10823 27854 10786 27855 10761 27855 10823 27855 10786 27856 10824 27856 10780 27856 10782 27857 10780 27857 10826 27857 10782 27858 10827 27858 10783 27858 10829 27859 9290 27859 9289 27859 10831 27860 10829 27860 10832 27860 9268 27861 9267 27861 10562 27861 10439 27862 9345 27862 10444 27862 10444 27863 9345 27863 9349 27863 9348 27864 10444 27864 9349 27864 9330 27865 10838 27865 10837 27865 10838 27866 9328 27866 10457 27866 9329 27867 10457 27867 9328 27867 9324 27868 9322 27868 10836 27868 10800 27869 9773 27869 10839 27869 10800 27870 10647 27870 10802 27870 10802 27871 10647 27871 10840 27871 10840 27872 10647 27872 10642 27872 10840 27873 10642 27873 10841 27873 10809 27874 10840 27874 10841 27874 10841 27875 10842 27875 9325 27875 10802 27876 10801 27876 10800 27876 10843 27877 10453 27877 10440 27877 10453 27878 9133 27878 10807 27878 10807 27879 10837 27879 10453 27879 10836 27880 10837 27880 9324 27880 10804 27881 10805 27881 10843 27881 10840 27882 10843 27882 10806 27882 10806 27883 10843 27883 10805 27883 9325 27884 9324 27884 10841 27884 9323 27885 9325 27885 10810 27885 10845 27886 9680 27886 10842 27886 10644 27887 10811 27887 10642 27887 10846 27888 10811 27888 9777 27888 10812 27889 10466 27889 10844 27889 10846 27890 9777 27890 10845 27890 10639 27891 10848 27891 10638 27891 10848 27892 10849 27892 10638 27892 10638 27893 10849 27893 10641 27893 10641 27894 10849 27894 10850 27894 10641 27895 10850 27895 10814 27895 9773 27896 9715 27896 10839 27896 10848 27897 9715 27897 10815 27897 10813 27898 10850 27898 10849 27898 10839 27899 9715 27899 10848 27899 10848 27900 10815 27900 10849 27900 8521 27901 10816 27901 8509 27901 8521 27902 10818 27902 10816 27902 10818 27903 8521 27903 10819 27903 10826 27904 8515 27904 8507 27904 10817 27905 8507 27905 8509 27905 10816 27906 10817 27906 8509 27906 10819 27907 8519 27907 10820 27907 10824 27908 8515 27908 10825 27908 10827 27909 8507 27909 10817 27909 10851 27910 10309 27910 10852 27910 10854 27911 10855 27911 10851 27911 10851 27912 10855 27912 9287 27912 9287 27913 10855 27913 10856 27913 9287 27914 10856 27914 10830 27914 10830 27915 10857 27915 10858 27915 10830 27916 10858 27916 9288 27916 10828 27917 10860 27917 9289 27917 10829 27918 10860 27918 10832 27918 10832 27919 10861 27919 10831 27919 10831 27920 10862 27920 10853 27920 10853 27921 10862 27921 10854 27921 10852 27922 10854 27922 10851 27922 10443 27923 10834 27923 10835 27923 10443 27924 10444 27924 10834 27924 10801 27925 10440 27925 10441 27925 10441 27926 10442 27926 10835 27926 10452 27927 10649 27927 10643 27927 10452 27928 10450 27928 10649 27928 10648 27929 10450 27929 10448 27929 10646 27930 10448 27930 10455 27930 10646 27931 10455 27931 10454 27931 10643 27932 10454 27932 10452 27932 10649 27933 10450 27933 10648 27933 10458 27934 10459 27934 10838 27934 10838 27935 10459 27935 10837 27935 8518 27936 10790 27936 10789 27936 10791 27937 8519 27937 8521 27937 10799 27938 10791 27938 8521 27938 10792 27939 8515 27939 8516 27939 10795 27940 10796 27940 8507 27940 8507 27941 10796 27941 8509 27941 8509 27942 10796 27942 10797 27942 8521 27943 10797 27943 10798 27943 8515 27944 10793 27944 8507 27944 10791 27945 10790 27945 8519 27945 9942 27946 10865 27946 10866 27946 9943 27947 10866 27947 10867 27947 9943 27948 10868 27948 10869 27948 9940 27949 10872 27949 10873 27949 9939 27950 10872 27950 9940 27950 9940 27951 10874 27951 9941 27951 10875 27952 9911 27952 9910 27952 9912 27953 10876 27953 10877 27953 9913 27954 10877 27954 10878 27954 9913 27955 10878 27955 9914 27955 9912 27956 9911 27956 10876 27956 10879 27957 10875 27957 9916 27957 10647 27958 10800 27958 10847 27958 10642 27959 10846 27959 10841 27959 10841 27960 10846 27960 10845 27960 10874 27961 8574 27961 10864 27961 10874 27962 8583 27962 8574 27962 10874 27963 10873 27963 8583 27963 8583 27964 10873 27964 8588 27964 8588 27965 10873 27965 10872 27965 8588 27966 10872 27966 10871 27966 8589 27967 10871 27967 10870 27967 8590 27968 10870 27968 10869 27968 8590 27969 10869 27969 10868 27969 8595 27970 10867 27970 10866 27970 8596 27971 10866 27971 10865 27971 8596 27972 10865 27972 10863 27972 8574 27973 8597 27973 10864 27973 8588 27974 10871 27974 8589 27974 8595 27975 10866 27975 8596 27975 10877 27976 8503 27976 10878 27976 8502 27977 10877 27977 10876 27977 8505 27978 10875 27978 10879 27978 8505 27979 10879 27979 8506 27979 8506 27980 10880 27980 8508 27980 8511 27981 10881 27981 8607 27981 8505 27982 10855 27982 10854 27982 8505 27983 8506 27983 10855 27983 10857 27984 8506 27984 8508 27984 10858 27985 8508 27985 10859 27985 10862 27986 10861 27986 8504 27986 8504 27987 10861 27987 8502 27987 8503 27988 10828 27988 8607 27988 8508 27989 8511 27989 10859 27989 8607 27990 10828 27990 8511 27990 8504 27991 8505 27991 10862 27991 10862 27992 8505 27992 10854 27992 10882 27993 10883 27993 10884 27993 10889 27994 10887 27994 10888 27994 10890 27995 10891 27995 10888 27995 10888 27996 10891 27996 10889 27996 10882 27997 10884 27997 10892 27997 10893 27998 10892 27998 10890 27998 10890 27999 10892 27999 10891 27999 10889 28000 10892 28000 10887 28000 10885 28001 10892 28001 10884 28001 10894 28002 10895 28002 10896 28002 10896 28003 10897 28003 10900 28003 10899 28004 10900 28004 10901 28004 10903 28005 10906 28005 10905 28005 10908 28006 10909 28006 10906 28006 10906 28007 10909 28007 10907 28007 10905 28008 10907 28008 10904 28008 10904 53 10907 53 10909 53 10912 28009 10911 28009 10913 28009 10914 28010 10915 28010 10910 28010 10914 28011 10916 28011 10915 28011 10911 53 10915 53 10913 53 10918 28012 10919 28012 10920 28012 10918 28013 10922 28013 10919 28013 10919 28014 10922 28014 10923 28014 10924 28015 10921 28015 10925 28015 10922 28016 10924 28016 10923 28016 10919 53 10925 53 10921 53 10926 28017 10927 28017 10928 28017 10928 28018 10927 28018 10929 28018 10929 28019 10927 28019 10930 28019 10930 28020 10931 28020 10929 28020 10934 28021 10933 28021 10935 28021 10928 28022 10929 28022 10934 28022 10934 28023 10929 28023 10932 28023 10938 28024 10937 28024 10939 28024 10937 28025 10936 28025 10940 28025 10943 28026 10944 28026 10945 28026 10946 28027 10949 28027 10950 28027 10949 28028 10939 28028 10950 28028 10937 28029 10940 28029 10946 28029 10945 28030 10940 28030 10943 28030 10951 28031 10954 28031 10952 28031 10951 28032 10955 28032 10954 28032 10951 28033 10956 28033 10955 28033 10955 28034 10956 28034 10957 28034 10960 28035 10961 28035 10962 28035 10963 28036 10964 28036 10965 28036 10966 28037 10964 28037 10967 28037 10975 28038 10977 28038 10976 28038 10979 28039 10980 28039 10981 28039 10979 28040 10978 28040 10980 28040 10972 28041 10970 28041 10983 28041 10970 28042 10968 28042 10983 28042 10984 28043 10968 28043 10985 28043 10984 28044 10985 28044 10986 28044 10986 28045 10985 28045 10987 28045 10960 28046 10958 28046 10959 28046 10957 28047 10958 28047 10955 28047 10991 28048 10990 28048 10992 28048 10992 28049 10993 28049 10994 28049 10998 28050 10999 28050 11000 28050 11001 28051 10998 28051 11000 28051 11005 28052 10998 28052 11002 28052 11005 28053 11006 28053 10998 28053 11006 28054 10995 28054 10999 28054 10997 28055 11000 28055 10999 28055 11007 28056 11008 28056 11009 28056 11010 28057 11009 28057 11011 28057 11017 28058 11016 28058 11013 28058 11021 28059 11022 28059 10959 28059 10957 28060 11021 28060 10959 28060 10957 28061 10956 28061 11023 28061 11025 28062 11024 28062 11026 28062 10977 28063 11027 28063 10978 28063 10980 28064 11027 28064 11028 28064 11029 28065 11028 28065 11030 28065 11033 28066 11036 28066 11031 28066 11029 28067 11030 28067 11031 28067 11032 28068 11037 28068 11034 28068 11034 28069 11037 28069 11038 28069 11035 28070 11038 28070 8132 28070 11035 28071 11034 28071 11038 28071 10973 28072 11039 28072 11040 28072 10971 28073 11040 28073 10969 28073 10970 28074 10971 28074 10969 28074 10973 28075 11040 28075 10971 28075 10972 28076 10973 28076 10971 28076 11042 28077 11011 28077 11009 28077 11008 28078 11042 28078 11009 28078 11008 28079 11014 28079 11042 28079 11008 28080 11043 28080 11014 28080 11012 28081 11011 28081 11041 28081 10995 28082 10992 28082 10996 28082 11041 28083 11011 28083 11042 28083 11041 28084 11018 28084 11026 28084 10888 28085 11047 28085 11046 28085 11046 28086 11047 28086 11048 28086 11049 28087 11046 28087 11048 28087 11053 28088 10930 28088 11055 28088 11056 28089 11053 28089 11055 28089 11057 28090 10942 28090 11054 28090 10948 28091 11057 28091 11058 28091 10949 28092 11059 28092 11060 28092 11061 28093 11062 28093 11063 28093 11061 28094 11063 28094 11064 28094 11068 28095 11067 28095 11069 28095 11069 28096 11070 28096 10927 28096 11073 28097 11072 28097 11074 28097 11075 28098 11076 28098 11074 28098 11075 28099 11077 28099 11076 28099 11075 28100 11079 28100 11078 28100 11075 28101 11080 28101 11079 28101 11079 28102 11080 28102 11081 28102 11080 28103 11082 28103 11081 28103 11082 28104 11083 28104 11084 28104 11086 28105 11087 28105 11088 28105 11086 28106 11088 28106 11089 28106 11080 28107 11090 28107 11091 28107 11093 28108 11094 28108 11095 28108 11096 28109 11094 28109 11097 28109 11095 28110 11098 28110 11099 28110 11095 28111 11099 28111 11100 28111 11103 28112 11104 28112 11105 28112 11107 28113 11103 28113 11105 28113 11107 28114 11108 28114 11103 28114 11107 28115 11109 28115 11108 28115 11089 28116 11088 28116 11108 28116 11111 28117 11089 28117 11110 28117 11111 28118 11112 28118 11089 28118 11111 28119 11113 28119 11112 28119 11112 28120 11113 28120 11114 28120 11115 28121 11116 28121 11114 28121 11116 28122 11115 28122 11117 28122 11117 28123 11115 28123 11118 28123 11119 28124 11120 28124 11113 28124 11124 28125 11130 28125 11129 28125 11122 28126 11131 28126 11123 28126 11123 28127 11131 28127 11132 28127 11133 28128 11123 28128 11132 28128 11135 28129 11136 28129 11137 28129 11138 28130 11137 28130 11139 28130 11135 28131 11140 28131 11134 28131 11132 28132 11131 28132 11141 28132 11142 28133 11141 28133 11143 28133 11142 28134 11132 28134 11141 28134 11137 28135 11144 28135 11145 28135 11146 28136 11148 28136 11147 28136 11150 28137 11149 28137 11151 28137 11154 28138 11152 28138 11153 28138 11154 28139 11155 28139 11152 28139 11155 28140 11154 28140 11156 28140 11133 28141 11160 28141 11144 28141 11144 28142 11160 28142 11161 28142 11145 28143 11144 28143 11161 28143 11147 28144 11149 28144 11150 28144 11139 28145 11137 28145 11147 28145 11166 28146 11165 28146 11167 28146 11168 28147 11170 28147 11169 28147 11168 28148 11171 28148 11170 28148 11168 28149 11172 28149 11171 28149 11171 28150 11172 28150 11173 28150 11174 28151 11173 28151 11172 28151 11174 28152 11049 28152 11173 28152 11174 28153 11051 28153 11049 28153 11175 28154 11178 28154 11176 28154 11108 28155 11181 28155 11103 28155 11093 28156 11177 28156 11090 28156 11182 28157 11118 28157 11184 28157 11187 28158 11189 28158 11190 28158 11188 28159 11185 28159 11186 28159 11086 28160 11084 28160 11085 28160 11129 28161 11192 28161 11166 28161 11124 28162 11121 28162 11123 28162 11114 28163 11120 28163 11193 28163 11193 28164 11194 28164 11114 28164 11193 28165 11195 28165 11194 28165 11074 28166 11197 28166 11073 28166 11194 28167 11195 28167 11196 28167 11196 28168 11197 28168 11198 28168 11198 28169 11197 28169 11074 28169 11108 28170 11180 28170 11181 28170 10927 28171 11070 28171 11055 28171 10930 28172 10927 28172 11055 28172 11170 28173 11067 28173 11169 28173 11169 28174 11067 28174 11065 28174 10949 28175 11201 28175 10938 28175 10949 28176 11060 28176 11201 28176 10927 28177 11068 28177 11069 28177 10941 28178 10936 28178 10931 28178 10931 28179 10936 28179 10933 28179 10935 28180 10936 28180 10938 28180 11129 28181 11128 28181 11192 28181 11192 28182 11128 28182 11163 28182 11201 28183 11060 28183 11062 28183 10938 28184 11201 28184 11066 28184 10935 28185 10938 28185 11066 28185 11062 28186 11167 28186 11063 28186 11061 28187 11066 28187 11201 28187 11125 28188 11126 28188 11130 28188 11208 28189 11206 28189 11209 28189 11214 28190 11215 28190 11204 28190 11214 28191 11216 28191 11215 28191 11219 28192 11220 28192 11221 28192 11219 28193 11218 28193 11222 28193 11218 28194 11213 28194 11222 28194 11212 28195 11210 28195 11211 28195 11226 28196 11227 28196 11228 28196 11229 28197 11228 28197 11230 28197 11229 28198 11226 28198 11228 28198 11226 28199 11231 28199 11224 28199 11237 28200 11235 28200 11236 28200 11238 28201 11239 28201 11235 28201 11241 28202 11233 28202 11239 28202 11241 28203 11225 28203 11233 28203 11224 28204 11232 28204 11233 28204 11228 28205 11242 28205 11243 28205 11245 28206 11246 28206 11247 28206 11245 28207 11243 28207 11246 28207 11252 28208 11253 28208 11251 28208 11252 28209 11254 28209 11253 28209 11254 28210 11255 28210 11256 28210 11259 28211 11260 28211 11258 28211 11260 28212 11262 28212 11207 28212 11255 28213 11264 28213 11256 28213 11256 28214 11264 28214 11265 28214 11266 28215 11264 28215 11267 28215 11265 28216 11264 28216 11266 28216 11271 28217 11241 28217 11240 28217 11280 28218 11279 28218 11281 28218 11279 28219 11282 28219 11281 28219 11281 28220 11282 28220 11283 28220 11284 28221 11283 28221 11282 28221 11284 28222 11285 28222 11283 28222 11284 28223 11286 28223 11285 28223 11287 28224 11288 28224 11289 28224 11288 28225 11285 28225 11272 28225 11290 28226 11213 28226 11288 28226 11291 28227 11289 28227 11292 28227 11295 28228 11294 28228 11296 28228 11291 28229 11292 28229 11293 28229 11295 28230 11296 28230 11263 28230 11254 28231 11256 28231 11258 28231 10989 28232 11297 28232 10990 28232 10993 28233 11298 28233 11299 28233 10993 28234 11299 28234 10994 28234 10994 28235 11300 28235 11301 28235 11300 28236 11302 28236 11301 28236 11304 28237 11303 28237 11305 28237 11306 28238 11305 28238 11307 28238 11302 28239 11305 28239 11303 28239 11246 28240 11249 28240 11247 28240 11233 28241 11234 28241 11235 28241 11311 28242 11312 28242 11313 28242 11313 28243 11315 28243 11316 28243 11316 28244 11315 28244 11317 28244 11318 28245 11316 28245 11317 28245 11314 28246 11309 28246 11310 28246 10993 28247 10990 28247 11298 28247 11319 28248 11320 28248 11321 28248 11320 28249 11322 28249 11321 28249 11326 28250 11322 28250 11325 28250 11325 28251 11324 28251 11327 28251 11327 28252 11328 28252 11329 28252 11332 28253 11330 28253 11333 28253 11330 28254 11328 28254 11333 28254 11325 28255 11327 28255 11335 28255 11327 28256 11336 28256 11335 28256 11338 28257 11339 28257 11340 28257 11342 28258 11343 28258 11339 28258 11339 28259 11343 28259 11341 28259 11347 28260 11346 28260 11348 28260 11346 28261 11349 28261 11348 28261 11348 28262 11349 28262 11350 28262 11351 28263 11347 28263 11352 28263 11351 28264 11344 28264 11347 28264 11348 28265 11353 28265 11347 28265 11350 28266 11356 28266 11355 28266 11337 28267 11321 28267 11326 28267 11326 28268 11321 28268 11322 28268 11329 28269 11331 28269 11358 28269 11323 28270 11320 28270 11360 28270 11331 28271 11330 28271 11359 28271 11323 28272 11360 28272 11361 28272 11324 28273 11323 28273 11361 28273 11361 28274 11333 28274 11324 28274 11324 28275 11333 28275 11328 28275 11344 28276 11351 28276 11345 28276 11347 28277 11353 28277 11352 28277 11342 28278 11339 28278 11363 28278 11363 28279 11339 28279 11338 28279 11364 28280 11349 28280 11366 28280 11349 28281 11346 28281 11366 28281 11365 28282 11366 28282 11343 28282 11367 28283 11368 28283 11369 28283 11370 28284 11371 28284 11372 28284 11373 28285 11370 28285 11372 28285 11374 28286 11375 28286 11376 28286 11379 28287 11378 28287 11113 28287 11378 28288 11377 28288 11122 28288 11122 28289 11380 28289 11131 28289 11385 28290 11382 28290 11142 28290 11142 28291 11382 28291 11132 28291 11132 28292 11382 28292 11384 28292 11132 28293 11386 28293 11133 28293 11381 28294 11143 28294 11377 28294 11380 28295 11377 28295 11141 28295 11385 28296 11387 28296 11383 28296 11386 28297 11384 28297 11383 28297 11388 28298 11389 28298 11220 28298 11389 28299 11390 28299 11391 28299 11393 28300 11391 28300 11396 28300 11396 28301 11397 28301 11398 28301 8279 28302 11398 28302 11399 28302 8279 28303 11396 28303 11398 28303 11397 28304 11288 28304 11398 28304 11401 28305 11400 28305 11403 28305 11402 28306 11405 28306 11403 28306 11403 28307 11405 28307 11406 28307 11404 28308 11406 28308 11407 28308 11405 28309 11240 28309 11406 28309 11406 28310 11240 28310 11408 28310 11407 28311 11408 28311 8281 28311 11407 28312 11406 28312 11408 28312 11240 28313 11409 28313 11408 28313 8281 28314 11410 28314 8282 28314 11417 28315 11314 28315 11418 28315 11417 28316 11418 28316 11419 28316 11314 28317 11417 28317 11416 28317 11410 28318 11411 28318 11412 28318 8282 28319 11410 28319 11412 28319 11421 28320 11412 28320 11413 28320 11413 28321 11414 28321 11415 28321 11314 28322 11423 28322 11418 28322 11419 28323 11313 28323 8284 28323 11394 28324 8277 28324 11220 28324 11219 28325 11388 28325 11220 28325 11388 28326 11222 28326 11390 28326 11395 28327 11390 28327 11222 28327 11290 28328 11395 28328 11222 28328 11290 28329 11397 28329 11395 28329 11290 28330 11288 28330 11397 28330 11238 28331 11409 28331 11240 28331 11237 28332 11309 28332 11414 28332 11311 28333 11423 28333 11314 28333 11101 28334 11099 28334 11425 28334 11429 28335 11430 28335 11431 28335 11432 28336 11431 28336 11430 28336 11430 28337 11433 28337 11432 28337 11434 28338 11435 28338 11432 28338 11433 28339 11436 28339 11432 28339 11432 28340 11436 28340 11437 28340 11437 28341 11436 28341 11439 28341 11442 28342 11443 28342 11444 28342 11448 28343 11092 28343 11090 28343 11448 28344 11090 28344 11449 28344 11450 28345 11448 28345 11449 28345 11445 28346 11092 28346 11448 28346 11451 28347 11456 28347 11455 28347 11451 28348 11457 28348 11456 28348 11456 28349 11457 28349 11458 28349 11453 28350 11460 28350 11451 28350 11462 28351 11463 28351 11464 28351 11465 28352 11463 28352 11462 28352 11469 28353 11471 28353 11470 28353 11470 28354 11471 28354 11450 28354 11473 28355 11470 28355 11472 28355 11473 28356 11474 28356 11470 28356 11476 28357 11472 28357 11477 28357 11476 28358 11475 28358 11472 28358 11477 28359 11450 28359 11478 28359 11459 28360 11480 28360 11481 28360 11462 28361 11466 28361 11465 28361 11466 28362 11483 28362 11465 28362 11469 28363 11459 28363 11457 28363 11478 28364 11485 28364 11479 28364 11450 28365 11449 28365 11478 28365 11448 28366 11450 28366 11487 28366 11487 28367 11450 28367 11471 28367 11433 28368 11488 28368 11436 28368 11436 28369 11488 28369 11440 28369 11433 28370 11429 28370 11488 28370 11445 28371 11487 28371 11444 28371 11444 28372 11491 28372 11490 28372 11492 28373 11487 28373 11493 28373 11432 28374 11435 28374 11431 28374 11495 28375 11431 28375 11435 28375 11496 28376 11497 28376 11461 28376 11461 28377 11497 28377 11498 28377 11484 28378 11498 28378 11499 28378 11500 28379 11458 28379 11482 28379 11500 28380 11481 28380 11501 28380 11501 28381 11481 28381 11483 28381 11483 28382 11481 28382 11480 28382 11499 28383 11502 28383 11469 28383 11469 28384 11502 28384 11471 28384 11471 28385 11502 28385 11493 28385 11503 28386 11504 28386 11470 28386 11470 28387 11504 28387 11463 28387 11463 28388 11504 28388 11468 28388 11505 28389 11503 28389 11470 28389 11505 28390 11473 28390 11475 28390 11476 28391 11477 28391 11479 28391 11479 28392 11486 28392 11476 28392 11424 28393 11098 28393 11427 28393 11428 28394 11427 28394 11506 28394 8168 28395 11507 28395 11508 28395 8167 28396 11507 28396 8168 28396 11508 28397 11507 28397 11515 28397 11030 28398 11028 28398 11518 28398 11518 28399 11519 28399 11520 28399 11515 28400 11507 28400 11519 28400 8165 28401 11037 28401 11032 28401 11518 28402 11520 28402 11032 28402 11507 28403 8167 28403 11519 28403 11518 28404 11028 28404 11027 28404 10977 28405 11518 28405 11027 28405 11513 28406 11019 28406 11521 28406 11510 28407 11508 28407 11514 28407 11514 28408 11512 28408 11510 28408 11516 28409 10986 28409 11511 28409 11519 28410 11517 28410 11516 28410 11017 28411 11013 28411 11521 28411 11523 28412 11202 28412 11521 28412 8168 28413 11509 28413 8273 28413 8273 28414 11524 28414 8274 28414 11001 28415 11525 28415 11003 28415 11258 28416 11525 28416 11000 28416 11523 28417 11013 28417 11015 28417 10996 28418 10992 28418 11304 28418 11304 28419 10992 28419 10994 28419 11528 28420 11454 28420 11455 28420 11528 28421 11455 28421 11529 28421 11533 28422 11530 28422 11535 28422 11534 28423 11533 28423 11535 28423 11455 28424 11456 28424 11529 28424 11529 28425 11537 28425 11531 28425 11530 28426 11538 28426 11535 28426 11532 28427 11454 28427 11533 28427 11533 28428 11454 28428 11528 28428 11092 28429 11447 28429 11094 28429 10908 28430 11057 28430 10902 28430 11539 28431 11541 28431 11075 28431 11075 28432 11541 28432 11090 28432 11541 28433 11542 28433 11090 28433 11074 28434 11539 28434 11075 28434 11104 28435 11101 28435 11425 28435 11425 28436 11543 28436 11104 28436 11104 28437 11543 28437 11106 28437 11104 28438 11103 28438 11101 28438 11097 28439 11094 28439 11506 28439 11524 28440 11545 28440 8274 28440 8274 28441 11545 28441 8275 28441 11546 28442 8275 28442 11545 28442 11502 28443 11492 28443 11493 28443 11548 28444 11540 28444 11047 28444 11552 28445 11553 28445 11554 28445 11371 28446 11475 28446 11372 28446 11371 28447 11505 28447 11475 28447 11371 28448 11559 28448 11505 28448 11371 28449 11560 28449 11559 28449 11371 28450 11376 28450 11560 28450 11562 28451 11560 28451 11561 28451 11565 28452 11566 28452 11564 28452 11466 28453 11501 28453 11483 28453 10896 28454 10900 28454 10918 28454 11557 28455 11567 28455 10924 28455 10924 28456 11567 28456 10920 28456 10906 28457 10914 28457 10910 28457 10916 28458 10918 28458 11552 28458 11568 28459 10916 28459 11552 28459 11568 28460 11569 28460 10916 28460 10916 28461 11569 28461 10912 28461 10916 28462 10914 28462 10918 28462 11539 28463 10912 28463 11547 28463 11332 28464 11360 28464 11572 28464 11359 28465 11332 28465 11572 28465 11358 28466 11573 28466 11357 28466 11576 28467 11531 28467 11537 28467 11577 28468 11531 28468 11578 28468 11578 28469 11579 28469 11577 28469 11572 28470 11360 28470 11580 28470 11581 28471 11582 28471 11572 28471 11583 28472 11581 28472 11584 28472 11588 28473 11585 28473 11587 28473 11588 28474 11538 28474 11590 28474 11592 28475 11337 28475 11335 28475 11574 28476 11335 28476 11336 28476 11574 28477 11592 28477 11335 28477 11574 28478 11352 28478 11592 28478 11366 28479 11363 28479 11364 28479 11593 28480 11356 28480 11566 28480 11593 28481 11354 28481 11355 28481 11593 28482 11352 28482 11354 28482 11340 28483 11362 28483 11594 28483 11488 28484 11536 28484 11440 28484 11488 28485 11537 28485 11536 28485 11537 28486 11429 28486 11495 28486 11537 28487 11495 28487 11441 28487 11575 28488 11441 28488 11438 28488 11556 28489 11554 28489 11555 28489 11595 28490 11560 28490 11369 28490 11368 28491 11597 28491 11596 28491 11599 28492 11570 28492 11547 28492 11571 28493 11598 28493 11375 28493 11542 28494 11373 28494 11475 28494 11486 28495 11475 28495 11476 28495 11486 28496 11485 28496 11542 28496 11090 28497 11485 28497 11449 28497 11600 28498 11376 28498 11375 28498 11429 28499 11431 28499 11495 28499 11537 28500 11441 28500 11575 28500 11458 28501 11500 28501 11456 28501 11456 28502 11500 28502 11594 28502 11351 28503 11601 28503 11362 28503 11500 28504 11501 28504 11594 28504 11468 28505 11504 28505 11467 28505 11548 28506 11047 28506 11603 28506 11560 28507 11565 28507 11559 28507 11581 28508 11604 28508 11605 28508 11607 28509 11606 28509 11608 28509 11613 28510 11615 28510 11610 28510 11615 28511 11589 28511 11607 28511 11611 28512 11616 28512 11612 28512 11614 28513 11612 28513 11617 28513 11621 28514 11620 28514 11622 28514 11619 28515 11620 28515 11621 28515 11626 28516 11621 28516 11623 28516 11626 28517 11619 28517 11621 28517 8139 28518 11624 28518 8102 28518 11625 28519 11623 28519 11624 28519 11619 28520 11627 28520 11617 28520 11585 28521 11588 28521 11590 28521 11351 28522 11536 28522 11601 28522 11559 28523 11564 28523 11504 28523 11504 28524 11564 28524 11467 28524 11467 28525 11564 28525 11566 28525 11332 28526 11361 28526 11360 28526 11338 28527 11594 28527 11501 28527 11630 28528 11629 28528 11631 28528 11628 28529 11636 28529 11629 28529 11632 28530 11634 28530 11637 28530 11635 28531 11636 28531 11628 28531 11641 28532 11642 28532 11640 28532 11638 28533 11640 28533 11642 28533 11643 28534 11641 28534 11644 28534 11644 28535 11645 28535 11643 28535 11648 28536 11647 28536 11649 28536 11653 28537 11639 28537 11654 28537 11654 28538 11639 28538 11651 28538 11658 28539 11660 28539 11655 28539 11662 28540 11661 28540 11663 28540 11666 28541 11665 28541 11667 28541 11645 28542 11669 28542 11643 28542 11642 28543 11677 28543 11678 28543 11642 28544 11679 28544 11638 28544 11639 28545 11638 28545 11680 28545 11639 28546 11680 28546 11652 28546 11651 28547 11639 28547 11652 28547 11682 28548 11684 28548 11683 28548 11685 28549 11684 28549 11686 28549 11686 28550 11684 28550 11687 28550 11687 28551 11689 28551 11688 28551 11688 28552 11689 28552 11690 28552 11693 28553 11691 28553 11694 28553 11691 28554 11696 28554 11695 28554 11695 28555 11696 28555 11697 28555 11698 28556 11701 28556 11699 28556 11698 28557 11702 28557 11701 28557 11703 28558 11702 28558 11698 28558 11704 28559 11705 28559 11703 28559 11704 28560 11706 28560 11705 28560 11704 28561 11707 28561 11706 28561 11709 28562 11695 28562 11697 28562 11710 28563 11692 28563 11693 28563 11692 28564 11710 28564 11711 28564 11711 28565 11710 28565 11712 28565 11713 28566 11711 28566 11712 28566 11713 28567 11715 28567 11714 28567 11716 28568 11717 28568 11718 28568 11718 28569 11717 28569 11719 28569 11719 28570 11717 28570 11720 28570 11721 28571 11722 28571 11712 28571 11726 28572 11724 28572 11725 28572 11725 28573 11728 28573 11727 28573 11727 28574 11728 28574 11729 28574 11731 28575 11729 28575 11730 28575 11731 28576 11732 28576 11729 28576 11732 28577 11731 28577 11733 28577 11699 28578 11734 28578 11733 28578 11732 28579 11734 28579 11736 28579 11656 28580 11688 28580 11657 28580 11673 28581 11649 28581 11737 28581 10989 28582 10991 28582 11297 28582 11647 28583 11738 28583 11737 28583 11673 28584 11740 28584 11671 28584 11645 28585 11673 28585 11671 28585 11671 28586 11670 28586 11669 28586 11670 28587 11665 28587 11663 28587 11736 28588 11735 28588 11741 28588 11742 28589 11736 28589 11741 28589 11742 28590 11744 28590 11743 28590 11743 28591 11744 28591 11745 28591 11746 28592 11743 28592 11745 28592 11669 28593 11663 28593 11747 28593 11677 28594 11676 28594 11748 28594 11752 28595 11659 28595 11751 28595 11661 28596 11752 28596 11663 28596 11752 28597 11661 28597 11658 28597 11752 28598 11658 28598 11659 28598 11756 28599 11748 28599 11749 28599 11757 28600 11669 28600 11747 28600 11755 28601 11669 28601 11757 28601 11759 28602 11752 28602 11751 28602 11760 28603 11759 28603 11751 28603 11758 28604 11752 28604 11761 28604 11655 28605 11762 28605 11656 28605 11681 28606 11763 28606 11666 28606 11685 28607 11686 28607 11763 28607 11666 28608 11763 28608 11764 28608 11763 28609 11683 28609 11685 28609 11765 28610 11762 28610 11655 28610 11767 28611 11656 28611 11768 28611 11690 28612 11689 28612 11769 28612 11770 28613 11708 28613 11769 28613 11705 28614 11770 28614 11702 28614 11770 28615 11706 28615 11708 28615 11667 28616 11701 28616 11702 28616 11771 28617 11667 28617 11702 28617 11772 28618 11682 28618 11668 28618 11772 28619 11684 28619 11682 28619 11769 28620 11773 28620 11774 28620 11769 28621 11689 28621 11773 28621 11690 28622 11707 28622 11775 28622 11709 28623 11777 28623 11700 28623 11709 28624 11697 28624 11777 28624 11700 28625 11777 28625 11698 28625 11778 28626 11703 28626 11698 28626 11779 28627 11707 28627 11704 28627 11779 28628 11703 28628 11778 28628 11780 28629 11691 28629 11781 28629 11781 28630 11691 28630 11690 28630 11781 28631 11690 28631 11775 28631 11710 28632 11782 28632 11721 28632 11728 28633 11784 28633 11730 28633 11783 28634 11725 28634 11723 28634 11721 28635 11782 28635 11723 28635 11786 28636 11695 28636 11709 28636 11786 28637 11709 28637 11700 28637 11693 28638 11787 28638 11782 28638 11693 28639 11788 28639 11787 28639 11788 28640 11693 28640 11694 28640 11254 28641 11789 28641 11255 28641 11252 28642 11790 28642 11254 28642 11264 28643 11255 28643 11791 28643 11791 28644 11269 28644 11267 28644 11255 28645 11789 28645 11791 28645 11242 28646 11793 28646 11250 28646 11250 28647 11793 28647 11790 28647 11073 28648 11789 28648 11254 28648 11073 28649 11254 28649 11790 28649 11790 28650 11059 28650 11073 28650 11794 28651 11257 28651 11256 28651 11277 28652 11257 28652 11794 28652 11795 28653 11274 28653 11275 28653 11796 28654 11266 28654 11270 28654 11266 28655 11796 28655 11265 28655 11796 28656 11270 28656 11268 28656 11265 28657 11796 28657 11256 28657 11074 28658 11794 28658 11256 28658 11076 28659 11794 28659 11074 28659 11797 28660 11259 28660 11258 28660 11798 28661 11282 28661 11279 28661 11261 28662 11259 28662 11798 28662 11282 28663 11286 28663 11284 28663 11800 28664 11276 28664 11273 28664 11276 28665 11800 28665 11278 28665 11797 28666 11258 28666 11278 28666 11278 28667 11800 28667 11797 28667 11077 28668 11259 28668 11797 28668 11078 28669 11259 28669 11077 28669 11801 28670 11802 28670 11283 28670 11283 28671 11285 28671 11801 28671 11295 28672 11263 28672 11803 28672 11803 28673 11804 28673 11293 28673 11287 28674 11291 28674 11804 28674 11079 28675 11802 28675 11190 28675 11185 28676 11188 28676 11801 28676 11190 28677 11802 28677 11187 28677 11187 28678 11801 28678 11188 28678 11089 28679 11801 28679 11287 28679 11185 28680 11801 28680 11089 28680 11081 28681 11082 28681 11803 28681 11084 28682 11803 28682 11082 28682 11294 28683 11806 28683 11296 28683 11292 28684 11807 28684 11294 28684 11292 28685 11289 28685 11807 28685 11807 28686 11289 28686 11805 28686 11207 28687 11808 28687 11206 28687 11806 28688 11207 28688 11263 28688 11809 28689 11209 28689 11808 28689 11808 28690 11209 28690 11206 28690 11080 28691 11806 28691 11083 28691 11083 28692 11806 28692 11807 28692 11083 28693 11807 28693 11085 28693 11091 28694 11176 28694 11808 28694 11180 28695 11809 28695 11178 28695 11178 28696 11809 28696 11176 28696 11210 28697 11810 28697 11208 28697 11214 28698 11204 28698 11811 28698 11811 28699 11812 28699 11214 28699 11205 28700 11810 28700 11177 28700 11177 28701 11810 28701 11175 28701 11181 28702 11179 28702 11212 28702 11100 28703 11218 28703 11812 28703 11095 28704 11812 28704 11811 28704 11813 28705 11814 28705 11649 28705 11814 28706 11815 28706 11648 28706 11653 28707 11817 28707 11640 28707 11816 28708 11818 28708 11644 28708 11751 28709 11753 28709 11760 28709 11819 28710 11820 28710 11779 28710 11779 28711 11820 28711 11821 28711 11824 28712 11697 28712 11776 28712 11780 28713 11824 28713 11776 28713 11778 28714 11698 28714 11826 28714 11827 28715 11785 28715 11699 28715 11827 28716 11733 28716 11828 28716 11784 28717 11829 28717 11830 28717 11787 28718 11783 28718 11782 28718 11830 28719 11828 28719 11784 28719 11784 28720 11828 28720 11733 28720 11786 28721 11833 28721 11834 28721 11834 28722 11788 28722 11786 28722 11786 28723 11788 28723 11694 28723 11765 28724 11766 28724 11835 28724 11762 28725 11836 28725 11768 28725 11765 28726 11836 28726 11762 28726 11763 28727 11837 28727 11764 28727 11838 28728 11763 28728 11839 28728 11767 28729 11763 28729 11686 28729 11767 28730 11839 28730 11763 28730 11841 28731 11771 28731 11842 28731 11844 28732 11770 28732 11769 28732 11845 28733 11846 28733 11772 28733 11687 28734 11772 28734 11773 28734 11177 28735 11093 28735 11205 28735 11205 28736 11093 28736 11203 28736 11286 28737 11798 28737 11189 28737 11189 28738 11798 28738 11191 28738 11078 28739 11798 28739 11259 28739 11799 28740 11116 28740 11117 28740 11799 28741 11117 28741 11273 28741 11273 28742 11117 28742 11118 28742 11800 28743 11118 28743 11182 28743 11800 28744 11182 28744 11077 28744 11112 28745 11799 28745 11286 28745 11186 28746 11112 28746 11286 28746 11116 28747 11799 28747 11112 28747 11262 28748 11079 28748 11081 28748 11262 28749 11081 28749 11263 28749 11073 28750 11197 28750 11791 28750 11195 28751 11193 28751 11269 28751 11124 28752 11227 28752 11121 28752 11124 28753 11129 28753 11227 28753 11793 28754 11129 28754 11166 28754 11060 28755 11059 28755 11793 28755 11120 28756 11121 28756 11792 28756 11120 28757 11241 28757 11269 28757 11120 28758 11269 28758 11193 28758 11795 28759 11115 28759 11271 28759 11183 28760 11795 28760 11794 28760 11796 28761 11198 28761 11074 28761 11256 28762 11796 28762 11074 28762 11114 28763 11268 28763 11271 28763 11806 28764 11080 28764 11207 28764 11848 28765 10964 28765 11849 28765 10968 28766 10967 28766 11850 28766 11851 28767 11850 28767 11848 28767 10962 28768 10987 28768 11853 28768 11851 28769 11853 28769 11852 28769 11851 28770 11852 28770 11850 28770 11850 28771 10967 28771 10964 28771 11849 28772 10963 28772 10952 28772 11854 28773 11855 28773 11578 28773 11590 28774 11579 28774 11860 28774 11576 28775 11575 28775 11854 28775 11573 28776 11359 28776 11572 28776 11861 28777 11573 28777 11856 28777 11861 28778 11575 28778 11573 28778 11861 28779 11858 28779 11854 28779 11856 28780 11858 28780 11861 28780 11855 28781 11860 28781 11578 28781 11590 28782 11860 28782 11862 28782 11590 28783 11862 28783 11583 28783 11583 28784 11862 28784 11863 28784 11582 28785 11863 28785 11864 28785 11866 28786 11855 28786 11867 28786 11869 28787 11582 28787 11864 28787 11873 28788 11867 28788 11859 28788 11874 28789 11859 28789 11872 28789 11875 28790 11872 28790 11868 28790 11877 28791 11864 28791 11863 28791 11878 28792 11863 28792 11870 28792 11879 28793 11870 28793 11871 28793 11881 28794 11882 28794 11865 28794 11874 28795 11872 28795 11875 28795 11875 28796 11868 28796 11876 28796 11879 28797 11871 28797 11880 28797 11880 28798 11865 28798 11882 28798 11865 28799 11866 28799 11881 28799 11881 28800 11866 28800 11873 28800 10960 28801 11885 28801 10958 28801 10958 28802 11885 28802 10954 28802 10952 28803 11876 28803 11877 28803 10952 28804 11886 28804 11876 28804 11881 28805 11853 28805 11882 28805 11882 28806 11853 28806 11851 28806 11877 28807 11848 28807 11849 28807 11876 28808 11886 28808 11875 28808 11873 28809 10962 28809 11881 28809 11880 28810 11851 28810 11879 28810 11890 28811 11891 28811 11173 28811 11892 28812 11888 28812 11890 28812 11893 28813 11889 28813 11888 28813 11894 28814 11069 28814 11895 28814 11895 28815 11896 28815 11894 28815 11895 28816 11897 28816 11896 28816 11898 28817 11896 28817 11200 28817 11899 28818 11900 28818 11891 28818 11891 28819 11900 28819 11898 28819 11896 28820 11900 28820 11901 28820 11894 28821 11901 28821 11902 28821 11898 28822 11900 28822 11896 28822 11896 28823 11901 28823 11894 28823 11894 28824 11902 28824 11887 28824 11888 28825 11902 28825 11899 28825 11891 28826 11888 28826 11899 28826 11905 28827 11908 28827 11907 28827 11906 28828 11907 28828 11909 28828 11910 28829 11911 28829 11906 28829 11910 28830 11912 28830 11911 28830 11913 28831 11912 28831 11914 28831 11914 28832 11915 28832 11913 28832 11912 28833 11916 28833 11914 28833 11914 28834 11917 28834 11915 28834 11915 28835 11917 28835 11918 28835 11920 28836 11903 28836 11921 28836 11903 28837 11920 28837 11918 28837 11918 28838 11922 28838 11915 28838 11915 28839 11922 28839 11913 28839 11927 28840 11928 28840 11929 28840 11930 28841 11927 28841 11931 28841 11932 28842 11930 28842 11931 28842 11932 28843 11925 28843 11930 28843 11925 28844 11932 28844 11926 28844 11933 28845 11924 28845 11926 28845 11924 28846 11933 28846 11934 28846 11934 28847 11936 28847 11935 28847 11934 28848 11937 28848 11936 28848 11938 28849 11929 28849 11928 28849 11928 28850 11927 28850 11930 28850 11935 28851 11936 28851 11938 28851 11924 28852 11941 28852 11942 28852 11938 28853 11941 28853 11935 28853 11924 28854 11942 28854 11925 28854 11930 28855 11943 28855 11940 28855 11928 28856 11930 28856 11940 28856 11944 28857 11945 28857 11946 28857 11947 28858 11948 28858 11949 28858 11950 28859 11952 28859 11951 28859 11944 28860 11946 28860 11954 28860 11944 28861 11954 28861 11955 28861 11957 28862 11959 28862 11958 28862 11947 28863 11949 28863 11951 28863 11951 28864 11952 28864 11945 28864 11955 28865 11961 28865 11956 28865 11962 28866 11958 28866 11959 28866 11951 28867 11963 28867 11947 28867 11958 28868 11965 28868 11966 28868 11958 28869 11966 28869 11956 28869 11944 28870 11967 28870 11945 28870 11945 28871 11967 28871 11964 28871 11968 28872 11969 28872 11904 28872 11914 28873 11971 28873 11917 28873 11969 28874 11905 28874 11904 28874 11905 28875 11969 28875 11972 28875 11974 28876 11912 28876 11910 28876 11979 28877 11978 28877 11980 28877 11981 28878 11983 28878 11984 28878 11985 28879 11984 28879 11986 28879 11981 28880 11987 28880 11988 28880 11993 28881 11992 28881 11994 28881 12000 28882 12001 28882 12002 28882 11045 28883 11050 28883 12003 28883 11997 28884 12006 28884 12007 28884 12002 28885 11970 28885 12000 28885 12003 28886 11051 28886 12011 28886 11969 28887 12011 28887 11972 28887 11974 28888 11168 28888 11912 28888 11065 28889 11061 28889 11971 28889 11917 28890 12012 28890 11970 28890 11064 28891 12012 28891 11061 28891 11064 28892 11162 28892 12012 28892 12013 28893 12014 28893 11983 28893 11998 28894 11999 28894 11980 28894 11983 28895 12014 28895 11984 28895 12015 28896 11982 28896 11981 28896 12017 28897 12018 28897 11987 28897 11987 28898 12018 28898 11988 28898 11988 28899 12019 28899 12020 28899 11978 28900 11979 28900 11976 28900 12021 28901 11995 28901 11976 28901 12022 28902 11979 28902 12024 28902 11979 28903 12020 28903 12024 28903 12033 28904 12026 28904 12025 28904 11992 28905 11993 28905 11989 28905 11989 28906 12035 28906 12037 28906 12038 28907 11990 28907 12037 28907 11907 28908 11908 28908 12011 28908 11904 28909 11970 28909 11968 28909 12000 28910 11970 28910 12013 28910 12016 28911 11982 28911 12001 28911 11983 28912 12016 28912 12013 28912 11168 28913 11971 28913 11916 28913 12039 28914 12030 28914 12035 28914 11994 28915 11992 28915 11991 28915 12007 28916 12040 28916 11999 28916 12041 28917 12040 28917 12042 28917 12043 28918 12009 28918 12001 28918 12011 28919 12005 28919 12003 28919 12011 28920 11969 28920 12005 28920 12041 28921 12042 28921 12043 28921 11994 28922 12044 28922 11996 28922 11999 28923 11997 28923 12007 28923 12000 28924 12016 28924 12001 28924 12000 28925 12013 28925 12016 28925 11982 28926 12041 28926 12043 28926 11977 28927 11997 28927 11998 28927 12029 28928 12028 28928 12027 28928 12022 28929 12045 28929 12023 28929 12045 28930 12033 28930 12032 28930 12020 28931 11979 28931 11988 28931 12045 28932 12022 28932 12024 28932 12023 28933 12031 28933 12021 28933 12015 28934 11981 28934 11999 28934 11988 28935 11999 28935 11981 28935 12036 28936 11993 28936 12039 28936 12039 28937 11993 28937 12031 28937 12046 28938 11921 28938 12047 28938 12046 28939 11920 28939 11921 28939 12047 28940 11923 28940 12048 28940 12046 28941 11922 28941 11920 28941 11975 28942 11910 28942 11909 28942 11975 28943 11909 28943 11973 28943 11919 28944 11917 28944 11970 28944 11971 28945 11914 28945 11916 28945 11927 28946 11929 28946 12049 28946 11931 28947 11927 28947 12049 28947 12052 28948 12051 28948 12053 28948 12056 28949 12009 28949 12057 28949 12057 28950 12058 28950 12059 28950 12063 28951 12062 28951 12064 28951 12067 28952 12068 28952 12069 28952 12071 28953 12072 28953 12073 28953 12074 28954 12003 28954 12005 28954 12076 28955 11990 28955 12038 28955 11994 28956 11991 28956 12077 28956 12068 28957 12082 28957 12083 28957 12084 28958 12082 28958 12064 28958 12084 28959 12064 28959 12085 28959 12086 28960 12080 28960 12072 28960 12066 28961 12087 28961 12065 28961 12088 28962 12089 28962 12090 28962 12087 28963 12091 28963 12065 28963 12089 28964 12096 28964 12097 28964 12098 28965 12097 28965 12099 28965 12097 28966 12096 28966 12101 28966 12102 28967 12101 28967 12096 28967 12102 28968 12095 28968 12101 28968 12100 28969 12103 28969 12049 28969 12104 28970 12049 28970 12103 28970 12104 28971 12051 28971 11932 28971 12104 28972 12105 28972 12051 28972 11933 28973 12105 28973 12050 28973 12105 28974 12074 28974 12050 28974 12106 28975 12050 28975 12005 28975 12010 28976 12106 28976 12004 28976 12089 28977 12102 28977 12096 28977 12089 28978 12097 28978 12098 28978 12098 28979 12107 28979 12090 28979 12109 28980 11937 28980 12106 28980 12106 28981 11939 28981 12050 28981 12110 28982 12076 28982 12111 28982 12083 28983 12078 28983 12112 28983 12069 28984 12072 28984 12070 28984 12111 28985 12081 28985 12113 28985 12077 28986 12078 28986 12114 28986 12075 28987 12061 28987 12006 28987 12085 28988 12075 28988 12084 28988 12056 28989 12090 28989 12055 28989 12055 28990 12090 28990 12107 28990 12109 28991 12106 28991 12010 28991 12058 28992 12007 28992 12059 28992 12077 28993 12084 28993 12075 28993 12081 28994 12080 28994 12086 28994 12111 28995 12079 28995 12081 28995 12082 28996 12084 28996 12083 28996 12059 28997 12061 28997 12060 28997 12108 28998 12115 28998 12094 28998 12060 28999 12115 28999 12059 28999 12115 29000 12088 29000 12057 29000 12057 29001 12059 29001 12115 29001 12072 29002 12069 29002 12086 29002 12068 29003 12083 29003 12112 29003 12082 29004 12066 29004 12064 29004 12093 29005 12094 29005 12063 29005 12062 29006 12063 29006 12060 29006 12070 29007 12072 29007 12071 29007 12063 29008 12064 29008 12065 29008 12095 29009 12108 29009 12094 29009 12066 29010 12082 29010 12087 29010 12068 29011 12067 29011 12082 29011 12082 29012 12067 29012 12087 29012 12078 29013 12077 29013 11991 29013 12117 29014 12116 29014 12119 29014 11940 29015 12116 29015 11941 29015 12116 29016 11940 29016 12119 29016 11943 29017 11942 29017 12117 29017 12118 29018 11941 29018 12116 29018 12052 29019 11926 29019 11932 29019 11929 29020 11938 29020 12107 29020 11936 29021 12107 29021 11938 29021 11934 29022 12106 29022 11937 29022 12120 29023 11954 29023 12121 29023 12121 29024 12123 29024 12120 29024 11948 29025 11950 29025 11949 29025 12128 29026 12130 29026 11950 29026 12127 29027 11960 29027 11952 29027 11953 29028 12125 29028 11946 29028 11603 29029 12133 29029 12134 29029 11548 29030 12134 29030 12135 29030 12136 29031 12135 29031 11955 29031 12120 29032 12123 29032 12136 29032 11602 29033 12136 29033 12137 29033 12136 29034 11548 29034 12135 29034 12139 29035 12140 29035 12141 29035 12139 29036 12145 29036 12144 29036 12144 29037 12145 29037 11950 29037 12144 29038 11950 29038 11948 29038 12143 29039 12144 29039 11948 29039 12149 29040 12148 29040 12150 29040 11830 29041 12154 29041 12155 29041 12158 29042 12157 29042 12159 29042 12160 29043 12159 29043 12161 29043 12160 29044 12158 29044 12159 29044 12157 29045 12163 29045 12156 29045 12152 29046 12164 29046 12153 29046 12154 29047 12165 29047 12155 29047 12154 29048 12153 29048 12165 29048 12164 29049 12166 29049 12153 29049 12153 29050 12166 29050 12165 29050 12168 29051 12167 29051 12157 29051 12157 29052 11828 29052 12168 29052 12168 29053 11828 29053 12155 29053 12170 29054 12171 29054 12172 29054 12171 29055 12169 29055 12172 29055 12172 29056 12169 29056 12159 29056 12162 29057 12173 29057 12163 29057 12156 29058 12163 29058 11827 29058 11828 29059 12156 29059 11827 29059 12173 29060 12174 29060 12163 29060 12163 29061 12174 29061 11827 29061 12175 29062 11827 29062 12174 29062 12175 29063 11826 29063 11827 29063 11826 29064 12176 29064 11841 29064 12177 29065 11841 29065 12176 29065 12177 29066 11840 29066 11841 29066 11840 29067 12178 29067 11757 29067 11757 29068 12178 29068 12179 29068 12180 29069 12181 29069 12182 29069 12182 29070 11813 29070 12180 29070 11813 29071 12183 29071 11814 29071 11815 29072 12183 29072 12184 29072 11653 29073 12186 29073 11753 29073 11753 29074 12186 29074 12187 29074 12188 29075 11767 29075 12187 29075 12188 29076 11773 29076 11767 29076 11774 29077 11780 29077 11781 29077 11781 29078 11821 29078 11774 29078 11774 29079 11821 29079 11844 29079 11843 29080 11820 29080 11819 29080 12189 29081 11788 29081 11780 29081 12192 29082 12191 29082 12137 29082 12122 29083 12192 29083 12137 29083 12127 29084 12192 29084 11960 29084 12127 29085 12190 29085 12192 29085 12190 29086 12127 29086 12193 29086 11787 29087 12193 29087 12147 29087 12151 29088 11831 29088 11832 29088 12137 29089 12191 29089 12138 29089 11548 29090 11603 29090 12134 29090 10883 29091 11603 29091 11549 29091 10882 29092 12133 29092 10883 29092 12179 29093 11813 29093 11755 29093 11816 29094 11817 29094 11756 29094 11754 29095 11817 29095 11653 29095 11753 29096 11754 29096 11653 29096 11835 29097 11761 29097 11759 29097 11836 29098 11759 29098 11760 29098 11836 29099 11760 29099 11768 29099 11827 29100 11826 29100 11825 29100 11785 29101 11827 29101 11825 29101 11834 29102 11823 29102 11824 29102 11834 29103 11824 29103 11780 29103 11830 29104 11829 29104 12154 29104 12193 29105 11787 29105 12190 29105 11845 29106 11841 29106 11837 29106 11846 29107 11838 29107 11839 29107 11847 29108 11839 29108 11767 29108 11845 29109 11838 29109 11846 29109 11847 29110 11767 29110 11773 29110 11954 29111 12120 29111 11955 29111 12122 29112 12125 29112 11953 29112 12193 29113 12127 29113 12126 29113 12193 29114 12126 29114 12147 29114 12129 29115 12195 29115 12140 29115 12196 29116 12140 29116 12195 29116 12196 29117 12134 29117 12133 29117 11955 29118 12135 29118 11961 29118 12141 29119 12196 29119 12132 29119 12132 29120 12196 29120 12133 29120 12198 29121 12201 29121 12199 29121 11963 29122 12200 29122 12199 29122 12198 29123 11967 29123 12201 29123 12201 29124 11966 29124 12199 29124 11948 29125 11947 29125 12143 29125 12142 29126 12202 29126 11962 29126 11956 29127 12203 29127 11957 29127 12129 29128 11959 29128 11957 29128 12195 29129 12129 29129 12204 29129 12197 29130 12203 29130 11961 29130 12196 29131 12195 29131 12204 29131 12203 29132 12197 29132 12204 29132 11071 29133 12205 29133 11070 29133 11893 29134 11053 29134 11199 29134 11049 29135 11048 29135 12206 29135 11173 29136 11049 29136 11890 29136 11171 29137 11173 29137 12207 29137 11200 29138 11897 29138 11170 29138 12206 29139 11048 29139 12209 29139 11048 29140 11053 29140 12209 29140 11053 29141 11892 29141 12209 29141 11889 29142 11199 29142 12210 29142 12210 29143 11070 29143 12205 29143 12211 29144 12212 29144 12213 29144 12213 29145 12214 29145 12211 29145 11900 29146 11899 29146 12212 29146 12214 29147 11902 29147 12211 29147 11902 29148 11901 29148 12211 29148 11071 29149 11887 29149 11889 29149 12205 29150 11889 29150 12210 29150 12209 29151 11892 29151 11890 29151 11200 29152 12215 29152 11898 29152 12207 29153 11173 29153 11898 29153 11171 29154 12215 29154 11200 29154 11170 29155 11895 29155 12208 29155 12208 29156 11895 29156 12217 29156 12217 29157 11067 29157 12208 29157 12216 29158 11171 29158 12207 29158 12215 29159 11171 29159 12216 29159 12103 29160 12100 29160 12218 29160 12218 29161 12097 29161 12219 29161 12172 29162 12221 29162 12170 29162 12172 29163 12222 29163 12221 29163 12172 29164 12159 29164 12222 29164 12222 29165 12159 29165 12223 29165 12223 29166 12159 29166 12157 29166 12223 29167 12157 29167 12224 29167 12226 29168 12164 29168 12219 29168 12219 29169 12164 29169 12220 29169 12146 29170 12220 29170 12148 29170 12146 29171 12218 29171 12220 29171 12146 29172 12145 29172 12103 29172 12104 29173 12145 29173 12105 29173 12105 29174 12145 29174 12139 29174 12074 29175 12139 29175 12141 29175 12105 29176 12139 29176 12074 29176 12074 29177 12131 29177 11044 29177 12170 29178 12227 29178 12228 29178 12230 29179 12228 29179 12229 29179 12230 29180 12229 29180 12231 29180 12232 29181 11297 29181 11720 29181 12232 29182 11720 29182 11717 29182 12233 29183 12232 29183 11717 29183 12234 29184 11713 29184 11712 29184 12236 29185 11722 29185 12237 29185 12236 29186 12235 29186 11722 29186 11726 29187 11727 29187 12239 29187 12240 29188 11727 29188 11729 29188 12244 29189 11743 29189 11746 29189 12247 29190 12246 29190 12248 29190 12247 29191 12248 29191 12249 29191 12243 29192 11743 29192 12244 29192 12233 29193 11713 29193 12234 29193 12254 29194 12255 29194 12256 29194 12257 29195 12258 29195 12259 29195 12261 29196 12260 29196 12262 29196 12263 29197 12262 29197 12264 29197 12265 29198 12264 29198 12266 29198 12267 29199 12268 29199 12269 29199 8247 29200 12270 29200 8246 29200 12273 29201 8248 29201 12253 29201 12274 29202 12275 29202 12276 29202 12280 29203 12283 29203 12284 29203 12277 29204 12276 29204 12286 29204 12287 29205 12286 29205 12288 29205 12290 29206 12291 29206 12292 29206 12292 29207 12293 29207 12294 29207 12295 29208 12252 29208 12251 29208 12297 29209 12286 29209 12298 29209 12297 29210 12298 29210 12299 29210 12236 29211 12299 29211 12300 29211 12293 29212 12292 29212 12291 29212 12232 29213 12251 29213 12252 29213 12235 29214 12295 29214 12234 29214 12235 29215 12300 29215 12295 29215 12279 29216 12278 29216 12301 29216 12304 29217 12303 29217 12305 29217 12307 29218 12266 29218 12264 29218 12263 29219 12265 29219 12268 29219 8245 29220 12310 29220 8244 29220 12269 29221 12313 29221 12309 29221 12313 29222 12308 29222 12309 29222 12312 29223 12309 29223 12311 29223 12296 29224 12294 29224 12314 29224 12314 29225 12294 29225 12293 29225 12318 29226 12258 29226 12256 29226 12300 29227 12294 29227 12296 29227 12305 29228 12282 29228 12281 29228 12254 29229 12320 29229 12273 29229 12273 29230 12253 29230 12254 29230 12321 29231 12320 29231 12319 29231 12322 29232 12319 29232 12257 29232 12261 29233 12257 29233 12260 29233 12316 29234 12305 29234 12303 29234 12280 29235 12284 29235 12275 29235 12285 29236 12290 29236 12292 29236 12285 29237 12292 29237 12298 29237 12299 29238 12294 29238 12300 29238 12304 29239 12302 29239 12303 29239 12304 29240 12324 29240 12302 29240 12273 29241 12320 29241 12321 29241 12319 29242 12325 29242 12321 29242 12301 29243 12323 29243 12279 29243 12286 29244 12285 29244 12298 29244 12306 29245 12302 29245 12324 29245 12268 29246 12267 29246 12322 29246 12272 29247 12321 29247 12325 29247 12286 29248 12297 29248 12288 29248 12279 29249 12274 29249 12277 29249 12268 29250 12322 29250 12263 29250 12309 29251 12271 29251 12269 29251 12326 29252 12091 29252 12087 29252 8207 29253 8180 29253 12071 29253 12091 29254 12326 29254 12327 29254 12328 29255 8181 29255 8182 29255 12329 29256 8182 29256 12092 29256 12329 29257 12328 29257 8182 29257 8189 29258 12330 29258 8184 29258 8189 29259 12332 29259 12331 29259 12332 29260 8185 29260 12333 29260 12333 29261 8185 29261 12334 29261 12334 29262 8185 29262 8190 29262 12335 29263 8186 29263 12336 29263 8186 29264 8191 29264 12336 29264 12336 29265 8191 29265 12337 29265 12337 29266 8191 29266 8188 29266 8188 29267 8187 29267 12339 29267 12330 29268 12093 29268 8184 29268 12343 29269 8187 29269 12344 29269 12345 29270 12346 29270 12347 29270 12343 29271 12344 29271 12349 29271 12344 29272 8206 29272 8205 29272 12344 29273 8205 29273 12350 29273 12352 29274 12351 29274 12354 29274 12352 29275 12341 29275 12355 29275 12353 29276 12355 29276 12348 29276 12354 29277 12222 29277 12356 29277 12356 29278 12223 29278 12225 29278 12345 29279 12342 29279 12343 29279 12343 29280 12349 29280 12346 29280 12229 29281 12227 29281 12353 29281 12223 29282 12224 29282 12225 29282 12353 29283 12348 29283 12347 29283 12229 29284 12347 29284 12231 29284 12229 29285 12353 29285 12347 29285 12347 29286 12350 29286 12231 29286 12351 29287 12227 29287 12221 29287 12231 29288 12357 29288 12230 29288 12357 29289 8203 29289 12228 29289 12357 29290 8204 29290 8203 29290 8259 29291 12246 29291 12358 29291 12358 29292 12246 29292 12359 29292 12246 29293 8258 29293 12250 29293 12249 29294 12246 29294 12250 29294 12360 29295 12250 29295 12361 29295 12247 29296 12363 29296 12245 29296 12242 29297 12243 29297 12366 29297 12241 29298 12242 29298 12367 29298 12240 29299 12241 29299 12367 29299 12360 29300 12369 29300 12368 29300 12360 29301 12361 29301 12369 29301 12364 29302 12372 29302 12370 29302 12372 29303 12373 29303 12370 29303 12365 29304 12378 29304 12377 29304 12378 29305 12363 29305 12376 29305 12369 29306 12373 29306 12368 29306 12362 29307 12374 29307 12375 29307 12370 29308 12361 29308 12364 29308 12379 29309 12278 29309 12367 29309 12381 29310 12382 29310 12378 29310 12374 29311 12373 29311 12383 29311 8255 29312 8256 29312 12372 29312 12308 29313 12384 29313 12310 29313 12384 29314 8257 29314 12310 29314 12379 29315 12377 29315 12382 29315 12381 29316 12265 29316 12266 29316 12382 29317 12278 29317 12379 29317 12382 29318 12307 29318 12278 29318 12378 29319 12382 29319 12377 29319 12374 29320 12381 29320 12378 29320 12266 29321 12382 29321 12381 29321 12308 29322 12380 29322 12384 29322 12265 29323 12381 29323 12380 29323 12374 29324 12380 29324 12381 29324 8177 29325 12387 29325 8176 29325 8176 29326 12387 29326 12388 29326 8176 29327 12388 29327 12389 29327 8175 29328 12389 29328 12390 29328 8179 29329 12391 29329 12392 29329 8178 29330 12393 29330 12394 29330 8178 29331 12394 29331 12395 29331 8177 29332 12396 29332 12386 29332 8176 29333 12389 29333 8175 29333 8179 29334 12393 29334 8178 29334 12400 29335 12402 29335 12401 29335 12406 29336 12403 29336 12407 29336 12399 29337 12398 29337 12401 29337 12404 29338 8296 29338 12405 29338 12403 29339 12401 29339 12404 29339 12404 29340 12401 29340 8295 29340 12410 29341 12407 29341 12408 29341 12408 29342 12409 29342 8298 29342 12410 29343 12408 29343 8298 29343 8299 29344 12412 29344 12413 29344 12413 29345 12412 29345 12414 29345 12418 29346 12417 29346 12419 29346 12418 29347 12419 29347 12410 29347 8298 29348 12418 29348 12410 29348 12412 29349 8299 29349 12400 29349 12226 29350 12225 29350 12167 29350 12226 29351 12167 29351 12166 29351 12225 29352 12226 29352 12101 29352 12354 29353 12338 29353 12340 29353 12092 29354 12063 29354 12328 29354 11727 29355 12240 29355 12367 29355 12239 29356 12289 29356 12238 29356 12328 29357 12091 29357 12327 29357 12334 29358 12335 29358 12333 29358 12332 29359 12331 29359 12330 29359 12095 29360 12331 29360 12332 29360 12095 29361 12332 29361 12333 29361 12333 29362 12101 29362 12095 29362 12338 29363 12421 29363 12337 29363 12397 29364 12406 29364 12417 29364 12420 29365 12398 29365 12397 29365 12396 29366 12395 29366 12423 29366 12423 29367 12395 29367 12424 29367 12425 29368 12423 29368 12424 29368 12423 29369 12425 29369 12422 29369 12422 29370 12425 29370 12426 29370 12390 29371 12433 29371 12434 29371 12390 29372 12389 29372 12433 29372 12432 29373 12389 29373 12388 29373 12429 29374 12388 29374 12387 29374 12427 29375 12387 29375 12385 29375 12435 29376 12385 29376 12386 29376 12422 29377 12435 29377 12386 29377 12422 29378 12426 29378 12435 29378 12395 29379 12394 29379 12424 29379 12424 29380 12394 29380 12436 29380 12437 29381 12436 29381 12438 29381 12393 29382 12392 29382 12438 29382 12438 29383 12392 29383 12439 29383 12437 29384 12438 29384 12439 29384 12439 29385 12391 29385 12434 29385 12440 29386 12434 29386 12431 29386 12432 29387 12388 29387 12429 29387 12430 29388 12432 29388 12429 29388 12429 29389 12387 29389 12427 29389 12437 29390 12440 29390 12425 29390 12431 29391 12430 29391 12426 29391 12428 29392 12426 29392 12430 29392 11172 29393 12011 29393 11051 29393 11172 29394 11065 29394 11168 29394 11300 29395 11302 29395 11299 29395 11305 29396 11302 29396 12443 29396 12448 29397 12450 29397 12451 29397 12452 29398 12451 29398 12453 29398 12460 29399 12461 29399 12462 29399 12463 29400 12462 29400 12464 29400 12467 29401 12468 29401 12469 29401 12468 29402 12467 29402 12457 29402 12476 29403 12475 29403 12477 29403 12478 29404 12479 29404 12480 29404 8251 29405 8252 29405 12481 29405 12481 29406 8252 29406 12464 29406 12478 29407 12464 29407 12462 29407 12483 29408 12461 29408 12458 29408 12484 29409 12456 29409 12455 29409 12473 29410 12455 29410 12485 29410 12458 29411 12476 29411 12483 29411 12317 29412 12258 29412 12475 29412 12488 29413 12477 29413 12318 29413 8250 29414 12489 29414 8249 29414 12253 29415 12489 29415 12255 29415 8253 29416 12465 29416 12463 29416 12464 29417 8253 29417 12463 29417 12466 29418 12469 29418 12490 29418 12490 29419 12469 29419 12468 29419 12467 29420 12491 29420 12457 29420 12456 29421 12457 29421 12454 29421 12457 29422 12491 29422 12454 29422 12453 29423 12493 29423 12452 29423 12447 29424 12495 29424 12445 29424 12448 29425 12499 29425 12500 29425 12499 29426 12501 29426 12495 29426 11245 29427 11247 29427 12497 29427 12443 29428 11302 29428 12442 29428 11299 29429 12444 29429 11302 29429 12444 29430 11299 29430 12252 29430 12258 29431 12318 29431 12475 29431 12446 29432 12315 29432 12486 29432 12447 29433 12446 29433 12486 29433 12488 29434 12482 29434 12483 29434 12476 29435 12474 29435 12475 29435 12478 29436 12480 29436 12481 29436 12473 29437 12484 29437 12455 29437 12476 29438 12458 29438 12487 29438 12484 29439 12473 29439 12474 29439 12317 29440 12474 29440 12473 29440 12473 29441 12485 29441 12450 29441 12471 29442 12472 29442 12470 29442 12453 29443 12451 29443 12485 29443 12444 29444 12296 29444 12442 29444 12293 29445 12496 29445 12314 29445 12314 29446 12496 29446 12502 29446 12470 29447 12472 29447 12449 29447 12255 29448 12479 29448 12318 29448 12483 29449 12482 29449 12461 29449 12458 29450 12461 29450 12459 29450 12450 29451 12485 29451 12451 29451 12452 29452 12448 29452 12451 29452 12448 29453 12500 29453 12449 29453 12500 29454 12447 29454 12449 29454 12446 29455 12445 29455 12496 29455 12495 29456 12441 29456 12445 29456 12495 29457 12501 29457 12441 29457 12465 29458 12466 29458 12463 29458 12497 29459 12445 29459 12441 29459 12315 29460 12470 29460 12486 29460 12470 29461 12315 29461 12283 29461 12503 29462 12020 29462 12504 29462 12503 29463 12045 29463 12024 29463 12033 29464 8217 29464 12026 29464 12026 29465 8217 29465 8216 29465 12509 29466 8226 29466 8225 29466 11986 29467 8224 29467 8223 29467 12511 29468 11986 29468 8223 29468 11985 29469 8222 29469 12512 29469 12513 29470 8222 29470 8221 29470 12017 29471 8221 29471 8220 29471 12513 29472 8221 29472 12017 29472 8219 29473 12018 29473 8220 29473 8219 29474 12019 29474 12018 29474 8219 29475 12514 29475 12019 29475 12514 29476 8218 29476 12515 29476 12515 29477 8218 29477 12503 29477 12504 29478 12515 29478 12503 29478 8218 29479 8217 29479 12503 29479 12017 29480 8220 29480 12018 29480 8229 29481 8228 29481 12520 29481 12520 29482 12516 29482 12521 29482 8230 29483 12520 29483 12522 29483 12522 29484 12521 29484 12523 29484 12525 29485 12518 29485 12526 29485 12527 29486 12519 29486 12528 29486 12529 29487 12528 29487 12530 29487 12531 29488 11138 29488 12532 29488 11138 29489 12531 29489 11140 29489 12524 29490 12523 29490 12516 29490 12526 29491 12518 29491 12527 29491 12524 29492 11159 29492 12523 29492 12532 29493 11139 29493 12530 29493 12532 29494 11138 29494 11139 29494 11159 29495 8230 29495 12522 29495 11139 29496 11150 29496 12529 29496 12524 29497 11157 29497 11159 29497 11159 29498 11158 29498 8231 29498 11313 29499 8285 29499 8284 29499 12536 29500 11234 29500 12537 29500 11318 29501 12538 29501 12539 29501 11318 29502 11317 29502 12538 29502 12540 29503 11317 29503 11315 29503 12540 29504 12538 29504 11317 29504 12535 29505 11236 29505 12536 29505 11234 29506 11232 29506 12537 29506 11315 29507 12534 29507 12540 29507 8285 29508 11318 29508 12542 29508 8285 29509 12542 29509 8286 29509 12543 29510 12542 29510 12539 29510 12538 29511 12544 29511 12539 29511 12545 29512 12546 29512 12547 29512 12538 29513 12546 29513 12544 29513 12538 29514 12547 29514 12546 29514 12546 29515 12548 29515 12544 29515 12543 29516 12539 29516 12544 29516 12548 29517 12543 29517 12544 29517 12547 29518 12540 29518 12549 29518 12545 29519 12549 29519 12550 29519 12545 29520 12547 29520 12549 29520 12552 29521 12535 29521 12541 29521 12534 29522 12535 29522 12553 29522 12553 29523 12535 29523 12552 29523 12541 29524 12536 29524 12554 29524 12534 29525 12553 29525 12551 29525 12549 29526 12540 29526 12534 29526 12555 29527 12545 29527 12550 29527 12501 29528 12554 29528 12537 29528 12555 29529 12469 29529 12558 29529 12556 29530 12558 29530 8254 29530 8287 29531 12548 29531 12556 29531 12558 29532 12556 29532 12555 29532 12545 29533 12555 29533 12556 29533 12491 29534 12557 29534 12492 29534 12559 29535 8174 29535 12560 29535 12559 29536 8173 29536 8174 29536 12559 29537 12561 29537 8173 29537 8172 29538 12562 29538 12563 29538 8172 29539 12563 29539 12564 29539 8171 29540 12564 29540 12565 29540 8170 29541 12566 29541 12567 29541 8170 29542 12567 29542 12568 29542 8169 29543 12569 29543 12570 29543 8170 29544 12568 29544 8169 29544 12571 29545 12572 29545 12573 29545 12575 29546 12576 29546 12574 29546 12579 29547 12576 29547 12575 29547 12579 29548 12577 29548 12576 29548 12571 29549 12573 29549 12580 29549 12580 29550 12573 29550 12578 29550 8290 29551 12580 29551 8289 29551 12578 29552 12581 29552 8289 29552 12581 29553 8288 29553 8289 29553 12576 29554 12573 29554 12574 29554 12578 29555 12577 29555 12582 29555 12578 29556 12582 29556 12581 29556 12582 29557 12583 29557 8293 29557 12585 29558 12586 29558 12587 29558 12589 29559 12588 29559 12590 29559 12591 29560 12590 29560 12592 29560 12584 29561 12593 29561 12583 29561 12587 29562 12588 29562 12589 29562 12586 29563 12572 29563 8292 29563 12586 29564 12574 29564 12572 29564 12586 29565 12585 29565 12574 29565 12572 29566 12571 29566 8292 29566 12571 29567 8291 29567 8292 29567 11162 29568 11127 29568 11984 29568 11984 29569 11127 29569 11140 29569 11984 29570 11140 29570 12531 29570 11140 29571 11127 29571 11126 29571 12509 29572 11986 29572 11984 29572 12509 29573 12531 29573 12508 29573 12531 29574 12509 29574 11984 29574 12515 29575 12504 29575 12020 29575 12441 29576 12501 29576 12537 29576 12554 29577 12536 29577 12537 29577 12537 29578 11226 29578 11229 29578 12537 29579 11229 29579 11230 29579 11230 29580 11244 29580 12441 29580 11318 29581 8285 29581 11316 29581 11986 29582 12509 29582 12510 29582 12508 29583 12532 29583 12506 29583 12512 29584 12513 29584 11987 29584 11986 29585 12511 29585 11985 29585 12513 29586 12017 29586 11987 29586 12585 29587 12575 29587 12574 29587 12587 29588 12591 29588 12585 29588 12591 29589 12587 29589 12589 29589 12570 29590 12595 29590 12594 29590 12570 29591 12569 29591 12595 29591 12595 29592 12569 29592 12596 29592 12597 29593 12596 29593 12598 29593 12597 29594 12595 29594 12596 29594 12594 29595 12597 29595 12599 29595 12600 29596 12602 29596 12601 29596 12600 29597 12603 29597 12602 29597 12605 29598 12606 29598 12604 29598 12564 29599 12606 29599 12607 29599 12564 29600 12563 29600 12606 29600 12604 29601 12563 29601 12562 29601 12602 29602 12561 29602 12559 29602 12594 29603 12601 29603 12560 29603 12594 29604 12599 29604 12601 29604 12569 29605 12568 29605 12596 29605 12596 29606 12568 29606 12608 29606 12598 29607 12596 29607 12608 29607 12608 29608 12567 29608 12609 29608 12610 29609 12598 29609 12608 29609 12567 29610 12566 29610 12609 29610 12609 29611 12566 29611 12611 29611 12610 29612 12611 29612 12612 29612 12610 29613 12609 29613 12611 29613 12604 29614 12562 29614 12603 29614 12600 29615 12604 29615 12603 29615 12595 29616 12597 29616 12594 29616 12605 29617 12612 29617 12607 29617 12597 29618 12598 29618 12599 29618 12612 29619 12600 29619 12599 29619 11379 29620 11111 29620 12613 29620 12615 29621 12613 29621 12614 29621 12615 29622 12617 29622 12613 29622 12613 29623 12617 29623 11379 29623 12618 29624 11107 29624 12619 29624 8238 29625 12618 29625 12619 29625 11107 29626 11105 29626 12619 29626 8238 29627 12619 29627 8239 29627 12620 29628 12616 29628 12614 29628 8236 29629 12622 29629 12617 29629 11161 29630 12623 29630 12625 29630 11161 29631 11387 29631 12623 29631 12624 29632 12626 29632 12625 29632 12628 29633 12631 29633 12629 29633 12628 29634 12632 29634 12631 29634 12631 29635 12632 29635 12633 29635 11151 29636 11149 29636 12631 29636 12631 29637 11149 29637 12629 29637 12629 29638 11149 29638 11148 29638 12627 29639 12630 29639 12629 29639 12627 29640 12626 29640 12630 29640 12635 29641 8232 29641 8231 29641 11156 29642 11154 29642 12635 29642 11154 29643 12634 29643 12635 29643 12622 29644 11385 29644 11381 29644 11142 29645 11143 29645 11385 29645 11385 29646 11143 29646 11381 29646 12618 29647 12620 29647 11110 29647 12636 29648 8203 29648 12358 29648 12636 29649 8202 29649 8203 29649 12636 29650 8261 29650 8202 29650 12638 29651 8261 29651 8262 29651 8263 29652 12640 29652 12639 29652 12640 29653 12641 29653 12642 29653 8198 29654 8267 29654 8197 29654 12646 29655 8267 29655 12647 29655 12642 29656 12641 29656 12643 29656 8197 29657 8267 29657 12646 29657 12648 29658 8269 29658 8195 29658 8194 29659 8269 29659 8270 29659 8271 29660 8193 29660 8194 29660 8192 29661 8272 29661 8129 29661 8128 29662 8129 29662 12649 29662 12651 29663 12649 29663 12652 29663 12651 29664 12652 29664 12653 29664 12650 29665 12649 29665 12651 29665 12655 29666 8130 29666 8126 29666 8099 29667 8119 29667 8120 29667 8100 29668 8104 29668 8105 29668 8100 29669 8108 29669 8097 29669 8097 29670 8110 29670 8111 29670 8119 29671 8099 29671 8114 29671 8116 29672 8130 29672 8115 29672 8115 29673 8130 29673 8131 29673 8165 53 8139 53 8102 53 8152 29674 8166 29674 8167 29674 8151 53 8167 53 8163 53 8135 29675 8142 29675 8143 29675 8135 29676 8143 29676 8144 29676 8136 29677 8145 29677 8146 29677 8134 29678 8149 29678 8150 29678 8167 53 8168 53 8163 53 8243 29679 8168 29679 8242 29679 8239 29680 11394 29680 8238 29680 12616 29681 11393 29681 8279 29681 12615 29682 8279 29682 11399 29682 12617 29683 11399 29683 11401 29683 12624 29684 11407 29684 8281 29684 11421 53 12630 53 11420 53 11421 53 11422 53 12628 53 12628 53 11422 53 12632 53 8232 29685 12633 29685 11417 29685 12616 53 8279 53 12615 53 12615 53 11399 53 12617 53 12624 29686 8281 29686 12626 29686 12626 29687 8282 29687 12630 29687 12632 29688 11416 29688 12633 29688 8231 29689 8284 29689 8230 29689 8285 29690 8229 29690 8230 29690 8171 29691 8293 29691 12592 29691 8172 29692 12592 29692 12590 29692 12588 29693 8292 29693 8172 29693 8174 29694 8219 29694 8220 29694 12581 29695 8286 29695 8288 29695 8289 29696 8287 29696 8254 29696 8289 29697 8254 29697 8290 29697 8253 53 12027 53 8216 53 12037 29698 8250 29698 8249 29698 12038 53 12037 53 8249 53 12029 53 8251 53 12034 53 12076 29699 8248 29699 12079 29699 12079 29700 8248 29700 8247 29700 12080 29701 8247 29701 8246 29701 8294 53 8180 53 8207 53 8294 53 8299 53 8180 53 12079 29702 8247 29702 12080 29702 8295 29703 8257 29703 8296 29703 12409 29704 8255 29704 8206 29704 8175 29705 8188 29705 8191 29705 8205 29706 8259 29706 8204 29706 8203 29707 8259 29707 12358 29707 8292 53 8291 53 8217 53 8174 29708 8173 29708 8218 29708 8171 29709 8170 29709 8226 29709 8177 29710 8176 29710 8190 29710 12418 29711 8175 29711 8179 29711 12416 29712 8179 29712 12413 29712 8299 29713 8179 29713 8178 29713 8151 29714 8152 29714 8167 29714 8162 29715 8157 29715 8139 29715 8139 53 8157 53 8138 53 8103 29716 8125 29716 8102 29716 8100 29717 8101 29717 8104 29717 8099 29718 8098 29718 8113 29718 11665 29719 12657 29719 11701 29719 12658 29720 11740 29720 11672 29720 12658 29721 11671 29721 11740 29721 11665 29722 11671 29722 12660 29722 11742 29723 11741 29723 12661 29723 11671 29724 11670 29724 12660 29724 8261 29725 12663 29725 12664 29725 8261 29726 12664 29726 12665 29726 8263 29727 8262 29727 12666 29727 11745 29728 12663 29728 12359 29728 11745 29729 11744 29729 12663 29729 12665 29730 12667 29730 12666 29730 11744 29731 11742 29731 12668 29731 12668 29732 11742 29732 12661 29732 12667 29733 12661 29733 12669 29733 12666 29734 12669 29734 12670 29734 12666 29735 12670 29735 12671 29735 12669 29736 11741 29736 11735 29736 12662 29737 11701 29737 12673 29737 12673 29738 11701 29738 12674 29738 12676 29739 12675 29739 8266 29739 12676 29740 12644 29740 12677 29740 11735 29741 12672 29741 12669 29741 12661 29742 11741 29742 12669 29742 12671 29743 12678 29743 12677 29743 11701 29744 12657 29744 12674 29744 8267 29745 8266 29745 12682 29745 12675 29746 12680 29746 12682 29746 8266 29747 12675 29747 12682 29747 11672 29748 8269 29748 12681 29748 8267 29749 12683 29749 12647 29749 12644 29750 12641 29750 12677 29750 12358 29751 12359 29751 12663 29751 12678 29752 12671 29752 12670 29752 12667 29753 12668 29753 12661 29753 12683 29754 12660 29754 12658 29754 12681 29755 12683 29755 12658 29755 12672 29756 12673 29756 12677 29756 12670 29757 12669 29757 12679 29757 12665 29758 12668 29758 12667 29758 8203 29759 12684 29759 12170 29759 12685 29760 12640 29760 12686 29760 12687 29761 12686 29761 12688 29761 12162 29762 12688 29762 12173 29762 12162 29763 12687 29763 12688 29763 12162 29764 12160 29764 12687 29764 12687 29765 12160 29765 12161 29765 12689 29766 12161 29766 12169 29766 12690 29767 12169 29767 12171 29767 12171 29768 12170 29768 12691 29768 12691 29769 12170 29769 12684 29769 12690 29770 12684 29770 12637 29770 12638 29771 12690 29771 12637 29771 12684 29772 8202 29772 12637 29772 12173 29773 12693 29773 12174 29773 12173 29774 12688 29774 12693 29774 12642 29775 12643 29775 12692 29775 12174 29776 12695 29776 12175 29776 12174 29777 12693 29777 12695 29777 12694 29778 12645 29778 12696 29778 12695 29779 12696 29779 12697 29779 12176 29780 12697 29780 12177 29780 12176 29781 12695 29781 12697 29781 12176 29782 12175 29782 12695 29782 12645 29783 8198 29783 12696 29783 12696 29784 8198 29784 12698 29784 12179 29785 12699 29785 12701 29785 12179 29786 12178 29786 12699 29786 12700 29787 12646 29787 12702 29787 12179 29788 12702 29788 12180 29788 12179 29789 12701 29789 12702 29789 8195 29790 12180 29790 12702 29790 12692 29791 12688 29791 12686 29791 12694 29792 12693 29792 12692 29792 12699 29793 12697 29793 12696 29793 12703 29794 8195 29794 8194 29794 12181 29795 12180 29795 8195 29795 12181 29796 12703 29796 12182 29796 12184 29797 12705 29797 12706 29797 12705 29798 12704 29798 12706 29798 12704 29799 12707 29799 12706 29799 12183 29800 11813 29800 12182 29800 12708 29801 12709 29801 12706 29801 11565 29802 12710 29802 11566 29802 11565 29803 11595 29803 12186 29803 12185 29804 12710 29804 12186 29804 11599 29805 12188 29805 11596 29805 11780 29806 11547 29806 12189 29806 11595 29807 11596 29807 12186 29807 11527 29808 11497 29808 11490 29808 11527 29809 11490 29809 11491 29809 8240 29810 12621 29810 11543 29810 11543 29811 12621 29811 11106 29811 11105 29812 11106 29812 12621 29812 12711 29813 12713 29813 8136 29813 8137 29814 12716 29814 12717 29814 8137 29815 12718 29815 12719 29815 8136 29816 8134 29816 12712 29816 8137 29817 12719 29817 8133 29817 8152 29818 8151 29818 12723 29818 12724 29819 12723 29819 12725 29819 12726 29820 8152 29820 12724 29820 12724 29821 8152 29821 12723 29821 12725 29822 12727 29822 12724 29822 8164 29823 12726 29823 8162 29823 8155 29824 8161 29824 12729 29824 12730 29825 8161 29825 8160 29825 12731 29826 12730 29826 8160 29826 8160 29827 8158 29827 12732 29827 11624 29828 12733 29828 8127 29828 12734 29829 12733 29829 12735 29829 12736 29830 12734 29830 12735 29830 12737 29831 12738 29831 12739 29831 12739 29832 12738 29832 8115 29832 8127 29833 12739 29833 8115 29833 12739 29834 12736 29834 12737 29834 8124 29835 8123 29835 12735 29835 12735 29836 8123 29836 12741 29836 12741 29837 8123 29837 8122 29837 12742 29838 12741 29838 8122 29838 12743 29839 8120 29839 12740 29839 12740 29840 8120 29840 8119 29840 12735 29841 12733 29841 8124 29841 12745 29842 8097 29842 12746 29842 12747 29843 8097 29843 8098 29843 12748 29844 8098 29844 8099 29844 12749 29845 8099 29845 8101 29845 12744 29846 12751 29846 8100 29846 12746 29847 8097 29847 12747 29847 12752 29848 8098 29848 12748 29848 12748 29849 8099 29849 12753 29849 12753 29850 8099 29850 12754 29850 12754 29851 8099 29851 12749 29851 12750 29852 8100 29852 12751 29852 11506 29853 11544 29853 11428 29853 8241 29854 11428 29854 11544 29854 8241 29855 11426 29855 11428 29855 8241 29856 8240 29856 11426 29856 11489 29857 11490 29857 8243 29857 8242 29858 11489 29858 8243 29858 8242 29859 11494 29859 11489 29859 11496 29860 11490 29860 11497 29860 8163 29861 11532 29861 8140 29861 11534 29862 11535 29862 12756 29862 8140 29863 12756 29863 8141 29863 8142 29864 12757 29864 12758 29864 8143 29865 12758 29865 12759 29865 8145 29866 12760 29866 12761 29866 12762 29867 8145 29867 12761 29867 8146 29868 12763 29868 8147 29868 8147 29869 12763 29869 12764 29869 8147 29870 12764 29870 8148 29870 8149 29871 11614 29871 8150 29871 8138 29872 11623 29872 11625 29872 8139 29873 8138 29873 11625 29873 8138 29874 12766 29874 11627 29874 11627 29875 12766 29875 11614 29875 8103 29876 11618 29876 12767 29876 8103 29877 11620 29877 11618 29877 8103 29878 11622 29878 11620 29878 8103 29879 11624 29879 11622 29879 8103 29880 8102 29880 11624 29880 12767 29881 11618 29881 11616 29881 12768 29882 8113 29882 12769 29882 12770 29883 8112 29883 8111 29883 12771 29884 8111 29884 8110 29884 12773 29885 8109 29885 8108 29885 12769 29886 8112 29886 12770 29886 12771 29887 8110 29887 12772 29887 12772 29888 8109 29888 12773 29888 12775 29889 8107 29889 8106 29889 12776 29890 8106 29890 8105 29890 12777 29891 12776 29891 8105 29891 12767 29892 8104 29892 8103 29892 8126 29893 8114 29893 12778 29893 12778 29894 8114 29894 12768 29894 12778 29895 12768 29895 12779 29895 12781 29896 12782 29896 12783 29896 12782 29897 12709 29897 12708 29897 8128 29898 12650 29898 12784 29898 12785 29899 12786 29899 12651 29899 12785 29900 12651 29900 12656 29900 11631 29901 12651 29901 11633 29901 11636 29902 12788 29902 12787 29902 12789 29903 11634 29903 12786 29903 12786 29904 11634 29904 11633 29904 11633 29905 12651 29905 12786 29905 11629 29906 11636 29906 12787 29906 12707 29907 8192 29907 12706 29907 12708 29908 8192 29908 8128 29908 12708 29909 12706 29909 8192 29909 12707 29910 12704 29910 8193 29910 12703 29911 8193 29911 12704 29911 12703 29912 8194 29912 8193 29912 12791 29913 8270 29913 11672 29913 12791 29914 12792 29914 8270 29914 8271 29915 12792 29915 12793 29915 8270 29916 12792 29916 8271 29916 8129 29917 8272 29917 12794 29917 8271 29918 12793 29918 8272 29918 12797 29919 8130 29919 12655 29919 12795 29920 12799 29920 12796 29920 12800 29921 12801 29921 12799 29921 12803 29922 11628 29922 12649 29922 11628 29923 12803 29923 11635 29923 11635 29924 12804 29924 11637 29924 11637 29925 12804 29925 12805 29925 11637 29926 12805 29926 11632 29926 11628 29927 11630 29927 12649 29927 12649 29928 11630 29928 12652 29928 12797 29929 12808 29929 12809 29929 12797 29930 12796 29930 12808 29930 10969 29931 12810 29931 10966 29931 11039 29932 10982 29932 10979 29932 12811 29933 10981 29933 11036 29933 12811 29934 11035 29934 8131 29934 12811 29935 8131 29935 8130 29935 10979 29936 10981 29936 12811 29936 11035 29937 8132 29937 8131 29937 12811 29938 12797 29938 12809 29938 10966 29939 12810 29939 12812 29939 12812 29940 12810 29940 12808 29940 11039 29941 12808 29941 12810 29941 8275 29942 11546 29942 12813 29942 11220 29943 12813 29943 11221 29943 12814 29944 11545 29944 11524 29944 11526 29945 12815 29945 11522 29945 11217 29946 12814 29946 11526 29946 12815 29947 11524 29947 11522 29947 12814 29948 11524 29948 12815 29948 11217 29949 11219 29949 12814 29949 12815 29950 11526 29950 12814 29950 11680 29951 11657 29951 12816 29951 11680 29952 11638 29952 11657 29952 10992 29953 11716 29953 11718 29953 11692 29954 11006 29954 11005 29954 11688 29955 11005 29955 11004 29955 11692 29956 11005 29956 11688 29956 11711 29957 11714 29957 10992 29957 10992 29958 11718 29958 11719 29958 11657 29959 11688 29959 12816 29959 11010 29960 11012 29960 11680 29960 12818 29961 12819 29961 11680 29961 12820 29962 12817 29962 12818 29962 12794 29963 12793 29963 12817 29963 12792 29964 12791 29964 11674 29964 11675 29965 11674 29965 12791 29965 12793 29966 12792 29966 12822 29966 12822 29967 12792 29967 11674 29967 12822 29968 11737 29968 11738 29968 12710 29969 12824 29969 11592 29969 11593 29970 11566 29970 12710 29970 12825 29971 12709 29971 12782 29971 12825 29972 12782 29972 12824 29972 11581 29973 11591 29973 12823 29973 12824 29974 11591 29974 11592 29974 12710 29975 12709 29975 12825 29975 12782 29976 12778 29976 12824 29976 12723 29977 12729 29977 12725 29977 12727 29978 12725 29978 12728 29978 12725 29979 12729 29979 12730 29979 12725 29980 12732 29980 12728 29980 12742 29981 12743 29981 12737 29981 12737 29982 12743 29982 12740 29982 12826 29983 11588 29983 12827 29983 11538 29984 11588 29984 12826 29984 11613 29985 12764 29985 11615 29985 12764 29986 11613 29986 12765 29986 12764 29987 12763 29987 11615 29987 11615 29988 12763 29988 12829 29988 11588 29989 12761 29989 12760 29989 11588 29990 12760 29990 12828 29990 12826 29991 12758 29991 12757 29991 12757 29992 12756 29992 11538 29992 11615 29993 12829 29993 11589 29993 12823 29994 12779 29994 11604 29994 11586 29995 11608 29995 11606 29995 12779 29996 12768 29996 11604 29996 11604 29997 12768 29997 12769 29997 11605 29998 12771 29998 11584 29998 11584 29999 12772 29999 11586 29999 11586 30000 12772 30000 12773 30000 11606 30001 12774 30001 11608 30001 12776 30002 11608 30002 12775 30002 12776 30003 11611 30003 11609 30003 12776 30004 12777 30004 11611 30004 11611 30005 12777 30005 11616 30005 12783 30006 12831 30006 12832 30006 12783 30007 12832 30007 12833 30007 12780 30008 12835 30008 12785 30008 12834 30009 12833 30009 12832 30009 12781 30010 12835 30010 12780 30010 12789 30011 12831 30011 12788 30011 11675 30012 12791 30012 11672 30012 12795 30013 12798 30013 12807 30013 12837 30014 12838 30014 12839 30014 12839 30015 12838 30015 12799 30015 12839 30016 12795 30016 12836 30016 12836 30017 12837 30017 12839 30017 12795 30018 12807 30018 12836 30018 12803 30019 12800 30019 12838 30019 12812 30020 12842 30020 12840 30020 12843 30021 12842 30021 12844 30021 12844 30022 12820 30022 12845 30022 12843 30023 12846 30023 12840 30023 12812 30024 12840 30024 10965 30024 12844 30025 12842 30025 12796 30025 12808 30026 12796 30026 12842 30026 12845 30027 12818 30027 12846 30027 10951 30028 10953 30028 12840 30028 12802 30029 12800 30029 12803 30029 12805 30030 12804 30030 12837 30030 12805 30031 12837 30031 12836 30031 12803 30032 12838 30032 12804 30032 12805 30033 12836 30033 12806 30033 12712 30034 12847 30034 12711 30034 12712 30035 12722 30035 12848 30035 12848 30036 12722 30036 12849 30036 12849 30037 12722 30037 12721 30037 12849 30038 12720 30038 12850 30038 12714 30039 12851 30039 12852 30039 12716 30040 12852 30040 12853 30040 12853 30041 12717 30041 12716 30041 12717 30042 12854 30042 12718 30042 12850 30043 12719 30043 12718 30043 12714 30044 12852 30044 12715 30044 12715 30045 12852 30045 12716 30045 12851 30046 12711 30046 12847 30046 12744 30047 12856 30047 12855 30047 12856 30048 12745 30048 12746 30048 12858 30049 12857 30049 12752 30049 12858 30050 12748 30050 12859 30050 12753 30051 12754 30051 12860 30051 12862 30052 12751 30052 12855 30052 12847 30053 12848 30053 12853 30053 12853 30054 12852 30054 12847 30054 12847 30055 12852 30055 12851 30055 12862 30056 12860 30056 12861 30056 12855 30057 12858 30057 12862 30057 11554 30058 12863 30058 11552 30058 11569 30059 11568 30059 12864 30059 12866 30060 11558 30060 12865 30060 12865 30061 11558 30061 11569 30061 11554 30062 12866 30062 12863 30062 12867 30063 11369 30063 12868 30063 11597 30064 12869 30064 11563 30064 11367 30065 12868 30065 12869 30065 12871 30066 11373 30066 11375 30066 11371 30067 11370 30067 12870 30067 11374 30068 12870 30068 11370 30068 12871 30069 11374 30069 11370 30069 12872 30070 12873 30070 11557 30070 11551 30071 11567 30071 12874 30071 11550 30072 11551 30072 12874 30072 12875 30073 11553 30073 11550 30073 11557 30074 11555 30074 12872 30074 8480 30075 12877 30075 10006 30075 12878 30076 12876 30076 12879 30076 12885 30077 12884 30077 12886 30077 12885 30078 12886 30078 12887 30078 12888 30079 12887 30079 12889 30079 12890 30080 12889 30080 12891 30080 12883 30081 12884 30081 12885 30081 12888 30082 12889 30082 12890 30082 12890 30083 12891 30083 12892 30083 12877 30084 12878 30084 12879 30084 12876 30085 10001 30085 12893 30085 12877 30086 10004 30086 10006 30086 12877 30087 10009 30087 12876 30087 8480 30088 8339 30088 8341 30088 8480 30089 8341 30089 8481 30089 8477 30090 8478 30090 8335 30090 8347 30091 8478 30091 8484 30091 8483 30092 8347 30092 8484 30092 10006 30093 8479 30093 8480 30093 8483 30094 10009 30094 8344 30094 10001 30095 10009 30095 8483 30095 10001 30096 8484 30096 10004 30096 10006 30097 10004 30097 8477 30097 8483 30098 8344 30098 8346 30098 8346 30099 8347 30099 8483 30099 8347 30100 8335 30100 8478 30100 12885 30101 12878 30101 12883 30101 12883 30102 12878 30102 12879 30102 12882 30103 12883 30103 12879 30103 12892 30104 12882 30104 12879 30104 12888 30105 12878 30105 12885 30105 8347 30106 12880 30106 8335 30106 12891 30107 8335 30107 12880 30107 12887 30108 8341 30108 8339 30108 8344 30109 8341 30109 12886 30109 8338 30110 12891 30110 8339 30110 10031 30111 12894 30111 10030 30111 10028 30112 12895 30112 10033 30112 12902 30113 12901 30113 12903 30113 12905 30114 12904 30114 12906 30114 12907 30115 12906 30115 12908 30115 12909 30116 12908 30116 12898 30116 12897 30117 12909 30117 12898 30117 12897 30118 12899 30118 12900 30118 12900 30119 12901 30119 12902 30119 12905 30120 12906 30120 12907 30120 12907 30121 12908 30121 12909 30121 12894 30122 10031 30122 10032 30122 12911 30123 12895 30123 12894 30123 12910 30124 12912 30124 12911 30124 12911 30125 12912 30125 12913 30125 12913 30126 12895 30126 12911 30126 10032 30127 8316 30127 8474 30127 8474 30128 10031 30128 8316 30128 10031 30129 8474 30129 10032 30129 10032 30130 8475 30130 10033 30130 8475 30131 8476 30131 10028 30131 8471 30132 8476 30132 8332 30132 10029 30133 10028 30133 8476 30133 10031 30134 8472 30134 8473 30134 10030 30135 8472 30135 10031 30135 10030 30136 10029 30136 8470 30136 8470 30137 10029 30137 8471 30137 8316 30138 10031 30138 8315 30138 12905 30139 12907 30139 12912 30139 12909 30140 12897 30140 12913 30140 8332 30141 12896 30141 8310 30141 12896 30142 8332 30142 12899 30142 12908 30143 8310 30143 12898 30143 12908 30144 8311 30144 8310 30144 12904 30145 8315 30145 12906 30145 8315 30146 12904 30146 8316 30146 8316 30147 12904 30147 12903 30147 8311 30148 12906 30148 8315 30148 8316 30149 12903 30149 8330 30149 10449 30150 12915 30150 12916 30150 10449 30151 12916 30151 10451 30151 12917 30152 12918 30152 12919 30152 12920 30153 12921 30153 12922 30153 12922 30154 12921 30154 12919 30154 12925 30155 12924 30155 12926 30155 12928 30156 12927 30156 8364 30156 12929 30157 8364 30157 12930 30157 12931 30158 12930 30158 12932 30158 12931 30159 12932 30159 12920 30159 12922 30160 12931 30160 12920 30160 12923 30161 12924 30161 12925 30161 12925 30162 12927 30162 12928 30162 12918 30163 12916 30163 12915 30163 12918 30164 12914 30164 12916 30164 10445 30165 10451 30165 12916 30165 8608 30166 8364 30166 8609 30166 8609 30167 8364 30167 8366 30167 8609 30168 8366 30168 12934 30168 8602 30169 8371 30169 8374 30169 8605 30170 8371 30170 8602 30170 8608 30171 8362 30171 8364 30171 8605 30172 8606 30172 8367 30172 10447 30173 10449 30173 8600 30173 8600 30174 10449 30174 8602 30174 8599 30175 10446 30175 10447 30175 8599 30176 8608 30176 10446 30176 10445 30177 8609 30177 12934 30177 8602 30178 8374 30178 8376 30178 12925 30179 12919 30179 12923 30179 12917 30180 12929 30180 12931 30180 12931 30181 12919 30181 12917 30181 12931 30182 12922 30182 12919 30182 8353 30183 12921 30183 12920 30183 8353 30184 8376 30184 12921 30184 12932 30185 8362 30185 8354 30185 12927 30186 8366 30186 8364 30186 8366 30187 12927 30187 8367 30187 8367 30188 12927 30188 12926 30188 8371 30189 8367 30189 12926 30189 8362 30190 12930 30190 8364 30190 10448 30191 12935 30191 12936 30191 12936 30192 10455 30192 10448 30192 10450 30193 12935 30193 10448 30193 10455 30194 12937 30194 10454 30194 12943 30195 12944 30195 12945 30195 12946 30196 12945 30196 12947 30196 12950 30197 12951 30197 12938 30197 12940 30198 12950 30198 12938 30198 12941 30199 12942 30199 12943 30199 12943 30200 12945 30200 12946 30200 12946 30201 12947 30201 12948 30201 12948 30202 12949 30202 12950 30202 12935 30203 12954 30203 12952 30203 12935 30204 12952 30204 12936 30204 12937 30205 12936 30205 12952 30205 8603 30206 8373 30206 8372 30206 8582 30207 8369 30207 12956 30207 8582 30208 8377 30208 12957 30208 12957 30209 8381 30209 8384 30209 8385 30210 12955 30210 8579 30210 8372 30211 12956 30211 8603 30211 8598 30212 8358 30212 8356 30212 8577 30213 12955 30213 8386 30213 8601 30214 8604 30214 8603 30214 10454 30215 8581 30215 8579 30215 8601 30216 8375 30216 8604 30216 8576 30217 8577 30217 12955 30217 12957 30218 12956 30218 8582 30218 10455 30219 8576 30219 10448 30219 12957 30220 10454 30220 10452 30220 8601 30221 10448 30221 8598 30221 8601 30222 10450 30222 10448 30222 10450 30223 8601 30223 8603 30223 8388 30224 12955 30224 8386 30224 8579 30225 8384 30225 8385 30225 12957 30226 8377 30226 8369 30226 8369 30227 8377 30227 12956 30227 8369 30228 12956 30228 8372 30228 12943 30229 12953 30229 12941 30229 12946 30230 12948 30230 12954 30230 12950 30231 12952 30231 12954 30231 12954 30232 12953 30232 12946 30232 12946 30233 12953 30233 12943 30233 8388 30234 12939 30234 12938 30234 8388 30235 8386 30235 12939 30235 12939 30236 8386 30236 8385 30236 12942 30237 8385 30237 8384 30237 8356 30238 12949 30238 8375 30238 12945 30239 8373 30239 12947 30239 12958 30240 12959 30240 12960 30240 12963 30241 12962 30241 12961 30241 12966 30242 12965 30242 12967 30242 12958 30243 12968 30243 12969 30243 12969 30244 12966 30244 12958 30244 12962 30245 12970 30245 12971 30245 12971 30246 12972 30246 12962 30246 12972 30247 12973 30247 12974 30247 12973 30248 12971 30248 12975 30248 12975 30249 12971 30249 12970 30249 12969 30250 12976 30250 12977 30250 12968 30251 12978 30251 12969 30251 12977 30252 12979 30252 12966 30252 12975 30253 12964 30253 12980 30253 12975 30254 12970 30254 12964 30254 12981 30255 12974 30255 12963 30255 12961 30256 12973 30256 12975 30256 12961 30257 12975 30257 12980 30257 12963 30258 12974 30258 12961 30258 12965 30259 12981 30259 12967 30259 12965 30260 12974 30260 12981 30260 12981 30261 12982 30261 12967 30261 12967 30262 12982 30262 12978 30262 12979 30263 12960 30263 12982 30263 12979 30264 12977 30264 12959 30264 12960 30265 12978 30265 12982 30265 12983 30266 12980 30266 12984 30266 12987 30267 12988 30267 12980 30267 12980 30268 12988 30268 12981 30268 12981 30269 12988 30269 12989 30269 12982 30270 12992 30270 12993 30270 12994 30271 12982 30271 12993 30271 12997 30272 12982 30272 12996 30272 13000 30273 12984 30273 12979 30273 13001 30274 12983 30274 13002 30274 13001 30275 12985 30275 12983 30275 13001 30276 13003 30276 12985 30276 12985 30277 13003 30277 12986 30277 12986 30278 13003 30278 13004 30278 12989 30279 13006 30279 13007 30279 12993 30280 13010 30280 13011 30280 12995 30281 13012 30281 13013 30281 12997 30282 13014 30282 13015 30282 12999 30283 13016 30283 13017 30283 12984 30284 13018 30284 13002 30284 12986 30285 13004 30285 12987 30285 12987 30286 13005 30286 12988 30286 12988 30287 13006 30287 12989 30287 12990 30288 13008 30288 12991 30288 12992 30289 13010 30289 12993 30289 12993 30290 13011 30290 12994 30290 12994 30291 13012 30291 12995 30291 12996 30292 13014 30292 12997 30292 12997 30293 13015 30293 12998 30293 12999 30294 13017 30294 13000 30294 13009 30295 13006 30295 13010 30295 13017 30296 13015 30296 13018 30296 13017 30297 13016 30297 13015 30297 13011 30298 13013 30298 13012 30298 13014 30299 13013 30299 13011 30299 13015 30300 13002 30300 13018 30300 13002 30301 13015 30301 13019 30301 13020 30302 13021 30302 13019 30302 13019 30303 13015 30303 13022 30303 13023 30304 13019 30304 13022 30304 13024 30305 13015 30305 13014 30305 13027 30306 13011 30306 13010 30306 13025 30307 13028 30307 13014 30307 13029 30308 13030 30308 13031 30308 13034 30309 13021 30309 13020 30309 13036 30310 13014 30310 13028 30310 13033 30311 13026 30311 13027 30311 13032 30312 13027 30312 13038 30312 13029 30313 13038 30313 13030 30313 13042 30314 13041 30314 13043 30314 13046 30315 13045 30315 13043 30315 13047 30316 13048 30316 13049 30316 13049 30317 13050 30317 13047 30317 13047 30318 13050 30318 13034 30318 13027 30319 13010 30319 13038 30319 13043 30320 13005 30320 13049 30320 13010 30321 13006 30321 13051 30321 13049 30322 13005 30322 13004 30322 13043 30323 13041 30323 13005 30323 13041 30324 13040 30324 13006 30324 13049 30325 13046 30325 13043 30325 13005 30326 13041 30326 13006 30326 13034 30327 13044 30327 13048 30327 13039 30328 13029 30328 13031 30328 13052 30329 13035 30329 13019 30329 13052 30330 13023 30330 13022 30330 13033 30331 13025 30331 13026 30331 13031 30332 13051 30332 13040 30332 13048 30333 13046 30333 13049 30333 13033 30334 13037 30334 13025 30334 13031 30335 13040 30335 13039 30335 13041 30336 13042 30336 13039 30336 13024 30337 13036 30337 13052 30337 13054 30338 13036 30338 13033 30338 13055 30339 13033 30339 13032 30339 13055 30340 13029 30340 13044 30340 13056 30341 13057 30341 13058 30341 13062 30342 13063 30342 13064 30342 13057 30343 13065 30343 13066 30343 13067 30344 13064 30344 13062 30344 13060 30345 13070 30345 13071 30345 13068 30346 13071 30346 13072 30346 13068 30347 13072 30347 13067 30347 13070 30348 13073 30348 13071 30348 13067 30349 13072 30349 13074 30349 13069 30350 13075 30350 13070 30350 13074 30351 13072 30351 13076 30351 13077 30352 13076 30352 13073 30352 13074 30353 13054 30353 13075 30353 13075 30354 13054 30354 13079 30354 13077 30355 13080 30355 13076 30355 13053 30356 13080 30356 13044 30356 13078 30357 13053 30357 13054 30357 13054 30358 13055 30358 13079 30358 13057 30359 13066 30359 13056 30359 13082 30360 13071 30360 13068 30360 13056 30361 13060 30361 13058 30361 13056 30362 13066 30362 13060 30362 13081 30363 13071 30363 13082 30363 13069 30364 13066 30364 13065 30364 13070 30365 13083 30365 13077 30365 13069 30366 13074 30366 13075 30366 13075 30367 13079 30367 13083 30367 13074 30368 13078 30368 13054 30368 13055 30369 13077 30369 13079 30369 13076 30370 13080 30370 13078 30370 13053 30371 13052 30371 13054 30371 13089 30372 13063 30372 13064 30372 13062 30373 13090 30373 13068 30373 13068 30374 13091 30374 13082 30374 13086 30375 13092 30375 13093 30375 13086 30376 13088 30376 13092 30376 13094 30377 13088 30377 13085 30377 13095 30378 13085 30378 13087 30378 13096 30379 13087 30379 13084 30379 13093 30380 13084 30380 13086 30380 13098 30381 13084 30381 13099 30381 13057 30382 13092 30382 13065 30382 13089 30383 13092 30383 13094 30383 13059 30384 13098 30384 13099 30384 13098 30385 13061 30385 13096 30385 13096 30386 13061 30386 13081 30386 13082 30387 13097 30387 13096 30387 13097 30388 13091 30388 13095 30388 13095 30389 13091 30389 13090 30389 13095 30390 13062 30390 13094 30390 13060 30391 13093 30391 13058 30391 13103 30392 13102 30392 13101 30392 13101 30393 13106 30393 13105 30393 13103 30394 13105 30394 13109 30394 13104 30395 13109 30395 13108 30395 13100 30396 13108 30396 13106 30396 13101 30397 13100 30397 13106 30397 13105 30398 13103 30398 13101 30398 13109 30399 13107 30399 13108 30399 13113 30400 13112 30400 13114 30400 13113 30401 13114 30401 13115 30401 13112 30402 13116 30402 13114 30402 13114 30403 13117 30403 13118 30403 13115 30404 13118 30404 13119 30404 13118 30405 13120 30405 13119 30405 13115 30406 13114 30406 13118 30406 13124 30407 13122 30407 13121 30407 13110 30408 13113 30408 13125 30408 13121 30409 13113 30409 13115 30409 13120 30410 13118 30410 13126 30410 13126 30411 13118 30411 13117 30411 13128 30412 13116 30412 13112 30412 13129 30413 13112 30413 13111 30413 13131 30414 13125 30414 13123 30414 13133 30415 13122 30415 13124 30415 13134 30416 13124 30416 13119 30416 13120 30417 13134 30417 13119 30417 13127 30418 13114 30418 13128 30418 13135 30419 13110 30419 13130 30419 13130 30420 13125 30420 13131 30420 13131 30421 13123 30421 13132 30421 13127 30422 13117 30422 13126 30422 13136 30423 13134 30423 13120 30423 13130 30424 13131 30424 13135 30424 13120 30425 13126 30425 13136 30425 13129 30426 13137 30426 13127 30426 13138 30427 13131 30427 13133 30427 13139 30428 13141 30428 13136 30428 13133 30429 13141 30429 13138 30429 13126 30430 13147 30430 13148 30430 13136 30431 13148 30431 13140 30431 13138 30432 13142 30432 13131 30432 13137 30433 13145 30433 13127 30433 13127 30434 13146 30434 13126 30434 13142 30435 13149 30435 13143 30435 13153 30436 13135 30436 13143 30436 13141 30437 13152 30437 13138 30437 13154 30438 13147 30438 13146 30438 13147 30439 13148 30439 13146 30439 13155 30440 13139 30440 13156 30440 13151 30441 13157 30441 13158 30441 13149 30442 13160 30442 13161 30442 13150 30443 13164 30443 13165 30443 13146 30444 13166 30444 13167 30444 13148 30445 13169 30445 13170 30445 13151 30446 13158 30446 13152 30446 13143 30447 13162 30447 13153 30447 13153 30448 13163 30448 13144 30448 13145 30449 13166 30449 13146 30449 13146 30450 13167 30450 13154 30450 13154 30451 13168 30451 13147 30451 13171 30452 13172 30452 13156 30452 13170 30453 13173 30453 13171 30453 13173 30454 13169 30454 13174 30454 13174 30455 13169 30455 13168 30455 13177 30456 13166 30456 13165 30456 13178 30457 13165 30457 13164 30457 13179 30458 13164 30458 13163 30458 13181 30459 13162 30459 13161 30459 13182 30460 13181 30460 13161 30460 13184 30461 13155 30461 13185 30461 13184 30462 13157 30462 13155 30462 13157 30463 13186 30463 13158 30463 13158 30464 13186 30464 13187 30464 13161 30465 13160 30465 13183 30465 13159 30466 13188 30466 13160 30466 13181 30467 13180 30467 13162 30467 13178 30468 13177 30468 13165 30468 13177 30469 13176 30469 13166 30469 13176 30470 13175 30470 13167 30470 13175 30471 13174 30471 13168 30471 13185 30472 13156 30472 13172 30472 12961 30473 13109 30473 13189 30473 13193 30474 13194 30474 13195 30474 13195 30475 13194 30475 13196 30475 13197 30476 13195 30476 13196 30476 13201 30477 13202 30477 13203 30477 13202 30478 13196 30478 13194 30478 13204 30479 13199 30479 13205 30479 13205 30480 13206 30480 13204 30480 13201 30481 13210 30481 13211 30481 13212 30482 13201 30482 13211 30482 13203 30483 13210 30483 13201 30483 13205 30484 13213 30484 13206 30484 13213 30485 13214 30485 13206 30485 13204 30486 13207 30486 12963 30486 13208 30487 13203 30487 12961 30487 13107 30488 13105 30488 13172 30488 13172 30489 13189 30489 13109 30489 13184 30490 13205 30490 13199 30490 13186 30491 13199 30491 13200 30491 13187 30492 13200 30492 13198 30492 13188 30493 13198 30493 13194 30493 13103 30494 13197 30494 13102 30494 13103 30495 13181 30495 13197 30495 13180 30496 13103 30496 13101 30496 13101 30497 13191 30497 13179 30497 13196 30498 13100 30498 13102 30498 13196 30499 13102 30499 13197 30499 13213 30500 13106 30500 13214 30500 13106 30501 13107 30501 13171 30501 13172 30502 13171 30502 13107 30502 13206 30503 13171 30503 13173 30503 13210 30504 13175 30504 13176 30504 13211 30505 13176 30505 13177 30505 13190 30506 13178 30506 13179 30506 13191 30507 13190 30507 13179 30507 13209 30508 13175 30508 13210 30508 13210 30509 13176 30509 13211 30509 13212 30510 13178 30510 13190 30510 13192 30511 13212 30511 13190 30511 13181 30512 13182 30512 13195 30512 13182 30513 13183 30513 13193 30513 13191 30514 13100 30514 13196 30514 13101 30515 12959 30515 12960 30515 13102 30516 13100 30516 12960 30516 12960 30517 13100 30517 13101 30517 12959 30518 13102 30518 12960 30518 13212 30519 12959 30519 13201 30519 13212 30520 13192 30520 12960 30520 12960 30521 13192 30521 13202 30521 12960 30522 13202 30522 12959 30522 13217 30523 13216 30523 13218 30523 13217 30524 13219 30524 13215 30524 13223 30525 13217 30525 13218 30525 13222 30526 13217 30526 13223 30526 13218 30527 13216 30527 13225 30527 13225 30528 13226 30528 13218 30528 13216 30529 13230 30529 13225 30529 13231 30530 13224 30530 13226 30530 13232 30531 13219 30531 13221 30531 13233 30532 13220 30532 13219 30532 13215 30533 13220 30533 13228 30533 13228 30534 13220 30534 13233 30534 13234 30535 13226 30535 13227 30535 13230 30536 13234 30536 13225 30536 13229 30537 13228 30537 13235 30537 13239 30538 13238 30538 13240 30538 13244 30539 13245 30539 13237 30539 13233 30540 13246 30540 13228 30540 13248 30541 13246 30541 13247 30541 13248 30542 13249 30542 13250 30542 13253 30543 13243 30543 13252 30543 13253 30544 13241 30544 13243 30544 13248 30545 13250 30545 13251 30545 13246 30546 13251 30546 13243 30546 13255 30547 13254 30547 13256 30547 13245 30548 13244 30548 13255 30548 13245 30549 13240 30549 13238 30549 13248 30550 13251 30550 13246 30550 13255 30551 13240 30551 13245 30551 13259 30552 13262 30552 13260 30552 13266 30553 13267 30553 13268 30553 13261 30554 13260 30554 13271 30554 13265 30555 13272 30555 13273 30555 13263 30556 13274 30556 13272 30556 13275 30557 13276 30557 13277 30557 13278 30558 13279 30558 7950 30558 13279 30559 13278 30559 13275 30559 13281 30560 13275 30560 13277 30560 13280 30561 13282 30561 13281 30561 13279 30562 13281 30562 13284 30562 13279 30563 13284 30563 7949 30563 13281 30564 13283 30564 13284 30564 13283 30565 13285 30565 13286 30565 13284 30566 13286 30566 7948 30566 13286 30567 7941 30567 7948 30567 13287 30568 13288 30568 13268 30568 13268 30569 13288 30569 13269 30569 13263 30570 13264 30570 13260 30570 13265 30571 13269 30571 13264 30571 13275 30572 13266 30572 13273 30572 13276 30573 13275 30573 13273 30573 13286 30574 13284 30574 13283 30574 13286 30575 13289 30575 13290 30575 13258 30576 13294 30576 13295 30576 13295 30577 13294 30577 13296 30577 13292 30578 13297 30578 13296 30578 13292 30579 13298 30579 13291 30579 13299 30580 13298 30580 13240 30580 13255 30581 13299 30581 13240 30581 13300 30582 13301 30582 13302 30582 13307 30583 13308 30583 13302 30583 13302 30584 13308 30584 13300 30584 13308 30585 13310 30585 13311 30585 13314 30586 13313 30586 13311 30586 13312 6 13315 6 13295 6 13285 30587 13293 30587 13289 30587 13285 30588 13289 30588 13286 30588 13239 30589 13316 30589 13236 30589 13318 30590 13317 30590 13319 30590 13320 30591 13319 30591 13321 30591 13324 30592 13323 30592 13316 30592 13239 30593 13324 30593 13316 30593 13327 30594 13326 30594 13328 30594 13329 30595 13327 30595 13328 30595 13327 30596 13329 30596 13330 30596 13322 30597 13330 30597 13331 30597 13327 30598 13330 30598 13322 30598 13327 30599 13334 30599 13325 30599 13320 30600 13321 30600 13325 30600 13285 30601 13297 30601 13293 30601 13289 30602 13293 30602 13290 30602 13292 30603 13293 30603 13297 30603 13313 30604 7945 30604 13336 30604 13315 30605 13322 30605 13324 30605 13315 30606 13313 30606 13322 30606 13315 30607 13312 30607 13313 30607 13335 30608 13313 30608 13337 30608 13337 30609 13338 30609 13335 30609 13339 30610 13340 30610 13320 30610 13343 30611 13342 30611 13341 30611 13343 30612 13341 30612 13344 30612 13346 30613 13345 30613 13347 30613 13351 30614 13349 30614 13350 30614 13351 30615 13352 30615 13349 30615 13310 30616 13348 30616 13314 30616 13353 30617 13354 30617 13314 30617 13354 30618 13355 30618 13314 30618 13314 30619 13355 30619 13338 30619 13356 30620 13357 30620 13346 30620 13360 30621 13308 30621 13307 30621 13360 30622 13361 30622 13308 30622 13308 30623 13361 30623 13309 30623 13309 30624 13361 30624 13362 30624 13363 30625 13364 30625 13365 30625 13365 30626 13364 30626 13366 30626 13348 30627 13327 30627 13371 30627 13333 30628 13371 30628 13327 30628 13334 30629 13339 30629 13320 30629 13345 30630 13341 30630 13327 30630 13341 30631 13339 30631 13327 30631 13354 30632 7945 30632 13335 30632 13354 30633 13353 30633 7945 30633 7945 30634 13353 30634 13336 30634 13371 30635 13370 30635 13353 30635 13336 30636 13368 30636 13322 30636 13372 30637 13373 30637 13374 30637 13375 30638 13374 30638 13376 30638 13377 30639 13372 30639 13375 30639 13376 30640 13374 30640 13378 30640 13377 30641 13380 30641 13379 30641 13377 30642 13381 30642 13380 30642 13379 30643 13380 30643 13382 30643 13382 30644 13383 30644 13372 30644 13379 30645 13382 30645 13372 30645 13374 30646 13375 30646 13372 30646 13389 30647 13388 30647 13390 30647 13391 30648 13392 30648 13390 30648 13387 30649 13386 30649 13393 30649 13395 30650 13390 30650 13388 30650 13395 30651 13396 30651 8087 30651 13400 30652 13401 30652 13398 30652 13398 30653 13393 30653 13386 30653 13402 30654 13399 30654 13386 30654 13388 30655 13389 30655 13386 30655 13390 30656 13392 30656 13389 30656 13397 30657 13395 30657 8087 30657 7943 30658 13403 30658 13394 30658 13407 30659 13408 30659 13409 30659 13409 30660 13408 30660 13410 30660 13406 30661 13409 30661 13410 30661 13406 30662 13404 30662 13411 30662 13413 30663 13416 30663 13414 30663 13419 30664 13415 30664 13418 30664 13420 30665 13415 30665 13421 30665 13421 30666 13415 30666 13419 30666 13422 30667 13421 30667 13423 30667 13428 30668 13427 30668 13407 30668 13432 30669 13431 30669 13433 30669 13437 30670 13435 30670 13436 30670 13440 30671 13438 30671 13439 30671 13443 30672 13440 30672 13442 30672 13443 30673 13444 30673 13440 30673 13443 30674 13445 30674 13444 30674 13444 30675 13447 30675 13448 30675 13432 30676 13450 30676 13448 30676 13430 30677 13432 30677 13448 30677 13452 30678 13425 30678 13451 30678 8090 30679 13425 30679 13453 30679 13427 30680 13428 30680 13425 30680 13425 30681 13428 30681 13440 30681 13457 30682 13458 30682 13456 30682 13456 30683 13458 30683 13459 30683 13462 30684 13463 30684 13460 30684 13462 30685 13464 30685 13463 30685 13463 30686 13464 30686 13423 30686 13426 30687 13466 30687 13465 30687 13456 30688 13459 30688 13460 30688 13464 30689 13470 30689 13471 30689 13468 30690 13452 30690 13467 30690 13472 30691 13473 30691 13461 30691 13473 30692 13474 30692 13475 30692 13473 30693 13472 30693 13474 30693 13464 30694 13475 30694 13469 30694 13476 30695 13413 30695 13420 30695 13420 30696 13421 30696 13476 30696 13477 30697 13421 30697 13422 30697 13478 30698 13480 30698 13477 30698 13484 30699 13485 30699 13440 30699 13449 30700 13484 30700 13440 30700 13484 30701 13449 30701 13486 30701 13449 30702 13444 30702 13486 30702 13486 30703 13444 30703 13463 30703 13451 30704 8090 30704 13465 30704 13487 30705 13465 30705 13453 30705 13425 30706 13468 30706 13466 30706 13463 30707 13465 30707 13487 30707 13463 30708 13487 30708 13486 30708 13462 30709 13475 30709 13464 30709 13484 30710 13453 30710 13485 30710 13383 30711 13489 30711 13372 30711 13373 30712 13490 30712 13491 30712 13373 30713 13372 30713 13490 30713 13504 30714 13505 30714 13500 30714 9112 30715 13507 30715 13501 30715 13508 30716 13509 30716 13503 30716 13500 30717 13499 30717 13387 30717 13510 30718 13396 30718 13499 30718 13367 30719 13360 30719 13306 30719 13306 30720 13416 30720 13483 30720 13477 30721 13483 30721 13476 30721 13416 30722 13413 30722 13476 30722 13511 30723 13512 30723 13513 30723 13509 30724 13494 30724 13513 30724 13494 30725 13509 30725 13495 30725 13495 30726 13509 30726 13508 30726 8085 30727 13383 30727 8087 30727 8088 30728 13383 30728 13384 30728 13404 30729 13403 30729 13412 30729 8087 30730 13383 30730 8088 30730 8088 30731 13384 30731 7943 30731 13514 30732 13393 30732 13515 30732 13518 30733 13516 30733 13401 30733 13520 30734 13504 30734 13514 30734 13514 30735 13504 30735 13500 30735 13515 30736 13517 30736 13521 30736 13398 30737 13515 30737 13393 30737 13398 30738 13517 30738 13515 30738 13398 30739 13401 30739 13517 30739 13519 30740 13522 30740 13516 30740 13521 30741 13524 30741 13525 30741 13514 30742 13500 30742 13393 30742 13520 30743 13514 30743 13515 30743 13523 30744 13524 30744 13516 30744 13253 30745 13527 30745 13526 30745 13253 30746 13529 30746 13528 30746 13529 30747 13253 30747 13252 30747 9071 30748 13527 30748 13528 30748 13526 30749 13530 30749 13244 30749 13244 30750 13530 30750 13254 30750 13244 30751 13241 30751 13526 30751 7950 30752 7949 30752 13254 30752 13254 30753 7949 30753 7948 30753 13254 30754 7948 30754 13256 30754 13256 30755 7948 30755 13257 30755 7941 30756 13290 30756 13257 30756 13299 30757 13290 30757 13291 30757 13257 30758 13290 30758 13299 30758 7950 30759 13531 30759 13532 30759 13278 30760 13532 30760 13267 30760 13533 30761 9082 30761 13534 30761 13534 30762 9082 30762 13536 30762 13252 30763 13288 30763 13287 30763 13271 30764 13250 30764 13537 30764 13288 30765 13250 30765 13271 30765 13538 243 13539 243 13537 243 13539 30766 13271 30766 13537 30766 13529 30767 13287 30767 13540 30767 13529 30768 9079 30768 13528 30768 13529 30769 13540 30769 9079 30769 9079 30770 9071 30770 13528 30770 13533 6 9071 6 9075 6 13532 30771 13526 30771 13533 30771 13526 30772 13532 30772 13530 30772 9082 30773 13535 30773 9077 30773 9077 30774 13535 30774 9076 30774 9077 30775 13536 30775 9082 30775 13340 30776 13342 30776 13234 30776 13230 30777 13229 30777 13235 30777 13242 30778 13318 30778 13235 30778 13324 30779 13239 30779 13315 30779 13315 30780 13239 30780 13258 30780 13294 30781 13258 30781 13240 30781 13340 30782 13235 30782 13320 30782 13458 30783 13342 30783 13343 30783 13357 30784 13472 30784 13461 30784 13472 30785 13357 30785 13358 30785 13544 30786 13472 30786 13543 30786 13544 30787 13545 30787 13472 30787 13544 30788 13547 30788 13546 30788 13358 30789 13548 30789 13543 30789 13549 30790 13350 30790 13550 30790 13549 30791 13351 30791 13350 30791 13363 30792 13350 30792 13362 30792 13363 30793 13551 30793 13550 30793 13552 30794 13365 30794 13366 30794 13553 30795 13366 30795 13482 30795 13554 30796 13553 30796 13482 30796 13554 30797 13556 30797 13553 30797 13554 30798 13557 30798 13556 30798 13554 30799 13558 30799 13557 30799 13558 30800 13554 30800 13559 30800 13559 30801 13554 30801 13560 30801 13362 30802 13310 30802 13309 30802 13482 30803 13481 30803 13555 30803 13555 30804 13481 30804 13563 30804 13422 30805 13471 30805 13478 30805 13422 30806 13423 30806 13471 30806 13565 30807 13471 30807 13470 30807 13568 30808 13570 30808 13567 30808 13357 30809 13459 30809 13344 30809 13378 30810 13455 30810 13376 30810 13385 30811 13435 30811 13377 30811 13377 30812 13435 30812 13437 30812 13428 30813 13381 30813 13438 30813 13428 30814 13407 30814 13381 30814 13381 30815 13407 30815 13380 30815 13377 30816 13437 30816 13381 30816 13576 30817 13577 30817 13578 30817 13579 30818 13578 30818 13580 30818 13581 30819 13584 30819 13582 30819 13574 30820 13573 30820 13575 30820 13586 30821 13578 30821 13587 30821 13586 30822 13588 30822 13578 30822 13587 30823 13578 30823 13577 30823 13575 30824 13589 30824 13577 30824 13589 30825 13575 30825 13585 30825 13587 30826 13585 30826 13581 30826 13587 30827 13589 30827 13585 30827 13247 30828 13584 30828 13248 30828 13247 30829 13582 30829 13584 30829 13247 30830 13233 30830 13232 30830 13378 30831 13231 30831 13234 30831 13455 30832 13378 30832 13234 30832 13570 30833 13591 30833 13567 30833 13591 30834 13566 30834 13567 30834 13592 30835 13562 30835 13593 30835 13592 30836 13593 30836 13594 30836 13567 30837 13594 30837 13569 30837 13567 30838 13592 30838 13594 30838 13596 30839 13553 30839 13598 30839 13553 30840 13552 30840 13366 30840 13549 30841 13548 30841 13351 30841 13543 30842 13599 30842 13600 30842 13543 30843 13600 30843 13601 30843 13602 30844 13603 30844 13543 30844 13543 30845 13603 30845 13604 30845 13604 30846 13603 30846 13605 30846 13609 30847 13608 30847 13607 30847 13609 30848 13546 30848 13608 30848 13611 30849 13606 30849 13547 30849 13433 30850 13435 30850 13385 30850 13459 30851 13542 30851 13344 30851 13232 30852 13221 30852 13571 30852 13584 30853 13581 30853 13573 30853 13343 30854 13344 30854 13542 30854 13571 30855 13590 30855 13232 30855 13582 30856 13590 30856 13583 30856 13572 30857 13231 30857 13378 30857 13319 30858 13272 30858 13321 30858 13319 30859 13273 30859 13272 30859 13319 30860 13317 30860 13276 30860 13277 30861 13317 30861 13316 30861 13612 30862 13613 30862 13391 30862 13316 30863 13323 30863 13280 30863 13280 30864 13323 30864 13439 30864 13332 30865 13441 30865 13323 30865 13443 30866 13331 30866 13330 30866 13445 30867 13329 30867 13446 30867 13330 30868 13445 30868 13443 30868 13446 30869 13329 30869 13328 30869 13326 30870 13325 30870 13448 30870 13400 30871 13615 30871 13401 30871 13400 30872 13430 30872 13615 30872 13400 30873 13431 30873 13430 30873 13400 30874 13399 30874 13431 30874 13431 30875 13399 30875 13434 30875 13326 30876 13448 30876 13447 30876 13448 30877 13325 30877 13616 30877 13518 30878 13618 30878 13619 30878 13620 30879 13619 30879 13263 30879 13399 30880 13402 30880 13434 30880 13447 30881 13446 30881 13328 30881 13331 30882 13442 30882 13441 30882 13441 30883 13439 30883 13323 30883 13419 30884 13622 30884 13614 30884 13427 30885 13391 30885 13408 30885 13624 30886 13282 30886 13623 30886 13624 30887 13625 30887 13282 30887 13295 30888 13283 30888 13282 30888 13295 30889 13296 30889 13283 30889 13282 30890 13625 30890 13300 30890 13627 30891 13301 30891 13626 30891 13630 30892 13629 30892 13631 30892 13417 30893 13632 30893 13418 30893 13301 30894 13627 30894 13303 30894 13633 30895 13414 30895 13416 30895 13306 30896 13633 30896 13416 30896 13633 30897 13304 30897 13414 30897 13630 30898 13631 30898 13417 30898 13414 30899 13630 30899 13417 30899 13418 30900 13632 30900 13560 30900 13263 30901 13634 30901 13274 30901 13618 30902 13617 30902 13634 30902 13634 30903 13617 30903 13274 30903 13519 30904 13262 30904 13635 30904 13637 30905 13638 30905 13261 30905 13639 30906 13261 30906 13539 30906 10732 30907 13539 30907 9089 30907 13261 30908 13636 30908 13259 30908 13640 30909 13641 30909 13523 30909 13640 30910 9957 30910 13641 30910 13523 30911 13642 30911 13637 30911 13523 30912 13522 30912 13642 30912 13642 30913 13522 30913 13636 30913 13519 30914 13643 30914 13522 30914 13643 30915 13519 30915 13635 30915 13410 30916 13408 30916 13390 30916 13304 30917 13303 30917 13630 30917 13616 30918 13274 30918 13617 30918 13261 30919 13523 30919 13637 30919 13638 30920 13637 30920 13642 30920 13262 30921 13259 30921 13635 30921 13635 30922 13259 30922 13522 30922 13615 30923 13448 30923 13616 30923 13540 30924 13536 30924 9079 30924 13534 30925 13540 30925 13287 30925 13644 30926 13579 30926 13645 30926 13646 30927 9972 30927 10282 30927 13539 30928 13538 30928 9089 30928 9089 30929 13538 30929 9972 30929 9077 30930 9076 30930 13541 30930 13541 30931 9076 30931 9079 30931 13647 30932 13571 30932 13648 30932 13373 30933 13498 30933 13648 30933 13648 30934 13498 30934 13647 30934 13374 30935 13648 30935 13571 30935 13649 30936 13647 30936 13498 30936 13583 30937 13571 30937 13647 30937 13497 30938 13504 30938 13498 30938 13498 30939 13504 30939 13520 30939 9101 30940 9099 30940 13641 30940 9110 30941 9099 30941 10739 30941 10739 30942 9099 30942 9101 30942 13650 30943 10739 30943 9101 30943 10738 30944 13650 30944 13651 30944 9110 30945 13652 30945 9099 30945 13580 30946 13652 30946 9960 30946 13639 30947 13580 30947 13640 30947 13579 30948 13639 30948 10281 30948 10281 30949 13639 30949 10732 30949 10282 30950 13653 30950 13654 30950 13654 30951 13653 30951 13655 30951 10292 30952 13655 30952 10290 30952 10290 30953 13655 30953 10291 30953 10281 30954 13645 30954 13579 30954 13591 30955 13570 30955 13658 30955 13658 30956 13570 30956 13659 30956 13662 30957 13565 30957 13661 30957 13555 30958 13563 30958 13662 30958 13563 30959 13564 30959 13662 30959 13554 30960 13555 30960 13663 30960 13663 6 13555 6 13662 6 13661 6 13664 6 13663 6 13661 6 13660 6 13665 6 13659 30961 13665 30961 13658 30961 13666 6 13667 6 13664 6 13554 30962 13663 30962 13560 30962 13593 30963 13562 30963 13667 30963 13667 30964 13562 30964 13663 30964 13594 30965 13666 30965 13569 30965 13570 30966 13568 30966 13659 30966 13670 6 13668 6 13671 6 13672 6 13670 6 13671 6 13672 30967 13675 30967 13674 30967 13668 6 13676 6 13671 6 13671 30968 13676 30968 13677 30968 13551 30969 13552 30969 13669 30969 13550 30970 13669 30970 13549 30970 13674 30971 13548 30971 13673 30971 13603 30972 13602 30972 13677 30972 13677 30973 13602 30973 13671 30973 13605 30974 13677 30974 13676 30974 13595 30975 13676 30975 13668 30975 13607 30976 13623 30976 13612 30976 13609 30977 13612 30977 13610 30977 13624 30978 13604 30978 13597 30978 13629 30979 13598 30979 13556 30979 13557 30980 13558 30980 13631 30980 13628 30981 13598 30981 13629 30981 13558 30982 13632 30982 13631 30982 13628 30983 13627 30983 13598 30983 13611 30984 13623 30984 13606 30984 13606 30985 13623 30985 13607 30985 13610 30986 13612 30986 13592 30986 13612 30987 13614 30987 13561 30987 13546 30988 13610 30988 13679 30988 13567 30989 13680 30989 13592 30989 13681 30990 13543 30990 13604 30990 13544 30991 13543 30991 13682 30991 13682 30992 13547 30992 13544 30992 13684 30993 13685 30993 13686 30993 9960 30994 9957 30994 13580 30994 13580 30995 9957 30995 13640 30995 13687 30996 9957 30996 9953 30996 13687 30997 13650 30997 9101 30997 13523 30998 13641 30998 13525 30998 13691 30999 10290 30999 9969 30999 9971 31000 13691 31000 9969 31000 10290 31001 13692 31001 9969 31001 9966 31002 13692 31002 13656 31002 13693 31003 13656 31003 13694 31003 13685 31004 13694 31004 13686 31004 13693 31005 9966 31005 13656 31005 13691 31006 13690 31006 10290 31006 13690 31007 13689 31007 13654 31007 9972 31008 9968 31008 9089 31008 9972 31009 13646 31009 9968 31009 13685 31010 9968 31010 9967 31010 9966 31011 13693 31011 9967 31011 13685 31012 9967 31012 13693 31012 13695 31013 13512 31013 13510 31013 13695 31014 13697 31014 13512 31014 13509 31015 13512 31015 13698 31015 13492 31016 13495 31016 13502 31016 13513 31017 13494 31017 13700 31017 13701 31018 13513 31018 13700 31018 13704 31019 13511 31019 13513 31019 13701 31020 13704 31020 13513 31020 13505 31021 13705 31021 13506 31021 13506 31022 13705 31022 9097 31022 13520 31023 13521 31023 13525 31023 13497 31024 13705 31024 13504 31024 9954 31025 9107 31025 9106 31025 10739 31026 13707 31026 9110 31026 13710 31027 13709 31027 9945 31027 13651 31028 13688 31028 13710 31028 13688 31029 13651 31029 13650 31029 9107 31030 9954 31030 13713 31030 13713 31031 9956 31031 13711 31031 13711 31032 13712 31032 13714 31032 13714 31033 13712 31033 9959 31033 9110 31034 13714 31034 9959 31034 13708 31035 9950 31035 13709 31035 13712 31036 13715 31036 9959 31036 13712 31037 13716 31037 13715 31037 13716 31038 13712 31038 9956 31038 13717 31039 9955 31039 9954 31039 9950 31040 13708 31040 13717 31040 13716 31041 9956 31041 13717 31041 9959 31042 13715 31042 9960 31042 13692 31043 9962 31043 13656 31043 13692 31044 10290 31044 9962 31044 10292 31045 10290 31045 10291 31045 10290 31046 10291 31046 9962 31046 13610 31047 13680 31047 13679 31047 13687 31048 13721 31048 13722 31048 13688 31049 13723 31049 13710 31049 13691 31050 9971 31050 13720 31050 13720 31051 9971 31051 9967 31051 13690 31052 13725 31052 13689 31052 13718 31053 13689 31053 13725 31053 9112 31054 13506 31054 9113 31054 9112 31055 9113 31055 13507 31055 9092 31056 13501 31056 9096 31056 13501 31057 13507 31057 9096 31057 9096 31058 13507 31058 9064 31058 13502 31059 13493 31059 13492 31059 13726 31060 13727 31060 13728 31060 13510 31061 13499 31061 13696 31061 13727 31062 13499 31062 13503 31062 13726 31063 13696 31063 13499 31063 13727 31064 13699 31064 13728 31064 13699 31065 13727 31065 13698 31065 13698 31066 13503 31066 13509 31066 13512 31067 13697 31067 13699 31067 13728 31068 13699 31068 13697 31068 9092 31069 9097 31069 13496 31069 13497 31070 9097 31070 13705 31070 13496 31071 9097 31071 13497 31071 13731 31072 13490 31072 13729 31072 13701 31073 13730 31073 13704 31073 13732 31074 13491 31074 13731 31074 13730 31075 13729 31075 13704 31075 13494 31076 13732 31076 13700 31076 13700 31077 13732 31077 13702 31077 13721 31078 10739 31078 13722 31078 13724 31079 13723 31079 10738 31079 13714 31080 13707 31080 13721 31080 13721 31081 13707 31081 10739 31081 13718 31082 13653 31082 10724 31082 13684 31083 13718 31083 10724 31083 13720 31084 13655 31084 13725 31084 13710 31085 13724 31085 13708 31085 13708 31086 13724 31086 13717 31086 13713 31087 13711 31087 13733 31087 13733 31088 13715 31088 13716 31088 13716 31089 13717 31089 13733 31089 13733 31090 13717 31090 13724 31090 13677 31091 13734 31091 13675 31091 13737 31092 13736 31092 13734 31092 13737 31093 13734 31093 13677 31093 13677 31094 13735 31094 13736 31094 13738 31095 13739 31095 13659 31095 13738 31096 13741 31096 13739 31096 13666 31097 13659 31097 13740 31097 13740 31098 13741 31098 13738 31098 13742 8265 13743 8265 13744 8265 13748 7838 13747 7838 13749 7838 13745 6 13746 6 13748 6 13745 243 13749 243 13744 243 13739 31099 13735 31099 13750 31099 13739 31100 13750 31100 13659 31100 13734 31101 13751 31101 13735 31101 13751 31102 13734 31102 13743 31102 13734 31103 13739 31103 13741 31103 13741 31104 13752 31104 13746 31104 13752 243 13741 243 13750 243 13753 7838 13754 7838 13755 7838 13755 7838 13754 7838 13756 7838 13758 53 13753 53 13755 53 13759 8265 13757 8265 13760 8265 13760 8265 13757 8265 13758 8265 13756 6 13759 6 13760 6 13760 427 13758 427 13756 427 13756 427 13758 427 13755 427 13752 7838 13750 7838 13761 7838 13761 7838 13750 7838 13762 7838 13763 53 13742 53 13761 53 13752 53 13761 53 13747 53 13750 31105 13735 31105 13762 31105 13737 31106 13738 31106 13736 31106 13737 31107 13763 31107 13759 31107 13763 31108 13737 31108 13764 31108 13764 31109 13737 31109 13677 31109 13736 31110 13738 31110 13762 31110 13666 31111 13762 31111 13738 31111 13762 31112 13666 31112 13740 31112 13754 31113 13740 31113 13738 31113 13762 427 13740 427 13761 427 13753 31114 13761 31114 13754 31114 13753 427 13757 427 13761 427 13763 31115 13757 31115 13759 31115 13765 31116 13766 31116 13767 31116 13766 31117 13765 31117 13556 31117 13766 31118 13556 31118 13769 31118 13770 31119 13765 31119 13767 31119 13772 31120 13773 31120 13774 31120 13678 31121 13683 31121 13775 31121 13776 31122 13774 31122 13775 31122 13773 31123 13772 31123 13612 31123 13612 31124 13772 31124 13777 31124 13776 31125 13778 31125 13779 31125 13780 31126 13776 31126 13779 31126 13777 31127 13781 31127 13782 31127 13609 31128 13774 31128 13607 31128 13614 31129 13612 31129 13622 31129 13597 31130 13624 31130 13625 31130 13783 31131 13626 31131 13596 31131 13784 31132 13785 31132 13598 31132 13628 31133 13629 31133 13556 31133 13556 31134 13631 31134 13769 31134 13559 31135 13560 31135 13788 31135 13787 31136 13789 31136 13558 31136 13786 31137 13558 31137 13631 31137 13597 31138 13790 31138 13604 31138 13790 31139 13611 31139 13604 31139 13623 31140 13607 31140 13773 31140 13783 31141 13625 31141 13596 31141 13559 31142 13787 31142 13558 31142 13772 31143 13781 31143 13777 31143 13792 31144 13791 31144 13793 31144 13791 31145 13794 31145 13793 31145 13796 31146 13795 31146 13797 31146 13792 31147 13793 31147 13796 31147 13783 31148 13799 31148 13790 31148 13799 31149 13783 31149 13785 31149 13782 31150 13561 31150 13592 31150 13788 31151 13789 31151 13787 31151 13788 31152 13561 31152 13782 31152 13780 31153 13779 31153 13772 31153 13778 31154 13775 31154 13606 31154 13606 31155 13683 31155 13607 31155 13607 31156 13678 31156 13609 31156 13768 31157 13769 31157 13771 31157 13770 31158 13767 31158 13771 31158 13558 31159 13797 31159 13795 31159 13769 31160 13558 31160 13795 31160 13796 31161 13797 31161 13789 31161 13800 31162 13784 31162 13794 31162 13770 31163 13794 31163 13784 31163 13776 31164 13780 31164 13774 31164 13781 31165 13796 31165 13801 31165 13801 31166 13796 31166 13789 31166 13794 31167 13791 31167 13802 31167 13801 31168 13803 31168 13782 31168 13799 31169 13800 31169 13805 31169 13807 31170 13629 31170 13628 31170 13807 31171 13628 31171 13627 31171 13805 31172 13625 31172 13808 31172 13626 31173 13625 31173 13805 31173 13808 31174 13778 31174 13623 31174 13622 31175 13773 31175 13614 31175 13809 31176 13560 31176 13786 31176 13786 31177 13631 31177 13807 31177 13622 31178 13560 31178 13809 31178 13627 31179 13805 31179 13807 31179 13810 31180 13811 31180 13812 31180 13814 31181 13816 31181 13817 31181 13818 31182 13814 31182 13817 31182 13820 31183 13822 31183 13823 31183 13822 31184 13812 31184 13813 31184 10962 31185 13824 31185 11884 31185 13822 31186 13824 31186 13825 31186 13824 31187 11853 31187 13825 31187 13810 31188 13826 31188 13827 31188 13814 31189 13827 31189 11849 31189 10952 31190 11886 31190 13814 31190 11853 31191 11851 31191 13825 31191 13825 31192 11851 31192 13812 31192 13812 31193 11851 31193 13826 31193 11851 31194 11848 31194 13826 31194 13814 31195 11886 31195 13828 31195 13815 31196 13828 31196 13819 31196 11886 31197 11885 31197 13828 31197 13828 31198 10960 31198 13819 31198 11885 31199 11884 31199 10960 31199 13819 31200 10960 31200 13824 31200 13814 31201 13818 31201 13827 31201 13829 31202 13830 31202 13831 31202 13830 31203 11855 31203 13831 31203 13833 31204 13834 31204 13835 31204 13836 31205 13837 31205 13838 31205 13832 31206 13833 31206 13831 31206 13839 31207 13836 31207 13844 31207 13844 31208 13836 31208 13842 31208 13842 31209 13841 31209 13844 31209 13845 31210 13836 31210 13838 31210 13846 31211 13847 31211 13834 31211 13834 31212 13847 31212 13848 31212 13850 31213 13847 31213 13851 31213 13829 31214 13853 31214 13830 31214 13829 31215 13854 31215 13853 31215 13853 31216 13854 31216 13855 31216 13856 31217 13855 31217 13857 31217 13853 31218 13855 31218 13856 31218 13856 31219 13857 31219 13839 31219 13853 31220 13846 31220 13830 31220 13837 31221 13840 31221 13843 31221 13837 31222 13843 31222 13842 31222 13838 31223 13840 31223 13859 31223 13838 31224 13859 31224 11883 31224 13843 31225 13838 31225 13845 31225 13852 31226 13843 31226 11883 31226 13846 31227 13834 31227 13833 31227 13830 31228 13846 31228 11855 31228 13835 31229 13860 31229 13832 31229 13861 31230 13832 31230 13860 31230 13861 31231 13829 31231 13832 31231 13866 31232 13851 31232 13867 31232 13867 31233 13868 31233 13866 31233 13869 31234 13846 31234 13853 31234 13871 31235 13856 31235 13839 31235 13873 31236 13853 31236 13870 31236 11883 31237 11878 31237 13852 31237 13852 31238 11878 31238 13858 31238 13850 31239 11871 31239 13849 31239 13860 31240 13848 31240 13849 31240 11870 31241 11878 31241 11879 31241 13850 31242 13858 31242 11870 31242 13874 31243 11872 31243 13875 31243 13876 31244 11880 31244 11871 31244 13877 31245 13878 31245 11875 31245 11875 31246 13878 31246 13875 31246 13878 31247 13874 31247 13875 31247 11868 31248 13879 31248 13877 31248 11871 31249 11870 31249 13881 31249 13877 31250 11875 31250 11868 31250 13880 31251 11870 31251 13882 31251 13882 31252 11870 31252 11879 31252 13876 31253 13883 31253 11880 31253 13873 31254 13885 31254 13886 31254 13869 53 13886 53 13887 53 13869 31255 13887 31255 13888 31255 13866 31256 13868 31256 13890 31256 13869 31257 13873 31257 13886 31257 13873 31258 13870 31258 13884 31258 13817 31259 13872 31259 13818 31259 13817 31260 13816 31260 13871 31260 13871 31261 13816 31261 13877 31261 13874 31262 13884 31262 13879 31262 13874 31263 13885 31263 13884 31263 13815 31264 13877 31264 13816 31264 13887 31265 13821 31265 13820 31265 13889 31266 13823 31266 13822 31266 13876 31267 13889 31267 13822 31267 13876 31268 13881 31268 13890 31268 13880 31269 13890 31269 13881 31269 13880 31270 13882 31270 13811 31270 13811 31271 13882 31271 13813 31271 13813 31272 13876 31272 13822 31272 13886 31273 13821 31273 13887 31273 13888 31274 13823 31274 13889 31274 13864 31275 13811 31275 13810 31275 13864 31276 13810 31276 13872 31276 10962 31277 11884 31277 13861 31277 13860 31278 10962 31278 13861 31278 11851 31279 11882 31279 11880 31279 11885 31280 13891 31280 11884 31280 11875 31281 11885 31281 11886 31281 13859 31282 11886 31282 10952 31282 11849 31283 13859 31283 10952 31283 11875 31284 11886 31284 13859 31284 11848 31285 11851 31285 11878 31285 13859 31286 13857 31286 11868 31286 13891 31287 13829 31287 13861 31287 13892 31288 13878 31288 13893 31288 13892 31289 13894 31289 13878 31289 13894 31290 13895 31290 13896 31290 13874 31291 13894 31291 13878 31291 13896 31292 13895 31292 13898 31292 13902 31293 13901 31293 13903 31293 13904 31294 13902 31294 13903 31294 13876 31295 13905 31295 13904 31295 13876 31296 13883 31296 13905 31296 13898 31297 13899 31297 13900 31297 13900 31298 13901 31298 13902 31298 13903 31299 13906 31299 13904 31299 13904 31300 13906 31300 13883 31300 13883 31301 13906 31301 13907 31301 13910 31302 13908 31302 13911 31302 13914 31303 13913 31303 13915 31303 13916 31304 13914 31304 13915 31304 13916 31305 13897 31305 13914 31305 13912 31306 13913 31306 13914 31306 13915 31307 13893 31307 13916 31307 13883 31308 13882 31308 13905 31308 13897 31309 13902 31309 13905 31309 13902 6 13896 6 13900 6 13897 31310 13905 31310 13909 31310 13912 31311 13914 31311 13910 31311 13897 31312 13909 31312 13914 31312 13882 31313 13917 31313 13907 31313 13883 31314 13917 31314 13882 31314 13907 31315 13917 31315 13883 31315 13883 31316 13917 31316 13918 31316 13904 31317 13883 31317 13918 31317 13876 31318 13904 31318 13918 31318 13883 31319 13876 31319 13918 31319 13878 31320 13919 31320 13874 31320 13894 31321 13874 31321 13920 31321 13921 31322 13919 31322 13878 31322 13916 31323 13921 31323 13877 31323 13920 31324 13919 31324 13894 31324 13894 31325 13919 31325 13878 31325 13919 31326 13922 31326 13916 31326 13923 31327 13921 31327 13916 31327 13877 31328 13921 31328 13878 31328 13924 31329 13926 31329 13925 31329 13925 31330 13923 31330 13928 31330 13926 31331 13924 31331 13927 31331 13923 31332 13926 31332 13921 31332 13923 31333 13929 31333 13928 31333 13926 31334 13919 31334 13921 31334 13927 31335 13930 31335 13931 31335 13932 31336 13918 31336 13917 31336 13931 31337 13892 31337 13920 31337 13893 31338 13919 31338 13892 31338 13920 31339 13919 31339 13926 31339 13903 31340 13930 31340 13932 31340 13908 31341 13932 31341 13928 31341 13915 31342 13929 31342 13893 31342 13908 31343 13906 31343 13932 31343 13933 31344 13934 31344 13935 31344 13936 31345 13937 31345 13938 31345 13939 31346 13940 31346 13941 31346 13941 31347 13940 31347 13942 31347 13939 6 13941 6 13943 6 13945 31348 13943 31348 13946 31348 13946 31349 13943 31349 13944 31349 13940 31350 13946 31350 13942 31350 13947 31351 13940 31351 13948 31351 13947 31352 13945 31352 13940 31352 13947 31353 13949 31353 13943 31353 13948 31354 13939 31354 13950 31354 13948 31355 13940 31355 13939 31355 13951 31356 13952 31356 13947 31356 13947 31357 13952 31357 13949 31357 13953 31358 13942 31358 13951 31358 13953 31359 13954 31359 13941 31359 13944 31360 13952 31360 13951 31360 13948 31361 13950 31361 13953 31361 13953 31362 13950 31362 13954 31362 13947 6 13953 6 13951 6 13856 31363 13853 31363 13862 31363 13862 31364 13853 31364 13863 31364 13866 31365 13851 31365 13865 31365 13872 31366 13841 31366 13844 31366 13856 31367 13870 31367 13871 31367 13886 31368 13853 31368 13830 31368 13865 31369 13851 31369 13864 31369 13885 31370 13853 31370 13886 31370 13886 31371 13830 31371 13887 31371 13889 31372 13867 31372 13866 31372 13885 31373 13870 31373 13853 31373 13888 31374 13950 31374 13887 31374 13888 31375 13889 31375 13950 31375 13950 31376 13889 31376 13866 31376 13866 31377 13954 31377 13950 31377 13866 31378 13865 31378 13954 31378 13872 31379 13954 31379 13864 31379 13952 31380 13872 31380 13871 31380 13949 31381 13870 31381 13885 31381 13886 31382 13949 31382 13885 31382 13830 31383 13958 31383 13957 31383 13863 31384 13959 31384 13957 31384 13862 31385 13959 31385 13863 31385 13862 31386 13960 31386 13959 31386 13960 31387 13862 31387 13839 31387 13867 31388 13963 31388 13965 31388 13867 31389 13966 31389 13963 31389 13867 31390 13968 31390 13967 31390 13967 31391 13968 31391 13834 31391 13955 31392 13834 31392 13956 31392 13834 31393 13968 31393 13851 31393 13851 31394 13968 31394 13965 31394 13851 31395 13964 31395 13841 31395 13969 31396 13937 31396 13970 31396 13970 31397 13933 31397 13969 31397 13933 31398 13970 31398 13963 31398 13963 31399 13966 31399 13933 31399 13936 31400 13957 31400 13959 31400 13963 31401 13970 31401 13961 31401 13936 31402 13959 31402 13937 31402 13971 31403 13972 31403 13973 31403 13971 31404 13974 31404 13972 31404 13976 31405 13975 31405 13977 31405 13978 31406 13973 31406 13979 31406 13980 31407 13975 31407 13976 31407 13976 31408 13978 31408 13979 31408 13981 31409 13971 31409 1089 31409 13982 31410 13983 31410 1093 31410 1094 31411 1093 31411 13983 31411 1091 31412 13982 31412 1093 31412 1088 31413 13984 31413 1089 31413 13985 31414 13973 31414 13986 31414 13990 31415 13989 31415 13991 31415 13992 31416 13991 31416 13979 31416 13986 31417 13987 31417 13988 31417 13988 31418 13989 31418 13993 31418 13993 31419 13989 31419 13990 31419 13990 31420 13991 31420 13992 31420 13972 31421 13989 31421 13987 31421 13976 31422 13979 31422 13991 31422 840 31423 1179 31423 1116 31423 840 31424 13994 31424 1179 31424 13995 31425 1179 31425 13994 31425 839 31426 1097 31426 13995 31426 1179 31427 13995 31427 1178 31427 1097 31428 13996 31428 1116 31428 1116 31429 13996 31429 13997 31429 837 31430 13998 31430 838 31430 13982 31431 838 31431 13998 31431 13998 31432 837 31432 14000 31432 1085 31433 1176 31433 1177 31433 832 31434 833 31434 14004 31434 14004 31435 1177 31435 1176 31435 14003 31436 833 31436 13981 31436 833 31437 832 31437 13981 31437 13981 31438 832 31438 13971 31438 14006 31439 14007 31439 14008 31439 14010 31440 14012 31440 14013 31440 14016 31441 14013 31441 14017 31441 14007 31442 14018 31442 14016 31442 14019 31443 14007 31443 14006 31443 14020 31444 13996 31444 1097 31444 14023 31445 14024 31445 14025 31445 14024 31446 13997 31446 14026 31446 14030 31447 14023 31447 14031 31447 14027 31448 14033 31448 14024 31448 14031 31449 14029 31449 14030 31449 13996 31450 14026 31450 13997 31450 14015 31451 14034 31451 14014 31451 1116 31452 13997 31452 14034 31452 14034 31453 13997 31453 14014 31453 14018 31454 1062 31454 14035 31454 840 31455 1116 31455 13994 31455 14036 31456 14016 31456 14035 31456 14038 31457 14007 31457 14017 31457 14017 31458 14012 31458 14011 31458 14017 31459 14013 31459 14012 31459 14039 31460 14021 31460 14022 31460 14040 31461 14030 31461 14029 31461 14042 31462 14022 31462 14023 31462 14042 31463 14023 31463 14041 31463 14044 31464 14049 31464 14045 31464 14049 31465 14048 31465 14050 31465 14040 31466 14047 31466 14046 31466 14040 31467 14046 31467 14041 31467 14051 31468 14047 31468 14052 31468 14051 31469 14052 31469 14043 31469 14051 31470 14043 31470 14045 31470 14021 31471 14053 31471 14040 31471 14009 31472 14045 31472 14006 31472 14009 31473 14048 31473 14051 31473 14009 31474 14055 31474 14054 31474 14009 31475 14056 31475 14055 31475 14058 31476 14059 31476 14056 31476 14058 31477 14019 31477 14060 31477 14060 31478 14019 31478 14050 31478 14055 31479 14057 31479 14062 31479 14056 31480 14063 31480 14057 31480 14049 31481 14041 31481 14046 31481 14049 31482 14044 31482 14042 31482 14047 31483 14040 31483 14052 31483 14061 31484 14064 31484 14050 31484 14066 31485 14060 31485 14050 31485 14067 31486 14068 31486 14062 31486 14062 31487 14068 31487 14055 31487 14067 31488 14062 31488 14069 31488 14060 31489 14066 31489 14062 31489 14066 31490 14069 31490 14062 31490 14070 31491 14031 31491 14025 31491 14065 31492 14070 31492 14064 31492 14032 31493 14072 31493 14033 31493 14033 31494 14071 31494 14024 31494 14055 31495 14073 31495 14054 31495 14074 31496 14029 31496 14031 31496 14031 31497 14070 31497 14074 31497 14065 31498 14054 31498 14073 31498 14067 31499 14032 31499 14068 31499 14025 31500 14071 31500 14064 31500 14070 31501 14065 31501 14074 31501 14071 31502 14072 31502 14066 31502 14079 31503 14080 31503 14028 31503 14026 31504 13996 31504 14080 31504 14081 31505 14082 31505 14024 31505 14075 31506 14077 31506 14081 31506 14083 31507 14084 31507 14085 31507 14028 31508 14086 31508 14078 31508 14027 31509 14086 31509 14028 31509 14082 31510 14086 31510 14024 31510 14086 31511 14027 31511 14024 31511 14083 31512 14087 31512 14059 31512 14079 31513 14087 31513 14080 31513 14088 31514 14082 31514 14089 31514 14090 31515 14083 31515 14060 31515 14091 31516 14092 31516 14057 31516 14086 31517 14092 31517 14091 31517 14089 31518 14092 31518 14088 31518 14057 31519 14092 31519 14089 31519 14076 31520 14085 31520 14084 31520 14077 31521 14076 31521 14084 31521 14084 31522 14083 31522 14077 31522 14086 31523 14091 31523 14078 31523 14080 31524 14085 31524 14076 31524 14083 31525 14090 31525 14077 31525 14077 31526 14090 31526 14081 31526 14058 31527 1062 31527 14093 31527 14056 31528 14008 31528 1085 31528 13977 31529 13975 31529 14094 31529 14038 31530 14095 31530 14008 31530 14008 31531 14095 31531 1085 31531 14038 31532 14094 31532 13975 31532 14002 31533 513 31533 14096 31533 14097 31534 14037 31534 14096 31534 14097 31535 13999 31535 14037 31535 13999 31536 13994 31536 14037 31536 1084 31537 1063 31537 13984 31537 1088 31538 513 31538 1084 31538 13985 6 1089 6 13992 6 14097 31539 13993 31539 13990 31539 1093 31540 13990 31540 13992 31540 511 31541 13990 31541 1093 31541 1093 31542 1094 31542 511 31542 1115 31543 13983 31543 14001 31543 14098 31544 14101 31544 14099 31544 14105 31545 14103 31545 14104 31545 14107 31546 14102 31546 14103 31546 14103 31547 14105 31547 14106 31547 2937 31548 14105 31548 2939 31548 2939 31549 14105 31549 2687 31549 2942 31550 2941 31550 14110 31550 2687 31551 14105 31551 14104 31551 2936 31552 14111 31552 2937 31552 2937 31553 14111 31553 14108 31553 14113 31554 14100 31554 14114 31554 14115 31555 14114 31555 14116 31555 14115 31556 14116 31556 14119 31556 14114 31557 14100 31557 14099 31557 14099 31558 14107 31558 14116 31558 14103 31559 14106 31559 14120 31559 2690 31560 14121 31560 3029 31560 2965 31561 3028 31561 2945 31561 14122 31562 3029 31562 14121 31562 3029 31563 14122 31563 3028 31563 2945 31564 14123 31564 2965 31564 2965 31565 14123 31565 14124 31565 2688 31566 14125 31566 2687 31566 14126 31567 14127 31567 2688 31567 14127 31568 14126 31568 14128 31568 14128 31569 14109 31569 14125 31569 2690 31570 14126 31570 2687 31570 2689 31571 2687 31571 14104 31571 2689 31572 2690 31572 2687 31572 2934 31573 3026 31573 2912 31573 14131 31574 2683 31574 14132 31574 14131 31575 3027 31575 3025 31575 14132 31576 2683 31576 3026 31576 2683 31577 2682 31577 14108 31577 14108 31578 2682 31578 14098 31578 14133 31579 14134 31579 14135 31579 14137 31580 14138 31580 14139 31580 14137 31581 14139 31581 14140 31581 14141 31582 14140 31582 14142 31582 14134 31583 14145 31583 14143 31583 14146 31584 14134 31584 14133 31584 14137 31585 14123 31585 14147 31585 14123 31586 14153 31586 14154 31586 14123 31587 14137 31587 14153 31587 14153 31588 14137 31588 14155 31588 14156 31589 14150 31589 14157 31589 14159 31590 14160 31590 14153 31590 14153 31591 14160 31591 14151 31591 14157 31592 14155 31592 14156 31592 14123 31593 14152 31593 14124 31593 14142 31594 14161 31594 14141 31594 14161 31595 14142 31595 2965 31595 14142 31596 14143 31596 14163 31596 14121 31597 14163 31597 14164 31597 2683 31598 14132 31598 2912 31598 14145 31599 2912 31599 14162 31599 2965 31600 14142 31600 14163 31600 14164 31601 14162 31601 2912 31601 2965 31602 14163 31602 14121 31602 14144 31603 14138 31603 14165 31603 14144 31604 14140 31604 14139 31604 14156 31605 14167 31605 14168 31605 14156 31606 14168 31606 14169 31606 14150 31607 14156 31607 14169 31607 14170 31608 14171 31608 14172 31608 14171 31609 14176 31609 14172 31609 14167 31610 14174 31610 14173 31610 14170 31611 14149 31611 14171 31611 14148 31612 14180 31612 14167 31612 14136 31613 14172 31613 14133 31613 14136 31614 14175 31614 14178 31614 14136 31615 14183 31615 14182 31615 14185 31616 14186 31616 14183 31616 14177 31617 14175 31617 14188 31617 14189 31618 14184 31618 14187 31618 14186 31619 14190 31619 14183 31619 14183 31620 14190 31620 14184 31620 14169 31621 14168 31621 14176 31621 14176 31622 14168 31622 14173 31622 14176 31623 14171 31623 14169 31623 14169 31624 14171 31624 14149 31624 14179 31625 14167 31625 14180 31625 14170 31626 14179 31626 14166 31626 14191 31627 14192 31627 14151 31627 14193 31628 14188 31628 14194 31628 14195 31629 14187 31629 14177 31629 14189 31630 14197 31630 14182 31630 14196 31631 14189 31631 14198 31631 14192 31632 14158 31632 14150 31632 14157 31633 14158 31633 14194 31633 14194 31634 14158 31634 14193 31634 14160 31635 14199 31635 14191 31635 14155 31636 14201 31636 14159 31636 14194 31637 14181 31637 14200 31637 14199 31638 14159 31638 14196 31638 14196 31639 14159 31639 14197 31639 14192 31640 14191 31640 14193 31640 14157 31641 14194 31641 14201 31641 14191 31642 14199 31642 14195 31642 14195 31643 14199 31643 14198 31643 14201 31644 14200 31644 14159 31644 14202 31645 14203 31645 14204 31645 14206 31646 14207 31646 14154 31646 14202 31647 14151 31647 14152 31647 14210 31648 14211 31648 14212 31648 14153 31649 14213 31649 14154 31649 14209 31650 14213 31650 14151 31650 14214 31651 14190 31651 14186 31651 14210 31652 14212 31652 14214 31652 14206 31653 14214 31653 14207 31653 14209 31654 14217 31654 14216 31654 14217 31655 14187 31655 14216 31655 14210 31656 14186 31656 14187 31656 14190 31657 14218 31657 14184 31657 14213 31658 14219 31658 14218 31658 14216 31659 14219 31659 14215 31659 14184 31660 14219 31660 14216 31660 14209 31661 14208 31661 14217 31661 14203 31662 14212 31662 14211 31662 14211 31663 14210 31663 14204 31663 14205 31664 14218 31664 14206 31664 14213 31665 14215 31665 14219 31665 14207 31666 14212 31666 14203 31666 14185 31667 14220 31667 14146 31667 14183 31668 14136 31668 14135 31668 14104 31669 14102 31669 14221 31669 14165 31670 14102 31670 14222 31670 14101 31671 14222 31671 14102 31671 14135 31672 14222 31672 2934 31672 14101 31673 14098 31673 2682 31673 14138 31674 14221 31674 14165 31674 14221 31675 2689 31675 14104 31675 2913 31676 2367 31676 14129 31676 14129 31677 2367 31677 14223 31677 14129 31678 14223 31678 14130 31678 14224 31679 14164 31679 14223 31679 14224 31680 14128 31680 14126 31680 14126 31681 14121 31681 14164 31681 14132 31682 14130 31682 14164 31682 2936 31683 2367 31683 2933 31683 2933 31684 2367 31684 2913 31684 2937 31685 14112 31685 2936 31685 2936 6 14112 6 14113 6 2367 31686 14113 31686 14115 31686 14119 6 14223 6 14115 6 14119 31687 14224 31687 14223 31687 14224 6 14119 6 14117 6 14112 31688 2939 31688 14120 31688 2941 31689 2942 31689 2365 31689 2365 31690 2942 31690 2964 31690 2942 31691 14110 31691 2964 31691 14225 31692 14226 31692 14227 31692 14225 31693 14228 31693 14226 31693 14226 31694 14228 31694 14229 31694 14232 31695 14227 31695 14233 31695 14232 31696 14225 31696 14227 31696 14230 31697 14232 31697 14233 31697 14235 31698 14225 31698 4790 31698 14236 31699 4792 31699 4523 31699 4795 31700 4794 31700 14237 31700 4792 31701 14236 31701 4794 31701 14241 31702 14227 31702 14242 31702 14243 31703 14242 31703 14244 31703 14245 31704 14246 31704 14247 31704 14242 31705 14227 31705 14226 31705 14226 31706 14244 31706 14242 31706 14246 31707 14234 31707 14230 31707 14230 31708 14233 31708 14246 31708 4818 31709 4881 31709 4798 31709 4798 31710 14251 31710 4818 31710 4818 31711 14251 31711 14252 31711 4522 31712 14253 31712 4523 31712 14254 31713 4522 31713 4523 31713 14255 31714 14256 31714 14253 31714 14236 31715 4523 31715 14253 31715 14253 31716 4522 31716 14255 31716 14256 31717 14236 31717 14253 31717 14249 31718 14254 31718 4525 31718 4525 31719 14254 31719 4523 31719 4524 31720 4525 31720 4523 31720 14235 31721 14238 31721 14257 31721 14258 31722 14257 31722 14238 31722 4517 31723 14259 31723 4878 31723 14259 31724 4518 31724 14260 31724 4880 31725 14260 31725 4879 31725 14259 31726 4880 31726 4878 31726 14259 31727 14260 31727 4880 31727 14260 31728 4518 31728 4879 31728 14257 31729 14260 31729 4518 31729 4518 31730 4517 31730 14235 31730 14261 31731 14262 31731 14263 31731 14263 31732 14264 31732 14261 31732 14265 31733 14267 31733 14268 31733 14269 31734 14268 31734 14270 31734 14262 31735 14271 31735 14272 31735 14265 31736 14275 31736 14266 31736 14266 31737 14275 31737 4798 31737 14265 31738 14251 31738 14275 31738 14268 31739 14276 31739 14265 31739 14268 31740 14269 31740 14276 31740 14276 31741 14269 31741 14277 31741 14277 31742 14269 31742 14278 31742 14277 31743 14278 31743 14279 31743 14251 31744 14281 31744 14282 31744 14284 31745 14277 31745 14285 31745 14286 31746 14287 31746 14281 31746 14281 31747 14287 31747 14288 31747 14276 31748 14289 31748 14265 31748 14290 31749 14252 31749 14269 31749 14271 31750 14273 31750 14291 31750 14270 31751 14271 31751 14292 31751 14260 31752 14293 31752 4765 31752 14263 31753 14262 31753 14294 31753 14272 31754 14268 31754 14267 31754 14297 31755 14284 31755 14283 31755 14284 31756 14297 31756 14298 31756 14299 31757 14276 31757 14277 31757 14284 31758 14298 31758 14277 31758 14299 31759 14277 31759 14298 31759 14300 31760 14301 31760 14302 31760 14303 31761 14304 31761 14305 31761 14301 31762 14306 31762 14302 31762 14297 31763 14304 31763 14303 31763 14297 31764 14303 31764 14298 31764 14309 31765 14304 31765 14310 31765 14309 31766 14310 31766 14300 31766 14309 31767 14300 31767 14302 31767 14289 31768 14311 31768 14297 31768 14289 31769 14297 31769 14283 31769 14276 31770 14296 31770 14289 31770 14264 31771 14302 31771 14261 31771 14264 31772 14312 31772 14305 31772 14264 31773 14313 31773 14312 31773 14316 31774 14317 31774 14314 31774 14316 31775 14307 31775 14317 31775 14316 31776 14274 31776 14307 31776 14261 31777 14302 31777 14274 31777 14313 31778 14315 31778 14318 31778 14318 31779 14315 31779 14319 31779 14314 31780 14320 31780 14315 31780 14274 31781 14302 31781 14307 31781 14306 31782 14301 31782 14299 31782 14304 31783 14297 31783 14310 31783 14321 31784 14319 31784 14307 31784 14288 31785 14322 31785 14278 31785 14308 31786 14323 31786 14307 31786 14324 31787 14325 31787 14318 31787 14319 31788 14321 31788 14318 31788 14321 31789 14326 31789 14318 31789 14327 31790 14285 31790 14279 31790 14287 31791 14322 31791 14288 31791 14329 31792 14330 31792 14312 31792 14313 31793 14325 31793 14329 31793 14283 31794 14331 31794 14286 31794 14287 31795 14324 31795 14326 31795 14287 31796 14286 31796 14324 31796 14279 31797 14322 31797 14323 31797 14323 31798 14322 31798 14321 31798 14327 31799 14323 31799 14331 31799 14331 31800 14323 31800 14330 31800 14322 31801 14287 31801 14321 31801 14286 31802 14329 31802 14325 31802 14282 31803 14337 31803 14251 31803 14333 31804 14332 31804 14280 31804 14280 31805 14251 31805 14337 31805 14332 31806 14334 31806 14338 31806 14278 31807 14332 31807 14338 31807 14282 31808 14340 31808 14335 31808 14281 31809 14340 31809 14282 31809 14339 31810 14340 31810 14288 31810 14341 31811 14336 31811 14320 31811 14342 31812 14343 31812 14341 31812 14336 31813 14341 31813 14337 31813 14319 31814 14346 31814 14307 31814 14345 31815 14347 31815 14346 31815 14346 31816 14317 31816 14307 31816 14320 31817 14348 31817 14315 31817 14340 31818 14349 31818 14348 31818 14346 31819 14349 31819 14344 31819 14315 31820 14346 31820 14319 31820 14339 31821 14338 31821 14345 31821 14334 31822 14333 31822 14342 31822 14335 31823 14348 31823 14336 31823 14340 31824 14344 31824 14349 31824 14341 31825 14343 31825 14337 31825 14337 31826 14343 31826 14333 31826 14334 31827 14347 31827 14338 31827 14316 31828 4765 31828 14350 31828 4765 31829 14273 31829 14350 31829 14314 31830 14264 31830 14263 31830 4787 31831 4765 31831 14314 31831 14314 31832 4765 31832 14316 31832 4524 31833 14351 31833 4798 31833 14231 31834 14229 31834 14351 31834 14294 31835 14229 31835 14352 31835 14228 31836 14352 31836 14229 31836 14352 31837 14228 31837 4787 31837 4787 31838 14228 31838 4517 31838 14266 31839 4798 31839 14351 31839 14351 31840 4524 31840 14231 31840 4766 31841 4202 31841 14258 31841 14258 31842 4202 31842 14353 31842 14354 31843 14293 31843 14353 31843 14354 31844 14256 31844 14254 31844 14254 31845 14249 31845 14293 31845 14260 31846 14257 31846 14293 31846 14239 31847 4766 31847 14258 31847 4789 31848 4202 31848 4786 31848 14240 31849 4790 31849 14247 31849 4790 31850 14240 31850 4789 31850 4794 6 14245 6 14247 6 4789 6 14241 6 4202 6 4202 31851 14243 31851 14353 31851 4200 31852 14245 31852 4794 31852 4794 6 14247 6 4792 6 14355 31853 14356 31853 14357 31853 14356 31854 14358 31854 14359 31854 14356 31855 14359 31855 14360 31855 14363 31856 14362 31856 14364 31856 6651 31857 14355 31857 14362 31857 6653 31858 14362 31858 6382 31858 14366 31859 6653 31859 6382 31859 14366 31860 14367 31860 6655 31860 6656 31861 6655 31861 14367 31861 6653 31862 14366 31862 6655 31862 6650 31863 14368 31863 6651 31863 6650 31864 14369 31864 14368 31864 6651 31865 14368 31865 14365 31865 14364 31866 14357 31866 14370 31866 14372 31867 14356 31867 14373 31867 14374 31868 14373 31868 14375 31868 14376 31869 14375 31869 14363 31869 14370 31870 14363 31870 14364 31870 14371 31871 14356 31871 14372 31871 14374 31872 14375 31872 14377 31872 14377 31873 14375 31873 14376 31873 14356 31874 14360 31874 14373 31874 14373 31875 14360 31875 14375 31875 6384 31876 6740 31876 6677 31876 6384 31877 14378 31877 6740 31877 6677 31878 6740 31878 6659 31878 14378 31879 6384 31879 6383 31879 14379 31880 6740 31880 14378 31880 6659 31881 14380 31881 6677 31881 6677 31882 14380 31882 14381 31882 6381 31883 14382 31883 6382 31883 14383 31884 6381 31884 6382 31884 14384 31885 14383 31885 14385 31885 14366 31886 6382 31886 14382 31886 14382 31887 6381 31887 14384 31887 14385 31888 14366 31888 14382 31888 6384 31889 14383 31889 6382 31889 6383 31890 6382 31890 14361 31890 6383 31891 6384 31891 6382 31891 14365 31892 14368 31892 14386 31892 6647 31893 6739 31893 6624 31893 6376 31894 14388 31894 6738 31894 6376 31895 6377 31895 14388 31895 14388 31896 6377 31896 14389 31896 14388 31897 14389 31897 6739 31897 6377 31898 6376 31898 14365 31898 14365 31899 6376 31899 14355 31899 14390 31900 14391 31900 14392 31900 14392 31901 14393 31901 14390 31901 14394 31902 14395 31902 14396 31902 14398 31903 14397 31903 14399 31903 14400 31904 14397 31904 14401 31904 14395 31905 14404 31905 6659 31905 14397 31906 14405 31906 14394 31906 14406 31907 14398 31907 14407 31907 14407 31908 14398 31908 14381 31908 14407 31909 14410 31909 14411 31909 14380 31910 14412 31910 14413 31910 14412 31911 14394 31911 14414 31911 14416 31912 14406 31912 14408 31912 14417 31913 14418 31913 14412 31913 14380 31914 14409 31914 14381 31914 14420 31915 14381 31915 14398 31915 14400 31916 14402 31916 14421 31916 14399 31917 14400 31917 14422 31917 14389 31918 14423 31918 6624 31918 14402 31919 6624 31919 14421 31919 14422 31920 14421 31920 14423 31920 6384 31921 6677 31921 14378 31921 14423 31922 14421 31922 6624 31922 6677 31923 14422 31923 14378 31923 14424 31924 14391 31924 14401 31924 14401 31925 14397 31925 14396 31925 14427 31926 14415 31926 14414 31926 14415 31927 14427 31927 14428 31927 14415 31928 14428 31928 14406 31928 14429 31929 14406 31929 14428 31929 14430 31930 14431 31930 14432 31930 14433 31931 14434 31931 14435 31931 14431 31932 14436 31932 14432 31932 14435 31933 14436 31933 14433 31933 14427 31934 14433 31934 14428 31934 14435 31935 14434 31935 14438 31935 14438 31936 14439 31936 14430 31936 14430 31937 14425 31937 14431 31937 14419 31938 14440 31938 14427 31938 14405 31939 14426 31939 14419 31939 14393 31940 14432 31940 14390 31940 14393 31941 14441 31941 14435 31941 14393 31942 14442 31942 14441 31942 14445 31943 14447 31943 14446 31943 14445 31944 14403 31944 14447 31944 14447 31945 14403 31945 14437 31945 14437 31946 14435 31946 14441 31946 14448 31947 14437 31947 14441 31947 14442 31948 14444 31948 14449 31948 14449 31949 14444 31949 14447 31949 14403 31950 14432 31950 14437 31950 14436 31951 14428 31951 14433 31951 14436 31952 14431 31952 14429 31952 14429 31953 14431 31953 14425 31953 14439 31954 14427 31954 14440 31954 14430 31955 14439 31955 14426 31955 14426 31956 14439 31956 14440 31956 14411 31957 14451 31957 14407 31957 14456 31958 14447 31958 14437 31958 14454 31959 14456 31959 14437 31959 14449 31960 14458 31960 14442 31960 14447 31961 14456 31961 14449 31961 14460 31962 14416 31962 14408 31962 14455 31963 14460 31963 14454 31963 14408 31964 14454 31964 14460 31964 14417 31965 14461 31965 14418 31965 14418 31966 14452 31966 14411 31966 14442 31967 14462 31967 14441 31967 14442 31968 14458 31968 14462 31968 14414 31969 14463 31969 14417 31969 14463 31970 14414 31970 14416 31970 14441 31971 14462 31971 14448 31971 14461 31972 14457 31972 14459 31972 14461 31973 14417 31973 14457 31973 14408 31974 14451 31974 14454 31974 14454 31975 14451 31975 14456 31975 14453 31976 14461 31976 14456 31976 14417 31977 14462 31977 14458 31977 14464 31978 14465 31978 14413 31978 14465 31979 14466 31979 14413 31979 14413 31980 14466 31980 14380 31980 14467 31981 14468 31981 14409 31981 14409 31982 14380 31982 14466 31982 14466 31983 14467 31983 14409 31983 14410 31984 14469 31984 14470 31984 14413 31985 14471 31985 14464 31985 14412 31986 14471 31986 14413 31986 14470 31987 14471 31987 14411 31987 14471 31988 14412 31988 14411 31988 14472 31989 14450 31989 14446 31989 14472 31990 14465 31990 14450 31990 14475 31991 14476 31991 14477 31991 14477 31992 14473 31992 14447 31992 14473 31993 14477 31993 14476 31993 14478 31994 14479 31994 14444 31994 14471 31995 14479 31995 14478 31995 14477 31996 14479 31996 14475 31996 14479 31997 14477 31997 14444 31997 14444 31998 14477 31998 14447 31998 14476 31999 14470 31999 14469 31999 14468 32000 14467 32000 14474 32000 14464 32001 14478 32001 14465 32001 14466 32002 14474 32002 14467 32002 14468 32003 14476 32003 14469 32003 14445 32004 6624 32004 14480 32004 6624 32005 14402 32005 14480 32005 14443 32006 14392 32006 6647 32006 14443 32007 14393 32007 14392 32007 6647 32008 6624 32008 14443 32008 14443 32009 6624 32009 14445 32009 14361 32010 14359 32010 14481 32010 14358 32011 14355 32011 6376 32011 14395 32012 14481 32012 14424 32012 14395 32013 6659 32013 14481 32013 6625 32014 6062 32014 14387 32014 14387 32015 6062 32015 14483 32015 14387 32016 14483 32016 14386 32016 14484 32017 14423 32017 14483 32017 14484 32018 6060 32018 14385 32018 14385 32019 6060 32019 6676 32019 14383 32020 14378 32020 14423 32020 14389 32021 14386 32021 14423 32021 14369 32022 6625 32022 14387 32022 6650 32023 6062 32023 6646 32023 6646 32024 6062 32024 6625 32024 6651 6 14370 6 6650 6 14372 32025 14484 32025 14483 32025 14372 6 14374 6 14484 6 6060 32026 14374 32026 14377 32026 14370 32027 6653 32027 14376 32027 14370 6 6651 6 6653 6 6650 6 14371 6 6062 6 14484 6 14374 6 6060 6 6060 32028 14377 32028 6655 32028 6060 32029 6656 32029 6676 32029 7910 32030 14486 32030 14487 32030 7907 32031 14488 32031 7905 32031 7901 32032 14485 32032 7903 32032 14491 32033 7901 32033 14489 32033 7907 32034 14492 32034 14493 32034 7910 32035 7907 32035 14493 32035 7901 32036 7903 32036 14489 32036 14486 32037 14485 32037 14488 32037 14491 32038 14495 32038 14492 32038 14495 32039 14496 32039 14492 32039 14494 32040 14498 32040 14490 32040 14490 32041 14498 32041 14495 32041 14489 32042 14490 32042 14495 32042 14496 32043 14495 32043 14498 32043 14492 32044 14496 32044 14497 32044 7740 32045 14500 32045 14501 32045 7731 32046 14502 32046 14503 32046 7728 32047 14503 32047 14499 32047 7749 32048 7728 32048 14499 32048 7745 32049 14500 32049 7740 32049 7740 32050 14501 32050 7735 32050 7733 32051 14501 32051 7732 32051 7732 32052 14502 32052 7731 32052 7731 32053 14503 32053 7728 32053 7749 32054 14504 32054 7728 32054 14506 32055 7747 32055 7745 32055 14506 32056 7745 32056 7740 32056 14507 32057 7740 32057 7735 32057 14508 32058 7731 32058 7728 32058 7732 32059 14508 32059 14509 32059 7732 32060 14509 32060 7733 32060 14500 32061 14503 32061 14502 32061 14510 32062 14511 32062 14509 32062 14507 32063 14509 32063 14512 32063 14504 32064 14505 32064 14510 32064 14508 32065 14504 32065 14510 32065 14509 32066 14511 32066 14512 32066 7774 32067 14514 32067 14516 32067 7763 32068 14517 32068 14518 32068 7762 32069 14518 32069 14519 32069 7760 32070 14519 32070 14515 32070 7774 32071 14516 32071 7773 32071 7763 32072 14518 32072 7762 32072 7762 32073 14519 32073 7760 32073 14523 32074 7771 32074 7767 32074 14524 32075 7760 32075 14521 32075 7762 32076 14524 32076 14525 32076 7763 32077 14525 32077 14523 32077 7767 32078 7763 32078 14523 32078 14523 32079 14522 32079 7771 32079 14516 32080 14519 32080 14518 32080 14514 32081 14519 32081 14516 32081 14523 32082 14525 32082 14527 32082 14524 32083 14521 32083 14528 32083 14525 32084 14526 32084 14527 32084 14529 32085 7730 32085 7768 32085 7734 32086 14531 32086 14532 32086 7765 32087 14533 32087 14529 32087 7730 32088 14530 32088 7729 32088 7778 32089 14533 32089 7776 32089 7776 32090 14533 32090 7775 32090 7768 32091 14534 32091 7765 32091 7768 32092 7730 32092 14535 32092 14537 32093 14536 32093 7734 32093 14538 32094 7765 32094 14534 32094 14538 32095 7775 32095 7765 32095 7775 32096 14538 32096 7776 32096 7734 32097 7780 32097 14537 32097 14530 32098 14529 32098 14533 32098 14531 32099 14533 32099 14532 32099 14530 32100 14533 32100 14531 32100 14538 32101 14540 32101 14539 32101 14540 32102 14541 32102 14539 32102 14539 32103 14542 32103 14537 32103 14535 32104 14536 32104 14543 32104 14542 32105 14543 32105 14536 32105 14534 32106 14543 32106 14540 32106 14536 32107 14537 32107 14542 32107 14539 32108 14541 32108 14542 32108 14543 32109 14544 32109 14541 32109 7782 32110 14546 32110 7852 32110 7848 32111 14548 32111 7849 32111 7793 32112 14549 32112 7791 32112 7791 32113 14545 32113 7789 32113 7785 32114 7781 32114 14551 32114 14551 32115 7781 32115 7782 32115 7849 32116 14554 32116 14553 32116 7793 32117 14554 32117 7849 32117 7849 32118 14553 32118 7848 32118 14552 32119 14551 32119 7782 32119 7791 32120 7789 32120 14550 32120 14547 32121 14549 32121 14548 32121 14552 32122 14557 32122 14551 32122 14556 32123 14557 32123 14552 32123 14550 32124 14551 32124 14555 32124 14552 32125 14553 32125 14556 32125 14554 32126 14555 32126 14556 32126 14556 32127 14555 32127 14557 32127 14558 32128 7886 32128 7860 32128 7886 32129 14558 32129 7882 32129 7882 32130 14558 32130 14559 32130 7862 32131 14561 32131 14562 32131 7862 32132 14562 32132 7858 32132 7858 32133 14562 32133 7860 32133 14563 32134 7886 32134 7882 32134 14565 32135 7882 32135 7879 32135 14566 32136 7879 32136 7876 32136 7862 32137 14567 32137 7864 32137 7864 32138 14567 32138 14568 32138 7866 32139 14568 32139 7876 32139 7858 32140 7860 32140 14564 32140 14559 32141 14561 32141 14560 32141 14558 32142 14562 32142 14559 32142 14567 32143 14569 32143 14568 32143 14566 32144 14568 32144 14571 32144 14571 32145 14572 32145 14565 32145 14564 32146 14563 32146 14569 32146 14565 32147 14566 32147 14571 32147 14570 32148 14572 32148 14571 32148 7899 32149 14577 32149 14574 32149 7863 32150 14573 32150 7865 32150 7900 32151 14576 32151 7899 32151 7861 32152 14578 32152 7896 32152 14578 32153 7861 32153 7863 32153 14578 32154 7863 32154 7865 32154 14580 32155 7867 32155 7869 32155 14581 32156 14580 32156 7869 32156 7900 32157 14581 32157 7869 32157 14573 32158 14574 32158 14577 32158 14579 32159 14583 32159 14582 32159 14581 32160 14582 32160 14584 32160 14581 32161 14584 32161 14580 32161 14578 32162 14580 32162 14585 32162 14584 32163 14585 32163 14580 32163 14578 32164 14585 32164 14579 32164 14585 32165 14583 32165 14579 32165 14586 32166 7813 32166 14587 32166 7918 32167 14586 32167 14588 32167 7920 32168 14589 32168 14590 32168 7813 32169 7816 32169 14587 32169 7915 32170 14589 32170 7919 32170 7919 32171 14589 32171 7920 32171 7818 32172 14587 32172 7816 32172 14593 32173 7918 32173 7916 32173 14594 32174 7916 32174 7915 32174 7818 32175 14592 32175 7920 32175 7915 32176 7919 32176 14594 32176 7920 32177 14595 32177 7919 32177 14593 32178 14591 32178 7918 32178 14588 32179 14590 32179 14589 32179 14592 32180 14596 32180 14595 32180 14596 32181 14597 32181 14595 32181 14594 32182 14595 32182 14598 32182 14593 32183 14599 32183 14591 32183 14591 32184 14599 32184 14596 32184 14597 32185 14596 32185 14599 32185 14595 32186 14597 32186 14598 32186 14598 32187 14600 32187 14599 32187 14599 32188 14600 32188 14597 32188 14598 32189 14597 32189 14600 32189 7815 32190 14602 32190 7817 32190 7817 32191 14603 32191 7819 32191 7822 32192 14604 32192 7824 32192 7824 32193 14604 32193 7826 32193 7826 32194 14605 32194 7828 32194 7828 32195 14605 32195 7831 32195 7881 32196 14606 32196 7831 32196 14607 32197 7815 32197 7817 32197 14609 32198 7828 32198 14606 32198 14609 32199 7826 32199 7828 32199 7822 32200 14610 32200 14608 32200 7824 32201 14610 32201 7822 32201 14601 32202 14605 32202 14602 32202 14607 32203 14608 32203 14613 32203 14612 32204 14613 32204 14608 32204 14607 32205 14613 32205 14606 32205 14610 32206 14611 32206 14612 32206 14613 32207 14611 32207 14609 32207 14614 32208 14615 32208 7921 32208 7904 32209 14615 32209 14616 32209 7922 32210 14616 32210 14617 32210 7922 32211 14617 32211 14618 32211 7821 32212 14618 32212 14614 32212 7921 32213 14615 32213 7902 32213 7902 32214 14615 32214 7904 32214 7904 32215 14616 32215 7906 32215 7906 32216 14616 32216 7922 32216 7820 32217 14619 32217 7821 32217 7922 32218 14623 32218 14624 32218 14622 32219 14621 32219 7904 32219 14614 32220 14618 32220 14615 32220 14615 32221 14618 32221 14617 32221 14615 32222 14617 32222 14616 32222 14621 32223 14626 32223 14620 32223 14627 32224 14626 32224 14625 32224 14628 32225 14629 32225 7877 32225 7880 32226 14629 32226 14630 32226 7870 32227 14632 32227 14628 32227 7877 32228 14629 32228 7878 32228 7878 32229 14629 32229 7880 32229 7923 32230 14631 32230 7872 32230 7872 32231 14632 32231 7870 32231 7870 32232 14628 32232 7868 32232 14634 32233 7878 32233 7880 32233 14635 32234 14634 32234 7832 32234 7872 32235 14637 32235 7923 32235 7870 32236 7868 32236 14636 32236 14629 32237 14628 32237 14632 32237 14629 32238 14631 32238 14630 32238 14636 32239 14638 32239 14637 32239 14635 32240 14639 32240 14634 32240 14639 32241 14640 32241 14634 32241 14634 32242 14640 32242 14633 32242 14633 32243 14640 32243 14636 32243 14638 32244 14636 32244 14640 32244 14641 32245 14638 32245 14640 32245 7889 32246 14642 32246 14643 32246 7859 32247 14643 32247 14644 32247 7890 32248 14642 32248 7889 32248 7897 32249 14645 32249 7894 32249 7897 32250 14651 32250 14652 32250 7898 32251 14652 32251 14650 32251 7859 32252 7898 32252 14650 32252 7897 32253 14652 32253 7898 32253 7894 32254 7892 32254 14648 32254 7892 32255 14646 32255 14642 32255 14643 32256 14645 32256 14644 32256 14656 32257 14649 32257 14650 32257 14651 32258 14648 32258 14653 32258 14647 32259 14656 32259 14657 32259 14656 32260 14655 32260 14657 32260 14657 32261 14655 32261 14654 32261 14658 32262 7805 32262 7802 32262 7805 32263 14659 32263 7924 32263 7787 32264 14659 32264 14660 32264 7786 32265 14660 32265 14661 32265 7790 32266 14661 32266 14662 32266 7786 32267 14661 32267 7790 32267 7790 32268 14662 32268 7792 32268 7792 32269 14662 32269 7796 32269 7796 32270 14663 32270 7798 32270 7798 32271 14663 32271 7802 32271 7802 32272 7805 32272 14664 32272 14667 32273 7787 32273 7786 32273 14665 32274 14669 32274 7796 32274 7790 32275 14669 32275 14668 32275 14667 32276 14666 32276 7787 32276 14666 32277 14664 32277 7924 32277 14658 32278 14663 32278 14659 32278 14669 32279 14670 32279 14668 32279 14666 32280 14673 32280 14664 32280 14672 32281 14673 32281 14666 32281 14664 32282 14673 32282 14670 32282 14666 32283 14667 32283 14672 32283 14674 32284 14675 32284 7801 32284 7930 32285 14675 32285 14676 32285 7803 32286 14678 32286 14679 32286 7800 32287 14679 32287 14674 32287 7801 32288 7800 32288 14674 32288 7931 32289 14675 32289 7930 32289 7930 32290 14676 32290 7927 32290 7927 32291 14676 32291 7926 32291 14680 32292 14681 32292 7800 32292 7801 32293 14680 32293 7800 32293 14682 32294 7801 32294 7931 32294 14683 32295 7930 32295 7927 32295 14683 32296 7927 32296 7926 32296 7803 32297 14681 32297 14684 32297 14674 32298 14679 32298 14675 32298 14675 32299 14679 32299 14678 32299 14680 32300 14688 32300 14685 32300 14680 32301 14685 32301 14681 32301 14686 32302 14685 32302 14688 32302 7929 32303 14691 32303 14692 32303 7847 32304 14691 32304 7929 32304 7932 32305 14693 32305 7799 32305 7799 32306 14693 32306 7797 32306 7794 32307 14694 32307 7795 32307 7795 32308 7845 32308 14695 32308 14695 32309 7845 32309 7847 32309 14697 32310 7847 32310 7929 32310 14698 32311 14697 32311 7929 32311 14699 32312 7794 32312 14696 32312 7797 32313 14699 32313 7799 32313 7932 32314 14700 32314 14698 32314 7929 32315 7932 32315 14698 32315 7799 32316 14700 32316 7932 32316 14699 32317 14701 32317 14700 32317 14701 32318 14702 32318 14700 32318 14695 32319 14704 32319 14701 32319 14697 32320 14698 32320 14703 32320 7769 32321 14708 32321 14709 32321 7770 32322 14708 32322 7769 32322 7756 32323 7755 32323 14710 32323 14712 32324 7753 32324 7750 32324 14714 32325 14715 32325 7772 32325 7750 32326 7751 32326 14713 32326 7770 32327 14713 32327 7751 32327 14712 32328 14711 32328 7753 32328 14714 32329 7757 32329 14710 32329 14707 32330 14709 32330 14708 32330 14713 32331 14717 32331 14712 32331 14712 32332 14717 32332 14718 32332 14715 32333 14716 32333 14717 32333 14718 32334 14716 32334 14719 32334 14716 32335 14718 32335 14717 32335 10660 32336 14722 32336 14723 32336 10670 32337 14723 32337 14724 32337 10663 32338 14724 32338 14725 32338 10664 32339 14725 32339 14726 32339 10666 32340 14726 32340 14720 32340 10667 32341 10666 32341 14720 32341 10660 32342 14723 32342 10670 32342 10663 32343 14725 32343 10662 32343 10664 32344 14726 32344 10665 32344 10667 32345 10668 32345 10654 32345 10655 32346 10665 32346 10656 32346 10655 32347 10664 32347 10665 32347 14722 32348 14726 32348 14725 32348 14723 32349 14725 32349 14724 32349 14727 32350 10655 32350 10656 32350 10653 32351 10658 32351 10652 32351 10654 32352 10650 32352 10656 32352 10650 32353 14727 32353 10656 32353 14727 32354 14728 32354 10655 32354 14729 32355 10149 32355 10144 32355 14729 32356 14730 32356 10149 32356 10147 32357 14731 32357 14732 32357 10146 32358 14732 32358 14733 32358 10139 32359 14733 32359 14734 32359 10143 32360 14730 32360 10148 32360 10147 32361 14732 32361 10141 32361 10141 32362 14732 32362 10146 32362 10139 32363 14734 32363 10138 32363 10144 32364 10153 32364 10145 32364 10139 32365 10151 32365 10140 32365 10155 32366 10154 32366 10143 32366 10138 32367 10145 32367 10152 32367 14729 32368 14734 32368 14730 32368 14730 32369 14734 32369 14733 32369 14730 32370 14733 32370 14731 32370 14735 32371 10153 32371 10787 32371 14735 32372 10788 32372 10153 32372 10788 32373 10152 32373 10153 32373 10151 32374 10788 32374 10150 32374 14737 32375 10155 32375 14736 32375 10154 32376 14738 32376 10787 32376 10155 32377 10150 32377 14736 32377 10154 32378 10155 32378 14738 32378 10788 32379 10151 32379 10152 32379 14739 32380 10521 32380 10522 32380 10515 32381 14742 32381 14743 32381 10522 32382 10520 32382 14739 32382 10513 32383 14740 32383 10512 32383 10512 32384 14741 32384 10523 32384 10516 32385 14742 32385 10515 32385 10515 32386 14743 32386 10517 32386 10517 32387 14743 32387 10518 32387 10518 32388 14744 32388 10519 32388 10519 32389 14744 32389 10520 32389 10506 32390 10521 32390 10513 32390 10506 32391 10513 32391 10512 32391 10504 32392 10509 32392 10518 32392 10515 32393 10509 32393 10511 32393 10514 32394 10516 32394 10511 32394 14739 32395 14744 32395 14740 32395 14740 32396 14744 32396 14743 32396 14740 32397 14743 32397 14741 32397 10508 32398 10504 32398 14745 32398 14747 32399 10510 32399 14746 32399 10510 32400 14747 32400 10506 32400 10506 32401 14747 32401 10503 32401 10507 32402 14745 32402 10504 32402 14745 32403 14747 32403 14746 32403 14748 32404 10580 32404 10579 32404 14748 32405 14749 32405 10580 32405 10573 32406 14750 32406 14751 32406 10574 32407 14751 32407 14752 32407 10576 32408 14752 32408 14753 32408 10579 32409 10577 32409 14748 32409 10571 32410 14750 32410 10581 32410 10573 32411 14751 32411 10582 32411 10574 32412 14752 32412 10575 32412 10575 32413 14752 32413 10576 32413 10579 32414 10563 32414 10577 32414 10565 32415 10572 32415 10571 32415 10568 32416 10565 32416 10571 32416 10578 32417 10577 32417 10566 32417 14749 32418 14753 32418 14752 32418 14749 32419 14752 32419 14750 32419 10564 32420 14754 32420 10567 32420 10570 32421 10569 32421 10568 32421 14756 32422 10568 32422 10569 32422 10568 32423 14756 32423 10563 32423 10563 32424 14756 32424 9582 32424 10563 32425 9582 32425 10566 32425 10567 32426 14754 32426 14755 32426 10564 32427 10567 32427 10566 32427 14757 32428 10826 32428 10827 32428 14757 32429 14758 32429 10826 32429 10825 32430 14758 32430 14759 32430 10822 32431 14760 32431 14761 32431 10818 32432 14762 32432 14763 32432 10824 32433 14759 32433 10823 32433 10823 32434 14760 32434 10822 32434 10819 32435 14762 32435 10818 32435 10818 32436 14763 32436 10816 32436 10816 32437 14763 32437 10817 32437 10782 32438 10783 32438 10817 32438 10821 32439 10785 32439 10761 32439 10822 32440 10821 32440 10761 32440 14757 32441 14763 32441 14758 32441 14760 32442 14762 32442 14761 32442 14759 32443 14762 32443 14760 32443 10762 32444 14764 32444 10761 32444 10782 32445 10781 32445 10783 32445 10786 32446 10761 32446 8918 32446 10780 32447 8918 32447 10781 32447 8918 32448 10761 32448 14764 32448 14766 32449 14765 32449 14764 32449 14767 32450 10867 32450 10868 32450 10868 32451 10869 32451 14767 32451 10864 32452 14771 32452 10874 32452 10874 32453 14771 32453 10873 32453 10872 32454 14772 32454 10871 32454 10864 32455 10874 32455 9941 32455 10873 32456 9940 32456 10874 32456 14770 32457 14772 32457 14771 32457 14768 32458 14773 32458 14769 32458 14769 32459 14772 32459 14770 32459 9939 32460 14775 32460 9940 32460 14775 32461 9939 32461 9938 32461 9941 32462 9940 32462 14776 32462 9940 32463 14775 32463 14776 32463 14774 32464 9938 32464 14777 32464 14774 32465 14777 32465 14776 32465 14778 32466 10876 32466 10877 32466 14778 32467 14779 32467 10876 32467 10876 32468 14779 32468 10875 32468 10875 32469 14780 32469 10879 32469 10879 32470 14781 32470 10880 32470 10880 32471 14782 32471 10881 32471 10881 32472 14783 32472 10878 32472 10878 32473 14783 32473 10877 32473 10877 32474 10876 32474 14784 32474 14786 32475 10875 32475 10879 32475 14787 32476 14786 32476 10879 32476 14788 32477 10881 32477 10878 32477 10880 32478 14789 32478 14787 32478 10881 32479 14789 32479 10880 32479 10880 32480 14787 32480 10879 32480 14786 32481 14785 32481 10875 32481 10878 32482 10877 32482 14788 32482 14779 32483 14782 32483 14780 32483 14789 32484 14791 32484 14787 32484 14785 32485 14792 32485 14788 32485 14784 32486 14785 32486 14788 32486 14786 32487 14787 32487 14791 32487 14790 32488 14792 32488 14791 32488 10092 32489 14794 32489 14795 32489 10086 32490 14796 32490 14797 32490 10087 32491 14798 32491 14799 32491 10090 32492 14800 32492 14793 32492 10093 32493 14796 32493 10086 32493 10086 32494 14798 32494 10087 32494 10090 32495 10091 32495 10098 32495 10098 32496 10091 32496 10099 32496 10099 32497 10091 32497 10092 32497 10100 32498 10092 32498 10093 32498 10086 32499 10101 32499 10100 32499 14793 32500 14800 32500 14794 32500 14794 32501 14800 32501 14799 32501 14795 32502 14799 32502 14798 32502 14797 32503 14796 32503 14798 32503 10102 32504 14802 32504 10101 32504 10099 32505 10100 32505 10104 32505 10099 32506 14803 32506 10105 32506 10099 32507 10105 32507 10098 32507 10105 32508 14801 32508 10103 32508 14801 32509 14802 32509 10102 32509 14804 32510 14803 32510 14802 32510 14805 32511 8009 32511 14806 32511 8009 32512 14805 32512 14807 32512 7999 32513 14808 32513 14809 32513 7999 32514 14809 32514 14806 32514 8009 32515 7997 32515 14806 32515 8009 32516 14807 32516 8011 32516 8011 32517 14808 32517 8013 32517 8013 32518 14808 32518 7999 32518 7999 32519 14806 32519 7997 32519 8009 32520 10417 32520 7997 32520 8009 32521 10419 32521 10417 32521 10419 32522 8009 32522 10421 32522 10422 32523 8009 32523 8011 32523 10436 32524 8013 32524 10435 32524 10436 32525 10437 32525 8013 32525 10416 32526 7999 32526 7997 32526 10437 32527 10424 32527 8011 32527 10422 32528 10421 32528 8009 32528 10412 32529 7997 32529 10414 32529 14807 32530 14806 32530 14809 32530 14805 32531 14806 32531 14807 32531 14807 32532 14809 32532 14808 32532 10433 32533 14811 32533 14810 32533 10433 32534 10416 32534 14811 32534 10434 32535 14810 32535 10429 32535 10435 32536 14810 32536 10436 32536 10422 32537 14812 32537 10421 32537 10422 32538 10424 32538 14812 32538 14812 32539 10424 32539 10436 32539 10417 32540 14813 32540 10414 32540 10424 32541 10437 32541 10436 32541 10416 32542 10412 32542 14811 32542 14814 32543 14811 32543 14813 32543 14814 32544 14810 32544 14811 32544 14810 32545 14812 32545 10436 32545 14813 32546 14812 32546 14814 32546 8026 32547 8025 32547 14815 32547 8029 32548 14818 32548 8028 32548 8028 32549 14818 32549 8025 32549 10614 32550 10615 32550 8025 32550 8026 32551 10614 32551 8025 32551 10613 32552 8026 32552 10612 32552 10603 32553 8036 32553 8032 32553 10605 32554 8032 32554 10606 32554 10617 32555 10609 32555 8028 32555 8028 32556 10609 32556 10608 32556 8029 32557 10607 32557 10606 32557 8028 32558 10608 32558 8029 32558 10603 32559 10602 32559 8036 32559 14816 32560 14815 32560 14818 32560 14816 32561 14818 32561 14817 32561 10608 32562 14819 32562 10607 32562 10605 32563 14821 32563 10604 32563 10605 32564 14819 32564 14821 32564 10602 32565 14822 32565 10612 32565 10612 32566 14822 32566 10613 32566 10613 32567 14822 32567 10614 32567 10615 32568 14822 32568 14820 32568 10603 32569 10604 32569 14821 32569 14819 32570 14823 32570 14821 32570 14826 32571 14827 32571 14828 32571 14827 32572 14830 32572 14831 32572 14832 32573 14833 32573 14834 32573 14835 32574 14837 32574 14838 32574 14839 32575 14840 32575 14841 32575 14842 32576 14843 32576 14844 32576 14846 32577 14847 32577 14848 32577 14850 32578 14851 32578 14852 32578 14853 32579 14854 32579 14855 32579 14858 32580 14856 32580 14859 32580 14855 32581 14860 32581 14856 32581 14862 32582 14856 32582 14861 32582 14863 32583 14864 32583 14865 32583 14828 32584 14829 32584 14867 32584 14836 32585 14871 32585 14872 32585 14836 32586 14873 32586 14837 32586 14874 32587 14826 32587 14866 32587 14867 32588 14826 32588 14828 32588 14867 32589 14866 32589 14826 32589 1288 32590 14849 32590 14876 32590 949 32591 14877 32591 14841 32591 949 32592 14878 32592 14877 32592 14879 32593 14880 32593 949 32593 949 32594 14880 32594 14881 32594 949 32595 14882 32595 14878 32595 959 32596 14884 32596 14883 32596 14884 32597 959 32597 14872 32597 14872 32598 959 32598 14873 32598 949 32599 14841 32599 14879 32599 14840 32600 14879 32600 14841 32600 14888 32601 14846 32601 14889 32601 14888 32602 14890 32602 14846 32602 14891 32603 14889 32603 14846 32603 14892 32604 14893 32604 14894 32604 14894 32605 14893 32605 14895 32605 14896 32606 14897 32606 14893 32606 14897 32607 14896 32607 14898 32607 14901 32608 14900 32608 14902 32608 14904 32609 14905 32609 14902 32609 14906 32610 14905 32610 14904 32610 14907 32611 14908 32611 14909 32611 14907 32612 14910 32612 14908 32612 14898 32613 14907 32613 14909 32613 14911 32614 14912 32614 14892 32614 14911 32615 14913 32615 14912 32615 14894 32616 14911 32616 14892 32616 14892 32617 14912 32617 14915 32617 14908 32618 277 32618 14917 32618 14919 32619 14901 32619 14903 32619 14906 32620 14920 32620 14921 32620 14922 32621 14906 32621 14921 32621 14919 32622 14903 32622 14923 32622 14923 32623 14903 32623 14824 32623 14924 32624 14923 32624 14824 32624 14926 32625 14858 32625 14925 32625 14883 32626 14884 32626 14924 32626 14912 32627 14928 32627 14863 32627 14912 32628 14863 32628 14918 32628 14929 32629 14930 32629 14931 32629 14931 53 14930 53 14932 53 14838 32630 14933 32630 14829 32630 14933 32631 14934 32631 14829 32631 14869 32632 14935 32632 14933 32632 14936 32633 14935 32633 14883 32633 14920 32634 14937 32634 14921 32634 14938 32635 14939 32635 14937 32635 14938 32636 14876 32636 14939 32636 14876 32637 14849 32637 14940 32637 14941 32638 14940 32638 14877 32638 14878 32639 14942 32639 14877 32639 14916 32640 14943 32640 14882 32640 14943 32641 14942 32641 14882 32641 14882 32642 14942 32642 14878 32642 14908 32643 14944 32643 14909 32643 14865 32644 14944 32644 14917 32644 14946 32645 14950 32645 14949 32645 14947 32646 14930 32646 14929 32646 14947 32647 14951 32647 14948 32647 14950 32648 14953 32648 14954 32648 14957 32649 14955 32649 14956 32649 14957 32650 14952 32650 14958 32650 14951 32651 14952 32651 14959 32651 14955 32652 14958 32652 14937 32652 14961 32653 14963 32653 14962 32653 14964 32654 14965 32654 14966 32654 14967 32655 14964 32655 14960 32655 14961 32656 14968 32656 14963 32656 14969 32657 14968 32657 14970 32657 14971 32658 14970 32658 14945 32658 14971 32659 14931 32659 14969 32659 14908 32660 14917 32660 14944 32660 14921 32661 14936 32661 14922 32661 14882 32662 14881 32662 14914 32662 14914 32663 14881 32663 14911 32663 14977 32664 952 32664 14938 32664 14901 32665 14859 32665 14977 32665 952 32666 14978 32666 14938 32666 14938 32667 14978 32667 1288 32667 1288 32668 14978 32668 14889 32668 14938 32669 1288 32669 14876 32669 14968 32670 14969 32670 14941 32670 14949 32671 14969 32671 14930 32671 14969 32672 14932 32672 14930 32672 14967 32673 14962 32673 14943 32673 14954 32674 14937 32674 14939 32674 14944 32675 14964 32675 14967 32675 14944 32676 14945 32676 14964 32676 14934 32677 14945 32677 14868 32677 14958 32678 14952 32678 14935 32678 14929 32679 14931 32679 14947 32679 14934 32680 14933 32680 14947 32680 14951 32681 14947 32681 14933 32681 14946 32682 14948 32682 14979 32682 14953 32683 14950 32683 14980 32683 14950 32684 14946 32684 14979 32684 14979 32685 14948 32685 14981 32685 14951 32686 14959 32686 14981 32686 14857 32687 14982 32687 14983 32687 14857 32688 14956 32688 14982 32688 14853 32689 14984 32689 14957 32689 14853 32690 14957 32690 14854 32690 14957 32691 14956 32691 14854 32691 14980 32692 14979 32692 14981 32692 14982 32693 14956 32693 14953 32693 14980 32694 14982 32694 14953 32694 14986 32695 14989 32695 14970 32695 14986 32696 14970 32696 14968 32696 14975 32697 14928 32697 14990 32697 14928 32698 14960 32698 14990 32698 14991 32699 14961 32699 14974 32699 14974 32700 14961 32700 14972 32700 14974 32701 14975 32701 14991 32701 14961 32702 14960 32702 14972 32702 14988 32703 14986 32703 14985 32703 14988 32704 14989 32704 14986 32704 14961 32705 14991 32705 14987 32705 14987 32706 14991 32706 14985 32706 14988 32707 14990 32707 14966 32707 14928 32708 14912 32708 14913 32708 14928 32709 14913 32709 14992 32709 14917 32710 14918 32710 14865 32710 14922 32711 14883 32711 14924 32711 14916 32712 14882 32712 14914 32712 14997 32713 14995 32713 14996 32713 14996 32714 14998 32714 14997 32714 15000 32715 15001 32715 14999 32715 14861 32716 15001 32716 15000 32716 14861 32717 15002 32717 15001 32717 14994 32718 15004 32718 14996 32718 14996 32719 15004 32719 14976 32719 14824 32720 15005 32720 14825 32720 15007 32721 15006 32721 14922 32721 15007 32722 1645 32722 14825 32722 1645 32723 15007 32723 14922 32723 14897 32724 14894 32724 14895 32724 15010 32725 15011 32725 15009 32725 15008 32726 15010 32726 15009 32726 15008 32727 14915 32727 15010 32727 15006 32728 14903 32728 14906 32728 15009 32729 15011 32729 14892 32729 14850 32730 15012 32730 15013 32730 15000 32731 15013 32731 15003 32731 15000 32732 15014 32732 15013 32732 14997 32733 14998 32733 15015 32733 15016 32734 14997 32734 15015 32734 14998 32735 15017 32735 15015 32735 14843 32736 14850 32736 15013 32736 15015 32737 15013 32737 15016 32737 15016 32738 15013 32738 15014 32738 15014 32739 14999 32739 15016 32739 14887 32740 14845 32740 14880 32740 14880 32741 14845 32741 14881 32741 14973 32742 15017 32742 14996 32742 14996 32743 15017 32743 14998 32743 14851 32744 14888 32744 14889 32744 14834 32745 15018 32745 15019 32745 15019 32746 15018 32746 14993 32746 14995 32747 15019 32747 14993 32747 15001 32748 15002 32748 15021 32748 15022 32749 15001 32749 15021 32749 15023 32750 15024 32750 15021 32750 15002 32751 15023 32751 15021 32751 14832 32752 14834 32752 15019 32752 15021 32753 14832 32753 15019 32753 15020 32754 15001 32754 15022 32754 14854 32755 15023 32755 14855 32755 14855 32756 15023 32756 14860 32756 14860 32757 15023 32757 14861 32757 14861 32758 15023 32758 15002 32758 14872 32759 15025 32759 14884 32759 14864 32760 14833 32760 14866 32760 14994 32761 15018 32761 15004 32761 14976 32762 15018 32762 14928 32762 15026 32763 14835 32763 14838 32763 14877 32764 14849 32764 15028 32764 15028 32765 15029 32765 14839 32765 14847 32766 15030 32766 14849 32766 14849 32767 15030 32767 15028 32767 14845 32768 15032 32768 14843 32768 14845 32769 15029 32769 15032 32769 15032 32770 15029 32770 15028 32770 15031 32771 15033 32771 15030 32771 15031 32772 14851 32772 15033 32772 14850 32773 14843 32773 15033 32773 15033 32774 14843 32774 15032 32774 14830 32775 15034 32775 14831 32775 14832 32776 15024 32776 15034 32776 15034 32777 15024 32777 15035 32777 15035 32778 15027 32778 15026 32778 15036 32779 15033 32779 15032 32779 15034 32780 15035 32780 15044 32780 14846 32781 14890 32781 14847 32781 14890 32782 14888 32782 15031 32782 15031 32783 14888 32783 14851 32783 14839 32784 15029 32784 14885 32784 14840 32785 14839 32785 14885 32785 14845 32786 14886 32786 15029 32786 14835 32787 15027 32787 14870 32787 15027 32788 15025 32788 14870 32788 14870 32789 15025 32789 14871 32789 14827 32790 14875 32790 14830 32790 14830 32791 14875 32791 14833 32791 15018 32792 14834 32792 14833 32792 15025 32793 15024 32793 15023 32793 14842 32794 14844 32794 15017 32794 14859 32795 14901 32795 14925 32795 14911 32796 14992 32796 14913 32796 14927 32797 15025 32797 15023 32797 14884 32798 15025 32798 14927 32798 14833 32799 14864 32799 14863 32799 14928 32800 15018 32800 14863 32800 14978 32801 15045 32801 14851 32801 15045 32802 14978 32802 14859 32802 14869 32803 14837 32803 14873 32803 14848 32804 1288 32804 14891 32804 14873 32805 959 32805 14869 32805 14918 32806 14915 32806 14912 32806 14915 32807 277 32807 14910 32807 1645 32808 14924 32808 14824 32808 14907 32809 14898 32809 14896 32809 278 32810 14907 32810 14898 32810 15014 32811 15000 32811 14999 32811 14852 32812 15045 32812 15012 32812 15048 32813 15049 32813 15050 32813 15054 32814 15055 32814 15056 32814 15057 32815 15059 32815 15060 32815 15061 32816 15062 32816 15063 32816 15069 32817 15072 32817 15070 32817 15076 32818 15077 32818 15078 32818 15082 32819 15083 32819 15079 32819 15082 32820 15074 32820 15083 32820 15081 32821 15085 32821 15082 32821 15086 32822 15085 32822 15087 32822 15088 32823 15089 32823 15090 32823 15089 32824 15049 32824 15090 32824 15060 32825 2911 32825 15092 32825 15096 32826 15097 32826 15058 32826 15098 32827 15050 32827 15091 32827 15078 32828 15077 32828 2806 32828 2806 32829 15077 32829 15100 32829 15101 32830 2807 32830 15102 32830 15101 32831 15102 32831 15068 32831 15101 32832 15103 32832 15104 32832 15101 32833 15104 32833 15105 32833 15101 32834 15105 32834 15102 32834 15106 32835 15107 32835 15108 32835 15092 32836 15108 32836 15107 32836 15109 32837 15078 32837 2806 32837 15101 32838 15067 32838 15110 32838 15067 32839 15112 32839 15103 32839 15116 32840 15117 32840 15118 32840 15120 32841 15118 32841 15119 32841 15119 32842 15121 32842 15122 32842 2168 32843 15124 32843 15125 32843 15124 32844 15127 32844 15125 32844 15129 32845 15128 32845 15127 32845 15130 32846 15131 32846 15132 32846 15132 32847 15133 32847 15130 32847 15130 32848 15133 32848 15122 32848 15118 32849 15134 32849 15136 32849 15138 32850 15120 32850 15139 32850 15122 32851 15133 32851 15120 32851 15046 32852 15132 32852 3496 32852 15132 32853 15046 32853 15140 32853 15046 32854 3496 32854 15140 32854 15141 32855 2168 32855 15126 32855 15143 32856 15144 32856 15145 32856 15143 32857 15129 32857 15144 32857 15143 32858 15147 32858 15126 32858 15126 32859 15147 32859 15142 32859 15148 32860 15147 32860 2114 32860 15144 32861 15123 32861 15149 32861 15123 32862 2167 32862 15141 32862 15141 32863 2167 32863 2168 32863 15151 32864 2114 32864 15152 32864 15084 32865 15141 32865 15153 32865 15084 32866 15154 32866 15080 32866 2797 32867 15106 32867 15151 32867 15148 32868 15106 32868 15080 32868 15052 32869 15051 32869 15140 32869 15155 53 15156 53 15157 53 15157 32870 15156 32870 15158 32870 15060 32871 15159 32871 15049 32871 15049 32872 15160 32872 15090 32872 15060 32873 15161 32873 15159 32873 15092 32874 15161 32874 15060 32874 15144 32875 15163 32875 15145 32875 15144 32876 15149 32876 15163 32876 15100 32877 15165 32877 15164 32877 15166 32878 15077 32878 15068 32878 15167 32879 15068 32879 15102 32879 15167 32880 15166 32880 15068 32880 15139 32881 15169 32881 15105 32881 15169 32882 15168 32882 15105 32882 15105 32883 15168 32883 15102 32883 15132 32884 15170 32884 15133 32884 15088 32885 15170 32885 15132 32885 15088 32886 15090 32886 15171 32886 15173 32887 15156 32887 15174 32887 15174 32888 15177 32888 15172 32888 15176 32889 15179 32889 15175 32889 15180 32890 15181 32890 15179 32890 15175 32891 15179 32891 15181 32891 15189 32892 15184 32892 15190 32892 15189 32893 15191 32893 15184 32893 15188 32894 15192 32894 15193 32894 15193 32895 15192 32895 15194 32895 15191 32896 15189 32896 15194 32896 15169 32897 15139 32897 15133 32897 15198 32898 15199 32898 15196 32898 2086 32899 15202 32899 15138 32899 15150 32900 15073 32900 15164 32900 15141 32901 15074 32901 15150 32901 15073 32902 15203 32902 15164 32902 15164 32903 15203 32903 15114 32903 15166 32904 15167 32904 15193 32904 15193 32905 15158 32905 15156 32905 15175 32906 15166 32906 15173 32906 15175 32907 15163 32907 15165 32907 15162 32908 15181 32908 15182 32908 15162 32909 15163 32909 15181 32909 15171 32910 15090 32910 15189 32910 15160 32911 15189 32911 15090 32911 15160 32912 15195 32912 15189 32912 15182 32913 15161 32913 15162 32913 15182 32914 15178 32914 15161 32914 15160 32915 15159 32915 15174 32915 15176 32916 15204 32916 15179 32916 15206 32917 15172 32917 15207 32917 15207 32918 15172 32918 15177 32918 15083 32919 15084 32919 15208 32919 15083 32920 15208 32920 15209 32920 15079 32921 15083 32921 15209 32921 15209 32922 15180 32922 15080 32922 15079 32923 15209 32923 15080 32923 15178 32924 15180 32924 15183 32924 15208 32925 15179 32925 15204 32925 15207 32926 15209 32926 15205 32926 15205 32927 15208 32927 15204 32927 15210 32928 15188 32928 15185 32928 15212 32929 15191 32929 15194 32929 15212 32930 15194 32930 15213 32930 15213 32931 15194 32931 15192 32931 15052 32932 15184 32932 15214 32932 15196 32933 15215 32933 15197 32933 15215 32934 15185 32934 15197 32934 15185 32935 15184 32935 15197 32935 15212 32936 15216 32936 15210 32936 15185 32937 15215 32937 15210 32937 15214 32938 15184 32938 15211 32938 15212 32939 15214 32939 15211 32939 15134 32940 15197 32940 15217 32940 15149 32941 15150 32941 15164 32941 15222 32942 15220 32942 15221 32942 15220 32943 15222 32943 15224 32943 15087 32944 15224 32944 15086 32944 15087 32945 15225 32945 15224 32945 15220 32946 15224 32946 15225 32946 15086 32947 15224 32947 15227 32947 15219 32948 15228 32948 15221 32948 15199 32949 15221 32949 15200 32949 15147 32950 15229 32950 2114 32950 15232 32951 15146 32951 2114 32951 15232 32952 2114 32952 15230 32952 15119 32953 15122 32953 15120 32953 15136 32954 3496 32954 15233 32954 15125 32955 15128 32955 15126 32955 15233 32956 15234 32956 15136 32956 15235 32957 15075 32957 15236 32957 15236 32958 15075 32958 15227 32958 15224 32959 15236 32959 15227 32959 15222 32960 15223 32960 15238 32960 15223 32961 15240 32961 15238 32961 15238 32962 15071 32962 15070 32962 15070 32963 15235 32963 15236 32963 15238 32964 15236 32964 15239 32964 15072 32965 15069 32965 15104 32965 15199 32966 15240 32966 15221 32966 15221 32967 15240 32967 15223 32967 15086 32968 15075 32968 15082 32968 15082 32969 15075 32969 15074 32969 15203 32970 15241 32970 15114 32970 15056 32971 15242 32971 15243 32971 15247 32972 15063 32972 15245 32972 15054 32973 15056 32973 15243 32973 15245 32974 15054 32974 15243 32974 15243 32975 15244 32975 15245 32975 15245 32976 15244 32976 15246 32976 15060 32977 15049 32977 15064 32977 15080 32978 15247 32978 15081 32978 15085 32979 15247 32979 15087 32979 15095 32980 15062 32980 15096 32980 15096 32981 15062 32981 15108 32981 15055 32982 15098 32982 15091 32982 15048 32983 15248 32983 15049 32983 15048 32984 15249 32984 15248 32984 15068 32985 15077 32985 15250 32985 15076 32986 15252 32986 15077 32986 15077 32987 15252 32987 15250 32987 15254 32988 15251 32988 15250 32988 15253 32989 15241 32989 15255 32989 15235 32990 15255 32990 15241 32990 15255 32991 15070 32991 15254 32991 15064 32992 15256 32992 15065 32992 15054 32993 15257 32993 15055 32993 15054 32994 15063 32994 15257 32994 15257 32995 15063 32995 15258 32995 15062 32996 15065 32996 15258 32996 15259 32997 15254 32997 15260 32997 15261 32998 15262 32998 15260 32998 15256 32999 15264 32999 15258 32999 15258 33000 15264 33000 15265 33000 15266 33001 15267 33001 15257 33001 15266 33002 15258 33002 15265 33002 15078 33003 15115 33003 15076 33003 15076 33004 15115 33004 15253 33004 15253 33005 15113 33005 15241 33005 15066 33006 15251 33006 15111 33006 15067 33007 15066 33007 15111 33007 15072 33008 15112 33008 15251 33008 15251 33009 15112 33009 15111 33009 15058 33010 15057 33010 15094 33010 15094 33011 15062 33011 15095 33011 15050 33012 15099 33012 15048 33012 15048 33013 15099 33013 15249 33013 15055 33014 15099 33014 15098 33014 15069 33015 15071 33015 15240 33015 15142 33016 15148 33016 15154 33016 15106 33017 15061 33017 15247 33017 15108 33018 15061 33018 15106 33018 15052 33019 15242 33019 15053 33019 15202 33020 15069 33020 15240 33020 15202 33021 15240 33021 15198 33021 15104 33022 15069 33022 2086 33022 15073 33023 15075 33023 15241 33023 15068 33024 15067 33024 15101 33024 15109 33025 2806 33025 15164 33025 15060 33026 15097 33026 15092 33026 3496 33027 15135 33027 15140 33027 15128 33028 2133 33028 15143 33028 15147 33029 15143 33029 15231 33029 15118 33030 3544 33030 15116 33030 15116 33031 15136 33031 15121 33031 15118 33032 15120 33032 15138 33032 3497 33033 15130 33033 15122 33033 15267 33034 15266 33034 15263 33034 15268 33035 15269 33035 15270 33035 15275 33036 15276 33036 15277 33036 15278 33037 15279 33037 15280 33037 15281 33038 15282 33038 15283 33038 15281 33039 15283 33039 15284 33039 15287 33040 15288 33040 15289 33040 15287 33041 15290 33041 15288 33041 15294 33042 15297 33042 15298 33042 15301 33043 15300 33043 15302 33043 15303 33044 15301 33044 15302 33044 15303 33045 15304 33045 15301 33045 15303 33046 15306 33046 15307 33046 15309 33047 15310 33047 15311 33047 15270 33048 15271 33048 4999 33048 15276 33049 15319 33049 15277 33049 15320 33050 15268 33050 15313 33050 15320 33051 15321 33051 15268 33051 15329 33052 15330 33052 15331 33052 15315 33053 15331 33053 15330 33053 15331 33054 15315 33054 15318 33054 15319 33055 15318 33055 15315 33055 15334 33056 15293 33056 15335 33056 15337 33057 15335 33057 15293 33057 15338 33058 15339 33058 15340 33058 15340 33059 15339 33059 15341 33059 15342 33060 15341 33060 15339 33060 15344 33061 15345 33061 15346 33061 15346 33062 15345 33062 15347 33062 15348 33063 15349 33063 15347 33063 15350 33064 15349 33064 15348 33064 15343 33065 15351 33065 15352 33065 15343 33066 15338 33066 15353 33066 15358 33067 15340 33067 15352 33067 15343 33068 15357 33068 15351 33068 15351 33069 15357 33069 15360 33069 15363 33070 15364 33070 15365 33070 15366 33071 15363 33071 15365 33071 15367 33072 15346 33072 15368 33072 15370 33073 15344 33073 15362 33073 15369 33074 15368 33074 15371 33074 15374 33075 15305 33075 15373 33075 15369 33076 15300 33076 15367 33076 15357 33077 15355 33077 15375 33077 15375 33078 15310 33078 15357 33078 15312 33079 15381 33079 15382 33079 15271 33080 15380 33080 15312 33080 15314 33081 15315 33081 15383 33081 15372 33082 15384 33082 15330 33082 15384 33083 15385 33083 15330 33083 15364 33084 15386 33084 15365 33084 15387 33085 15386 33085 15344 33085 15387 33086 15388 33086 15386 33086 15322 33087 15389 33087 15388 33087 15389 33088 15296 33088 15284 33088 15390 33089 15389 33089 15284 33089 15284 33090 15391 33090 15390 33090 15392 33091 15391 33091 15326 33091 15352 33092 15393 33092 15392 33092 15309 33093 15312 33093 15382 33093 15394 33094 15397 33094 15395 33094 15394 33095 15398 33095 15397 33095 15395 33096 15377 33096 15376 33096 15395 33097 15399 33097 15396 33097 15398 33098 15400 33098 15401 33098 15402 33099 15403 33099 15401 33099 15404 33100 15403 33100 15402 33100 15404 33101 15405 33101 15403 33101 15405 33102 15404 33102 15406 33102 15404 33103 15399 33103 15406 33103 15413 33104 15407 33104 15414 33104 15413 33105 15415 33105 15407 33105 15410 33106 15412 33106 15391 33106 15412 33107 15416 33107 15417 33107 15415 33108 15381 33108 15418 33108 15351 33109 15360 33109 15393 33109 15285 33110 15420 33110 15421 33110 15375 33111 15423 33111 15422 33111 15326 33112 15327 33112 15359 33112 4658 33113 15359 33113 15327 33113 15359 33114 4658 33114 15285 33114 15359 33115 15285 33115 15354 33115 15370 33116 15291 33116 4657 33116 15424 33117 15370 33117 4657 33117 15370 33118 15424 33118 15387 33118 15387 33119 15425 33119 15337 33119 15337 33120 15425 33120 15335 33120 15387 33121 15337 33121 15322 33121 15412 33122 15417 33122 15390 33122 15389 33123 15390 33123 15417 33123 15397 33124 15389 33124 15417 33124 15391 33125 15409 33125 15410 33125 15392 33126 15393 33126 15414 33126 15401 33127 15386 33127 15388 33127 15393 33128 15413 33128 15414 33128 15384 33129 15403 33129 15405 33129 15384 33130 15386 33130 15403 33130 15380 33131 15419 33131 15381 33131 15381 33132 15413 33132 15382 33132 15405 33133 15385 33133 15384 33133 15376 33134 15378 33134 15395 33134 15395 33135 15378 33135 15419 33135 15419 33136 15383 33136 15395 33136 15419 33137 15380 33137 15383 33137 15399 33138 15383 33138 15406 33138 15406 33139 15315 33139 15385 33139 15426 33140 15398 33140 15394 33140 15428 33141 15399 33141 15404 33141 15305 33142 15402 33142 15304 33142 15304 33143 15402 33143 15429 33143 15301 33144 15304 33144 15429 33144 15430 33145 15301 33145 15429 33145 15301 33146 15430 33146 15299 33146 15402 33147 15299 33147 15404 33147 15299 33148 15402 33148 15305 33148 15427 33149 15426 33149 15428 33149 15429 33150 15402 33150 15400 33150 15427 33151 15429 33151 15400 33151 15431 33152 15412 33152 15411 33152 15431 33153 15416 33153 15412 33153 15432 33154 15415 33154 15433 33154 15433 33155 15415 33155 15418 33155 15433 33156 15418 33156 15434 33156 15375 33157 15407 33157 15423 33157 15423 33158 15407 33158 15435 33158 15423 33159 15435 33159 15436 33159 15423 33160 15436 33160 15421 33160 15436 33161 15408 33161 15421 33161 15421 33162 15408 33162 15285 33162 15408 33163 15407 33163 15285 33163 15433 33164 15437 33164 15431 33164 15431 33165 15437 33165 15416 33165 15410 33166 15408 33166 15411 33166 15433 33167 15436 33167 15435 33167 15431 33168 15436 33168 15433 33168 15433 33169 15435 33169 15432 33169 15285 33170 15375 33170 15439 33170 15375 33171 15438 33171 15439 33171 15404 33172 15299 33172 15430 33172 15360 33173 15357 33173 15309 33173 15344 33174 15370 33174 15387 33174 15358 33175 15326 33175 15359 33175 15270 33176 4999 33176 15311 33176 15440 33177 15441 33177 15442 33177 15444 33178 15442 33178 15443 33178 15442 33179 15446 33179 15449 33179 15449 33180 15446 33180 15447 33180 15451 33181 15441 33181 15422 33181 15348 33182 15344 33182 15350 33182 15368 33183 15452 33183 15453 33183 15454 33184 15455 33184 15452 33184 15455 33185 15454 33185 15366 33185 15454 33186 15363 33186 15366 33186 15455 33187 15366 33187 15371 33187 15341 33188 15343 33188 15340 33188 15356 33189 15456 33189 15457 33189 15456 33190 15458 33190 15457 33190 15347 33191 15349 33191 15346 33191 15454 33192 15346 33192 15363 33192 15454 33193 15452 33193 15346 33193 15342 33194 15339 33194 15338 33194 15457 33195 15458 33195 15353 33195 15461 33196 15460 33196 15450 33196 15446 33197 15461 33197 15450 33197 15446 33198 15462 33198 15461 33198 15464 33199 15444 33199 15463 33199 15465 33200 15289 33200 15463 33200 15445 33201 15465 33201 15463 33201 15463 33202 15288 33202 15461 33202 15288 33203 15459 33203 15461 33203 15463 33204 15461 33204 15464 33204 15464 33205 15461 33205 15462 33205 15462 33206 15446 33206 15464 33206 15464 33207 15446 33207 15444 33207 15420 33208 15465 33208 15451 33208 15450 33209 15460 33209 15307 33209 15307 33210 15460 33210 15303 33210 15303 33211 15460 33211 15291 33211 15425 33212 15466 33212 15335 33212 15466 33213 15334 33213 15335 33213 15442 33214 15467 33214 15440 33214 15442 33215 15468 33215 15467 33215 15447 33216 15448 33216 15469 33216 15272 33217 15274 33217 15467 33217 15469 33218 15272 33218 15467 33218 15469 33219 15280 33219 15272 33219 15442 33220 15449 33220 15468 33220 15300 33221 15471 33221 15302 33221 15308 33222 15471 33222 15448 33222 15317 33223 15279 33223 15318 33223 15318 33224 15279 33224 15331 33224 15310 33225 15273 33225 15313 33225 15441 33226 15274 33226 15422 33226 15422 33227 15274 33227 15375 33227 15269 33228 15474 33228 15271 33228 15269 33229 15475 33229 15474 33229 15476 33230 15281 33230 15284 33230 15296 33231 15298 33231 15476 33231 15290 33232 15478 33232 15288 33232 15297 33233 15479 33233 15298 33233 15297 33234 15466 33234 15479 33234 15459 33235 15479 33235 15466 33235 15459 33236 15288 33236 15479 33236 15479 33237 15288 33237 15478 33237 15272 33238 15481 33238 15273 33238 15484 33239 15478 33239 15476 33239 15298 33240 15484 33240 15476 33240 15486 33241 15479 33241 15483 33241 15483 33242 15479 33242 15478 33242 15485 33243 15486 33243 15484 33243 15484 33244 15486 33244 15483 33244 15487 33245 15480 33245 15488 33245 15482 33246 15487 33246 15489 33246 15490 33247 15488 33247 15481 33247 15481 33248 15482 33248 15490 33248 15490 33249 15482 33249 15489 33249 15488 33250 15490 33250 15487 33250 15487 33251 15490 33251 15489 33251 15293 33252 15336 33252 15294 33252 15294 33253 15336 33253 15297 33253 15281 33254 15477 33254 15332 33254 15477 33255 15333 33255 15332 33255 15275 33256 15473 33256 15316 33256 15276 33257 15275 33257 15316 33257 15473 33258 15279 33258 15316 33258 15268 33259 15321 33259 15269 33259 15269 33260 15321 33260 15475 33260 15273 33261 15321 33261 15320 33261 15278 33262 15280 33262 15471 33262 15287 33263 15289 33263 15465 33263 15373 33264 15361 33264 15374 33264 15361 33265 15367 33265 15374 33265 15354 33266 15438 33266 15355 33266 15292 33267 15291 33267 15460 33267 15331 33268 15278 33268 15329 33268 15300 33269 15329 33269 15278 33269 15286 33270 15327 33270 15287 33270 15425 33271 15292 33271 15466 33271 15328 33272 15284 33272 15323 33272 15470 33273 15449 33273 15447 33273 4644 33274 15319 33274 15315 33274 15284 33275 15283 33275 15323 33275 15337 33276 15295 33276 15322 33276 15343 33277 5342 33277 15458 33277 15343 33278 15456 33278 15357 33278 15363 33279 15346 33279 15349 33279 15349 33280 15350 33280 15363 33280 15366 33281 3972 33281 15363 33281 3972 33282 15366 33282 3973 33282 15366 33283 15363 33283 3973 33283 15369 33284 15329 33284 15300 33284 15493 33285 15494 33285 15495 33285 15494 33286 15496 33286 15495 33286 15499 33287 15500 33287 15501 33287 15500 33288 15502 33288 15501 33288 15505 33289 15506 33289 15507 33289 15505 33290 15507 33290 15508 33290 15509 33291 15510 33291 6431 33291 15511 33292 15509 33292 6431 33292 15512 33293 15513 33293 15514 33293 6485 33294 15517 33294 15518 33294 15518 33295 15520 33295 15521 33295 15522 33296 15504 33296 15523 33296 15523 33297 15504 33297 15524 33297 15525 33298 15526 33298 15524 33298 15525 33299 15527 33299 15526 33299 15526 33300 15523 33300 15524 33300 15530 33301 15528 33301 15529 33301 15534 33302 6621 33302 15535 33302 15531 33303 6621 33303 15533 33303 15495 33304 15496 33304 15533 33304 15539 33305 15540 33305 15506 33305 15506 33306 15540 33306 15507 33306 15541 33307 15542 33307 15493 33307 6485 33308 15519 33308 15543 33308 15543 33309 15519 33309 15544 33309 6431 33310 15545 33310 15511 33310 15546 33311 15547 33311 6519 33311 6623 33312 15550 33312 15536 33312 6623 33313 15551 33313 15550 33313 15551 33314 6623 33314 15552 33314 15540 33315 15539 33315 6623 33315 15556 33316 15546 33316 15510 33316 15557 33317 15516 33317 15558 33317 15557 33318 15559 33318 15516 33318 15553 33319 15558 33319 15516 33319 15564 33320 15565 33320 15561 33320 15561 33321 15565 33321 15563 33321 15565 33322 15564 33322 15566 33322 15567 33323 15568 33323 15569 33323 15570 33324 15567 33324 15569 33324 15571 33325 15572 33325 15569 33325 15573 33326 15572 33326 15571 33326 15574 33327 15491 33327 15575 33327 15575 33328 15576 33328 15574 33328 15562 33329 15577 33329 15560 33329 15577 33330 15562 33330 7298 33330 7298 33331 15562 33331 15563 33331 15566 33332 15581 33332 15563 33332 15581 33333 15566 33333 15576 33333 15582 33334 15491 33334 5800 33334 15491 33335 5798 33335 5800 33335 15584 33336 15583 33336 15570 33336 15585 33337 15573 33337 15586 33337 15584 33338 15589 33338 5850 33338 5850 33339 15589 33339 5849 33339 15586 33340 15567 33340 15590 33340 5849 33341 15591 33341 5850 33341 15591 33342 5849 33342 15592 33342 5849 33343 15588 33343 15592 33343 15593 33344 15522 33344 15527 33344 15550 33345 15503 33345 15591 33345 5850 33346 6501 33346 15522 33346 5800 33347 15578 33347 6848 33347 15595 33348 6848 33348 15578 33348 6848 33349 15532 33349 5800 33349 15596 53 15597 53 15598 53 15598 33350 15597 33350 15599 33350 15508 33351 15600 33351 15496 33351 15600 33352 15601 33352 15496 33352 15496 33353 15601 33353 15533 33353 15592 33354 15602 33354 15550 33354 15587 33355 15604 33355 15602 33355 15605 33356 15606 33356 15604 33356 15544 33357 15607 33357 15606 33357 15608 33358 15511 33358 15545 33358 15581 33359 15610 33359 15549 33359 15610 33360 15609 33360 15549 33360 15576 33361 15611 33361 15610 33361 15531 33362 15611 33362 15582 33362 15612 33363 15613 33363 15614 33363 15612 33364 15615 33364 15613 33364 15606 33365 15612 33365 15616 33365 15606 33366 15616 33366 15617 33366 15615 33367 15597 33367 15613 33367 15613 33368 15597 33368 15596 33368 15613 33369 15618 33369 15614 33369 15616 33370 15620 33370 15617 33370 15621 33371 15617 33371 15622 33371 15623 33372 15621 33372 15622 33372 15624 33373 15623 33373 15618 33373 15619 33374 15618 33374 15623 33374 15625 33375 15626 33375 15627 33375 15628 33376 15626 33376 15629 33376 15630 33377 15625 33377 15631 33377 15632 33378 15630 33378 15635 33378 15582 33379 15611 33379 15575 33379 15576 33380 15610 33380 15581 33380 15587 33381 15602 33381 15592 33381 15637 33382 15638 33382 15639 33382 15640 33383 15638 33383 15641 33383 15595 33384 15642 33384 6848 33384 15549 33385 15548 33385 15580 33385 15527 33386 15643 33386 15583 33386 15605 33387 15643 33387 15543 33387 15608 33388 15609 33388 15628 33388 15615 33389 15634 33389 15597 33389 15615 33390 15607 33390 15634 33390 15609 33391 15627 33391 15628 33391 15609 33392 15610 33392 15627 33392 15606 33393 15607 33393 15615 33393 15610 33394 15611 33394 15631 33394 15617 33395 15604 33395 15606 33395 15611 33396 15630 33396 15631 33396 15602 33397 15621 33397 15624 33397 15611 33398 15533 33398 15630 33398 15601 33399 15630 33399 15533 33399 15601 33400 15636 33400 15630 33400 15624 33401 15603 33401 15602 33401 15596 33402 15598 33402 15613 33402 15646 33403 15616 33403 15644 33403 15620 33404 15616 33404 15646 33404 15644 33405 15616 33405 15612 33405 15647 33406 15614 33406 15619 33406 15647 33407 15619 33407 15648 33407 15645 33408 15614 33408 15647 33408 15527 33409 15622 33409 15649 33409 15526 33410 15649 33410 15650 33410 15523 33411 15526 33411 15650 33411 15622 33412 15522 33412 15623 33412 15647 33413 15644 33413 15645 33413 15646 33414 15650 33414 15649 33414 15620 33415 15622 33415 15617 33415 15625 33416 15632 33416 15653 33416 15653 33417 15632 33417 15654 33417 15654 33418 15632 33418 15635 33418 15640 33419 15656 33419 15657 33419 15657 33420 15626 33420 15639 33420 15639 33421 15640 33421 15657 33421 15637 33422 15625 33422 15595 33422 15654 33423 15658 33423 15652 33423 15652 33424 15658 33424 15633 33424 15626 33425 15657 33425 15651 33425 15654 33426 15657 33426 15656 33426 15656 33427 15625 33427 15653 33427 15652 33428 15657 33428 15654 33428 15654 33429 15656 33429 15653 33429 15637 33430 15595 33430 15659 33430 15623 33431 15522 33431 15648 33431 15592 33432 15550 33432 15591 33432 15586 33433 15590 33433 15605 33433 15581 33434 15549 33434 15580 33434 6623 33435 15507 33435 15540 33435 15660 33436 15661 33436 15662 33436 15662 33437 15661 33437 15663 33437 15664 33438 15662 33438 15663 33438 15663 33439 15665 33439 15664 33439 15662 33440 15664 33440 15666 33440 15529 33441 15669 33441 15667 33441 15662 33442 15666 33442 15668 33442 15663 33443 15671 33443 15672 33443 15638 33444 15672 33444 15641 33444 15571 33445 15567 33445 15573 33445 15589 33446 15673 33446 5849 33446 5849 33447 15673 33447 15674 33447 15673 33448 15676 33448 15674 33448 15676 33449 5849 33449 15674 33449 5798 33450 15492 33450 15677 33450 15678 33451 15679 33451 15677 33451 15492 33452 15678 33452 15677 33452 15491 33453 15679 33453 15678 33453 15675 33454 15673 33454 15589 33454 15677 33455 15679 33455 15560 33455 15682 33456 15681 33456 15670 33456 15666 33457 15683 33457 15682 33457 15664 33458 15665 33458 15684 33458 15686 33459 15514 33459 15684 33459 15665 33460 15686 33460 15684 33460 15684 33461 15513 33461 15682 33461 15513 33462 15680 33462 15682 33462 15684 33463 15682 33463 15685 33463 15685 33464 15682 33464 15683 33464 15637 33465 15686 33465 15638 33465 15672 33466 15686 33466 15663 33466 15530 33467 15681 33467 15528 33467 15528 33468 15681 33468 15525 33468 15643 33469 15688 33469 15558 33469 15688 33470 15557 33470 15558 33470 15501 33471 15689 33471 15690 33471 15690 33472 15689 33472 15660 33472 15662 33473 15690 33473 15660 33473 15662 33474 15691 33474 15690 33474 15667 33475 15669 33475 15692 33475 15694 33476 15695 33476 15692 33476 15669 33477 15694 33477 15692 33477 15692 33478 15695 33478 15499 33478 15690 33479 15691 33479 15692 33479 15504 33480 15694 33480 15524 33480 15524 33481 15694 33481 15529 33481 15529 33482 15694 33482 15669 33482 15539 33483 15697 33483 15552 33483 15532 33484 15500 33484 15535 33484 15500 33485 15541 33485 15535 33485 15661 33486 15689 33486 15671 33486 15641 33487 15689 33487 15642 33487 15494 33488 15498 33488 15496 33488 15496 33489 15498 33489 15696 33489 15699 33490 15509 33490 15511 33490 15699 33491 15700 33491 15509 33491 15518 33492 15521 33492 15519 33492 15519 33493 15521 33493 15699 33493 15701 33494 15700 33494 15699 33494 15520 33495 15702 33495 15521 33495 15696 33496 15703 33496 15698 33496 15497 33497 15704 33497 15498 33497 15497 33498 15500 33498 15704 33498 15499 33499 15695 33499 15704 33499 15705 33500 15698 33500 15703 33500 15707 33501 15701 33501 15699 33501 15708 33502 15702 33502 15709 33502 15708 33503 15707 33503 15521 33503 15709 33504 15702 33504 15706 33504 15706 33505 15702 33505 15701 33505 15708 33506 15709 33506 15707 33506 15707 33507 15709 33507 15706 33507 15704 33508 15705 33508 15713 33508 15710 33509 15713 33509 15712 33509 15559 33510 15557 33510 15520 33510 15520 33511 15557 33511 15688 33511 15510 33512 15509 33512 15554 33512 15700 33513 15555 33513 15554 33513 15505 33514 15698 33514 15537 33514 15506 33515 15505 33515 15537 33515 15500 33516 15542 33516 15541 33516 15697 33517 15695 33517 15694 33517 15512 33518 15514 33518 15686 33518 15593 33519 15584 33519 15594 33519 15584 33520 5850 33520 15594 33520 15694 33521 15504 33521 15697 33521 15502 33522 6848 33522 15689 33522 15512 33523 15686 33523 15548 33523 15522 33524 6501 33524 15504 33524 15532 33525 15502 33525 15500 33525 15689 33526 6848 33526 15642 33526 15687 33527 15512 33527 15548 33527 15508 33528 15507 33528 6623 33528 15495 33529 15533 33529 15534 33529 15544 33530 6518 33530 15543 33530 15573 33531 15585 33531 5819 33531 15588 33532 5846 33532 15585 33532 15574 33533 15566 33533 15564 33533 15687 33534 15548 33534 15547 33534 10684 33535 15714 33535 10685 33535 10684 33536 15715 33536 15714 33536 15715 33537 10684 33537 15716 33537 15717 33538 10711 33538 15718 33538 10741 33539 15719 33539 10740 33539 10741 33540 15718 33540 15719 33540 10741 33541 10742 33541 15718 33541 15718 33542 10742 33542 15717 33542 15716 33543 10721 33543 15715 33543 10684 33544 10687 33544 15716 33544 15716 33545 10687 33545 15721 33545 15718 33546 10712 33546 15719 33546 15721 33547 15724 33547 15722 33547 15719 33548 10713 33548 15723 33548 10740 33549 15725 33549 15726 33549 10740 33550 15723 33550 15725 33550 10712 33551 15727 33551 15728 33551 10713 33552 15729 33552 10715 33552 15725 33553 10715 33553 15730 33553 15726 33554 15730 33554 15731 33554 10725 33555 15726 33555 15731 33555 15727 33556 15732 33556 15728 33556 15728 33557 15732 33557 15729 33557 15730 33558 10716 33558 15731 33558 15729 33559 15732 33559 15734 33559 15731 33560 10716 33560 15733 33560 10726 33561 15733 33561 15736 33561 15733 33562 10719 33562 15736 33562 10727 33563 15736 33563 15738 33563 10719 33564 15740 33564 10722 33564 15736 33565 10722 33565 15738 33565 10727 33566 15738 33566 15741 33566 15737 33567 10685 33567 15740 33567 15738 33568 10722 33568 15741 33568 10728 33569 15741 33569 15720 33569 10722 33570 15715 33570 10721 33570 15741 33571 10721 33571 15720 33571 10722 33572 15740 33572 15714 33572 15721 33573 10711 33573 15716 33573 10711 33574 15721 33574 15722 33574 15717 33575 15720 33575 10711 33575 10712 33576 15722 33576 15727 33576 15719 33577 10712 33577 10713 33577 10713 33578 15728 33578 15729 33578 10715 33579 15729 33579 15734 33579 10716 33580 15735 33580 15737 33580 10726 33581 10728 33581 10742 33581 10725 33582 10742 33582 10741 33582 10725 33583 10741 33583 15726 33583 10685 33584 15739 33584 15732 33584 15732 33585 15739 33585 15734 33585 15732 33586 15727 33586 10685 33586 15742 33587 15743 33587 15744 33587 15742 33588 15745 33588 15743 33588 15745 33589 15742 33589 15746 33589 15747 33590 15746 33590 15748 33590 15749 33591 15747 33591 15748 33591 15749 33592 15750 33592 15747 33592 15751 6 15750 6 15752 6 15755 33593 15754 33593 15756 33593 15757 33594 15755 33594 15756 33594 15757 33595 15743 33595 15755 33595 15746 33596 15742 33596 15758 33596 15758 33597 15742 33597 15759 33597 15760 33598 15758 33598 15759 33598 15760 6 15759 6 15763 6 15768 33599 15769 33599 15770 33599 15760 33600 15763 33600 15764 33600 15764 33601 15765 33601 15771 33601 15753 6 15751 6 15752 6 15747 6 15745 6 15746 6 15772 33602 15767 33602 15768 33602 15749 33603 15748 33603 15773 33603 15768 33604 15775 33604 15776 33604 15772 33605 15776 33605 15777 33605 15766 33606 15777 33606 15778 33606 15760 33607 15780 33607 15781 33607 15761 33608 15781 33608 15782 33608 15749 33609 15783 33609 15784 33609 15754 33610 15786 33610 15787 33610 15768 33611 15776 33611 15772 33611 15771 33612 15779 33612 15764 33612 15764 33613 15780 33613 15760 33613 15754 33614 15787 33614 15756 33614 15788 53 15789 53 15775 53 15775 33615 15789 33615 15776 33615 15776 53 15789 53 15790 53 15777 53 15790 53 15791 53 15781 33616 15793 33616 15794 33616 15777 33617 15791 33617 15778 33617 15794 53 15795 53 15782 53 15786 33618 15798 33618 15799 33618 15787 33619 15799 33619 15800 33619 15782 33620 15795 33620 15783 33620 15783 53 15796 53 15784 53 15801 33621 15788 33621 15802 33621 15801 33622 15789 33622 15788 33622 15789 33623 15801 33623 15803 33623 15791 33624 15804 33624 15805 33624 15792 33625 15805 33625 15806 33625 15794 33626 15807 33626 15808 33626 15798 33627 15811 33627 15812 33627 15799 33628 15812 33628 15813 33628 15800 33629 15813 33629 15802 33629 15789 33630 15803 33630 15790 33630 15794 33631 15808 33631 15795 33631 15796 33632 15810 33632 15797 33632 15798 33633 15812 33633 15799 33633 15799 33634 15813 33634 15800 33634 15800 33635 15802 33635 15788 33635 15816 33636 15815 33636 15817 33636 15820 33637 15819 33637 15821 33637 15822 33638 15821 33638 15814 33638 15816 33639 15822 33639 15814 33639 15820 33640 15821 33640 15823 33640 15823 33641 15821 33641 15822 33641 15814 53 15821 53 15819 53 15834 33642 15833 33642 15835 33642 15836 33643 15835 33643 15837 33643 15838 33644 15837 33644 15839 33644 15848 33645 15847 33645 15849 33645 15852 33646 15853 33646 15854 33646 15838 33647 15839 33647 15840 33647 15842 33648 15843 33648 15845 33648 15848 33649 15849 33649 15850 33649 15850 33650 15851 33650 15853 33650 15855 33651 15825 33651 15824 33651 15855 33652 15857 33652 15825 33652 15833 33653 15861 33653 15862 33653 15833 33654 15862 33654 15835 33654 15830 33655 15859 33655 15831 33655 15831 33656 15861 33656 15833 33656 15837 33657 15863 33657 15864 33657 15839 33658 15865 33658 15866 33658 15841 33659 15867 33659 4902 33659 15841 33660 4902 33660 15868 33660 15843 33661 15868 33661 15869 33661 15837 33662 15865 33662 15839 33662 15839 33663 15867 33663 15841 33663 15841 33664 15868 33664 15843 33664 15849 33665 15872 33665 15873 33665 15853 33666 4940 33666 4937 33666 15854 33667 4937 33667 15856 33667 15854 33668 15856 33668 15824 33668 15846 33669 15871 33669 15847 33669 15847 33670 15872 33670 15849 33670 15849 33671 15873 33671 15851 33671 15851 33672 4940 33672 15853 33672 15853 33673 4937 33673 15854 33673 15874 53 15862 53 15861 53 15876 53 15861 53 15860 53 15876 33674 15860 33674 15817 33674 15817 33675 15818 33675 15877 33675 15877 53 15818 53 15878 53 15865 53 15818 53 15866 53 15876 53 15874 53 15861 53 15879 33676 15872 33676 15871 33676 15879 33677 15880 33677 15872 33677 15873 33678 15880 33678 15881 33678 15881 33679 4940 33679 15873 33679 4940 33680 15881 33680 4937 33680 4937 53 15881 53 15882 53 15822 53 15856 53 15882 53 15822 33681 15855 33681 15856 33681 15822 33682 15816 33682 4993 33682 4929 33683 15816 33683 15883 33683 15883 33684 15816 33684 15817 33684 4937 53 15882 53 15856 53 15882 33685 15885 33685 15822 33685 15822 53 15885 53 15823 53 15879 53 15823 53 15885 53 15879 53 15871 53 15823 53 15886 33686 15820 33686 15823 33686 4983 33687 15820 33687 15887 33687 4983 33688 15818 33688 15820 33688 4983 33689 15866 33689 15818 33689 15886 33690 15870 33690 15869 33690 15858 33691 15857 33691 4930 33691 15868 33692 15888 33692 15869 33692 15867 33693 4983 33693 4902 33693 15802 33694 15853 33694 15852 33694 15802 33695 15813 33695 15853 33695 15845 33696 15811 33696 15810 33696 15842 6 15810 6 15809 6 15801 6 15826 6 15803 6 15804 33697 15830 33697 15829 33697 15806 6 15832 6 15834 6 15803 6 15827 6 15804 6 15804 6 15829 6 15805 6 15806 33698 15834 33698 15807 33698 15838 6 15840 6 15808 6 15844 33699 15848 33699 15812 33699 15848 6 15850 6 15812 6 15801 33700 15802 33700 15824 33700 15824 33701 15802 33701 15852 33701 15888 33702 15762 33702 15773 33702 15886 33703 15748 33703 15746 33703 15887 33704 15886 33704 15746 33704 4902 33705 15762 33705 15888 33705 15888 33706 15773 33706 15886 33706 15884 33707 15769 33707 15767 33707 15883 33708 15767 33708 15743 33708 4993 33709 15757 33709 15769 33709 15883 33710 15743 33710 4929 33710 4929 33711 15743 33711 4993 33711 15885 33712 15755 33712 15745 33712 15880 33713 15747 33713 15751 33713 15882 33714 15755 33714 15885 33714 15885 33715 15745 33715 15879 33715 15879 33716 15747 33716 15880 33716 15744 33717 15765 33717 15874 33717 15875 33718 15763 33718 15759 33718 15878 33719 15759 33719 15742 33719 15875 33720 15759 33720 15878 33720 15892 33721 15889 33721 15893 33721 15894 33722 15893 33722 15895 33722 15896 33723 15895 33723 15897 33723 15898 33724 15899 33724 15900 33724 15904 6 15889 6 15905 6 15906 33725 15907 33725 15904 33725 15906 6 15908 6 15907 6 15905 6 15910 6 15906 6 15913 6 15891 6 15914 6 15915 6 15914 6 15916 6 15918 33726 15917 33726 15919 33726 15903 6 15919 6 15917 6 15890 6 15914 6 15891 6 15894 33727 15892 33727 15893 33727 15901 33728 15921 33728 15900 33728 15915 33729 15916 33729 15918 33729 15922 6 15909 6 15908 6 15897 33730 15909 33730 15922 33730 15923 33731 15924 33731 15919 33731 15915 33732 15924 33732 15925 33732 15899 33733 15932 33733 15933 33733 15920 33734 15928 33734 15906 33734 15906 33735 15930 33735 15908 33735 15896 33736 15932 33736 15899 33736 15900 33737 15934 33737 15902 33737 15935 33738 15923 33738 15936 33738 15935 53 15924 53 15923 53 15924 53 15935 53 15937 53 15926 53 15937 53 15938 53 15928 33739 15939 33739 15940 33739 15929 33740 15940 33740 15941 33740 15930 53 15929 53 15941 53 15925 53 15937 53 15926 53 15926 33741 15938 33741 15927 33741 15941 53 15942 53 15930 53 15931 53 15942 53 15943 53 15931 53 15943 53 15944 53 15932 53 15944 53 15945 53 15931 33742 15944 33742 15932 33742 15932 53 15945 53 15933 53 15937 33743 15948 33743 15949 33743 15938 33744 15950 33744 15951 33744 15939 33745 15951 33745 15952 33745 15941 33746 15953 33746 15954 33746 15946 33747 15958 33747 15959 33747 15938 33748 15951 33748 15939 33748 15940 33749 15953 33749 15941 33749 15941 33750 15954 33750 15942 33750 15943 33751 15955 33751 15944 33751 15944 33752 15957 33752 15945 33752 15960 33753 15961 33753 15962 33753 15964 33754 15965 33754 15966 33754 15966 33755 15967 33755 15969 33755 15960 53 15967 53 15965 53 15960 33756 15965 33756 15961 33756 15970 33757 15971 33757 15972 33757 15971 33758 15970 33758 15973 33758 15974 33759 15973 33759 15975 33759 15974 33760 15975 33760 15976 33760 15977 33761 15976 33761 15978 33761 15981 33762 15980 33762 15982 33762 15985 33763 15986 33763 15987 33763 15988 33764 15987 33764 15989 33764 15990 33765 15991 33765 15992 33765 15993 33766 15992 33766 15994 33766 15993 33767 15994 33767 15995 33767 15996 33768 15995 33768 15997 33768 15974 33769 15976 33769 15977 33769 15979 33770 15980 33770 15981 33770 15981 33771 15982 33771 15983 33771 15983 33772 15984 33772 15986 33772 15990 33773 15992 33773 15993 33773 15970 33774 16004 33774 15973 33774 15975 33775 16005 33775 16006 33775 15978 33776 16007 33776 16008 33776 15978 33777 16008 33777 16009 33777 15980 33778 16009 33778 16010 33778 15980 33779 16010 33779 15982 33779 15973 33780 16005 33780 15975 33780 15986 33781 16012 33781 16013 33781 15989 33782 16014 33782 16015 33782 15989 33783 16015 33783 16016 33783 15991 33784 16016 33784 16017 33784 15986 33785 16013 33785 15987 33785 16017 33786 16018 33786 15992 33786 15992 33787 16018 33787 15994 33787 15994 33788 16018 33788 1198 33788 15997 33789 16019 33789 16020 33789 15999 33790 16020 33790 16021 33790 15972 33791 16003 33791 15970 33791 15995 33792 16019 33792 15997 33792 15997 33793 16020 33793 15999 33793 15999 33794 16021 33794 16001 33794 16011 33795 16010 33795 16022 33795 16024 33796 16008 33796 15963 33796 15963 53 15964 53 16025 53 16013 33797 15964 33797 16014 33797 16013 33798 16026 33798 15964 33798 16013 53 16012 53 16026 53 16026 53 16012 53 16023 53 16027 33799 16028 33799 16019 33799 16029 33800 16030 33800 16021 33800 16031 33801 15962 33801 16032 33801 16007 33802 15963 33802 16008 33802 16019 33803 16028 33803 16020 33803 16021 33804 16030 33804 16003 33804 16030 33805 16034 33805 15968 33805 16027 53 15969 53 16034 53 16027 33806 1198 33806 15969 33806 15969 33807 1198 33807 16018 33807 16035 53 16018 53 16036 53 16037 53 15966 53 16035 53 16017 53 16039 53 16036 53 16031 53 16040 53 16002 53 16002 33808 16040 33808 16004 33808 16041 33809 16005 33809 16004 33809 16005 33810 16041 33810 16033 33810 16006 33811 16005 33811 16033 33811 16014 33812 16037 33812 16015 33812 15998 6 15959 6 15958 6 15993 6 15957 6 15956 6 15988 6 15955 6 15954 6 15985 33813 15954 33813 15986 33813 15948 33814 15973 33814 15974 33814 15949 6 15974 6 15977 6 15948 33815 15974 33815 15949 33815 15952 33816 15983 33816 15953 33816 15990 33817 15993 33817 15956 33817 15971 6 15947 6 16000 6 15893 33818 15904 33818 16035 33818 16035 33819 15904 33819 16037 33819 16037 33820 15904 33820 15907 33820 16039 33821 15909 33821 16036 33821 16036 33822 15895 33822 16035 33822 16032 33823 15914 33823 15890 33823 16040 33824 15903 33824 15917 33824 16032 33825 15890 33825 16031 33825 16031 33826 15903 33826 16040 33826 16029 33827 15898 33827 15921 33827 16030 33828 15901 33828 16034 33828 16028 33829 15898 33829 16029 33829 16024 33830 15912 33830 16022 33830 16022 33831 15912 33831 15910 33831 16025 33832 15905 33832 15889 33832 16024 33833 15889 33833 15891 33833 16026 33834 15905 33834 16025 33834 16025 33835 15889 33835 16024 33835 16049 33836 16048 33836 16050 33836 16049 6 16047 6 16048 6 16051 33837 16052 33837 16053 33837 16054 6 16053 6 16055 6 16056 33838 16058 33838 16055 33838 16045 33839 16056 33839 16043 33839 16060 33840 16046 33840 16059 33840 16060 33841 16059 33841 16063 33841 16063 33842 16059 33842 16064 33842 16067 33843 16066 33843 16044 33843 16069 6 16068 6 16070 6 16057 33844 16055 33844 16072 33844 16063 6 16064 6 16065 6 16047 33845 16045 33845 16046 33845 16058 6 16054 6 16055 6 16073 33846 16061 33846 16074 33846 16072 33847 16075 33847 16071 33847 16065 33848 16077 33848 16078 33848 16060 33849 16079 33849 16080 33849 16062 33850 16080 33850 16081 33850 16074 33851 16081 33851 16082 33851 16050 33852 16082 33852 16083 33852 16055 33853 16085 33853 16086 33853 16055 33854 16086 33854 16075 33854 16067 33855 16077 33855 16065 33855 16065 33856 16078 33856 16063 33856 16049 33857 16083 33857 16052 33857 16053 33858 16085 33858 16055 33858 16076 53 16088 53 16089 53 16080 33859 16092 33859 16093 33859 16080 53 16093 53 16081 53 16076 33860 16089 33860 16077 33860 16077 33861 16090 33861 16078 33861 16082 53 16094 53 16095 53 16084 53 16096 53 16097 53 16085 53 16097 53 16098 53 16086 53 16098 53 16087 53 16075 53 16086 53 16087 53 16082 53 16095 53 16083 53 16083 33862 16096 33862 16084 33862 16084 33863 16097 33863 16085 33863 16085 33864 16098 33864 16086 33864 16089 33865 16101 33865 16102 33865 16091 33866 16103 33866 16104 33866 16092 33867 16104 33867 16105 33867 16093 33868 16105 33868 16106 33868 16094 33869 16106 33869 16107 33869 16089 33870 16103 33870 16090 33870 16090 33871 16103 33871 16091 33871 16092 33872 16105 33872 16093 33872 16094 33873 16107 33873 16095 33873 16098 33874 16100 33874 16087 33874 16111 33875 16112 33875 16113 33875 16113 33876 16112 33876 16114 33876 16117 33877 16116 33877 16118 33877 16113 33878 16119 33878 16111 33878 16114 33879 16112 33879 16115 33879 16121 33880 16122 33880 16123 33880 16128 33881 16129 33881 16130 33881 16133 33882 16132 33882 16134 33882 16137 33883 16136 33883 16138 33883 16144 33884 16145 33884 16146 33884 16149 33885 16148 33885 16150 33885 16151 33886 16150 33886 16123 33886 16131 33887 16132 33887 16133 33887 16135 33888 16136 33888 16137 33888 16137 33889 16138 33889 16139 33889 16141 33890 16143 33890 16145 33890 16144 33891 16146 33891 16147 33891 16147 33892 16148 33892 16149 33892 16149 33893 16150 33893 16151 33893 16152 33894 16121 33894 16153 33894 16152 33895 16124 33895 16121 33895 16125 33896 3039 33896 16154 33896 16129 33897 16155 33897 16156 33897 16130 33898 16156 33898 16157 33898 16132 33899 16158 33899 16159 33899 16132 33900 16159 33900 16134 33900 16129 33901 16156 33901 16130 33901 16136 33902 16160 33902 16161 33902 16138 33903 16162 33903 16163 33903 16140 33904 16165 33904 16166 33904 16134 33905 16160 33905 16136 33905 16138 33906 16164 33906 16140 33906 16140 33907 16166 33907 16142 33907 16145 33908 16168 33908 16169 33908 16146 33909 16169 33909 16170 33909 16123 33910 16172 33910 16153 33910 16160 33911 16159 33911 16173 33911 16173 53 16159 53 16158 53 16175 33912 16158 33912 16157 33912 16175 33913 16157 33913 16114 33913 16114 33914 16176 33914 16175 33914 16114 33915 16115 33915 16176 33915 16176 33916 16115 33916 16177 33916 16162 53 16161 53 16177 53 16177 53 16161 53 16174 53 16174 33917 16161 33917 16160 33917 16175 53 16173 53 16158 53 16178 33918 16170 33918 16169 33918 16180 33919 16181 33919 16172 33919 16119 33920 16152 33920 16153 33920 16119 33921 16113 33921 3048 33921 3048 33922 16113 33922 16182 33922 16156 53 16182 53 16114 53 16156 33923 16155 33923 16183 33923 16172 33924 16181 33924 16153 33924 16119 33925 16185 33925 16120 33925 16178 53 16120 53 16185 53 16186 33926 16117 33926 16120 33926 3071 33927 16117 33927 16186 33927 3071 33928 16115 33928 16117 33928 3071 33929 16163 33929 16115 33929 3071 33930 16164 33930 16163 33930 16164 33931 3071 33931 3073 33931 16152 33932 3047 33932 3039 33932 3039 33933 3047 33933 3046 33933 3046 33934 16154 33934 3039 33934 16154 33935 3046 33935 16184 33935 16155 33936 16154 33936 16184 33936 16147 6 16110 6 16109 6 16144 6 16109 6 16108 6 16142 33937 16107 33937 16106 33937 16099 33938 16125 33938 16101 33938 16102 33939 16126 33939 16129 33939 16102 33940 16129 33940 16128 33940 16103 6 16128 6 16131 6 16104 6 16131 6 16133 6 16137 33941 16139 33941 16105 33941 16142 33942 16141 33942 16107 33942 16141 33943 16145 33943 16108 33943 16145 33944 16144 33944 16108 33944 16147 6 16149 6 16110 6 16099 6 16100 6 16122 6 16122 6 16100 6 16151 6 16046 33945 16186 33945 16048 33945 16186 33946 16046 33946 3071 33946 3073 33947 16061 33947 16073 33947 3071 33948 16061 33948 3073 33948 3073 33949 16073 33949 16188 33949 16182 33950 16068 33950 16043 33950 3048 33951 16043 33951 16056 33951 3047 33952 16056 33952 16057 33952 16184 33953 16070 33953 16183 33953 16183 33954 16068 33954 16182 33954 3047 33955 16057 33955 3046 33955 16179 33956 16047 33956 16051 33956 16181 33957 16180 33957 16054 33957 16185 33958 16045 33958 16178 33958 16179 33959 16051 33959 16180 33959 16044 33960 16066 33960 16173 33960 16177 33961 16059 33961 16042 33961 16173 33962 16066 33962 16174 33962 16193 33963 16195 33963 16194 33963 16196 33964 12834 33964 12833 33964 12832 33965 12834 33965 16196 33965 16196 33966 16197 33966 16199 33966 16199 33967 16197 33967 16198 33967 16200 33968 16201 33968 16202 33968 16204 33969 16207 33969 16206 33969 16206 33970 16207 33970 16208 33970 16207 33971 16209 33971 16208 33971 16208 33972 16209 33972 16210 33972 16211 33973 16212 33973 16213 33973 16213 33974 16212 33974 16214 33974 16215 33975 16211 33975 16216 33975 16216 33976 16211 33976 16213 33976 16217 33977 16215 33977 16218 33977 16218 33978 16215 33978 16216 33978 16206 33979 16208 33979 16218 33979 16218 33980 16208 33980 16214 33980 16213 33981 16210 33981 16205 33981 16216 33982 16205 33982 16218 33982 16193 33983 16222 33983 16219 33983 12832 33984 16223 33984 16198 33984 16196 33985 16199 33985 16225 33985 16198 33986 16226 33986 16199 33986 16226 33987 16198 33987 16223 33987 16227 33988 16226 33988 16223 33988 16227 33989 16228 33989 16226 33989 16224 33990 16196 33990 16225 33990 16219 33991 16222 33991 16224 33991 16218 33992 16201 33992 16217 33992 16232 33993 16233 33993 16234 33993 16233 33994 16229 33994 16234 33994 16236 33995 13097 33995 16237 33995 16238 33996 13096 33996 13098 33996 16239 33997 13098 33997 13099 33997 16240 33998 13099 33998 13093 33998 16242 33999 13056 33999 16243 33999 16244 34000 16243 34000 16245 34000 16246 34001 16245 34001 16247 34001 16252 34002 16251 34002 13090 34002 16235 34003 16252 34003 13090 34003 16238 34004 13098 34004 16239 34004 16241 34005 13056 34005 16242 34005 16242 34006 16243 34006 16244 34006 16246 34007 16247 34007 16248 34007 16248 34008 16249 34008 16250 34008 16250 34009 16251 34009 16252 34009 13062 34010 13063 34010 16253 34010 16253 34011 13063 34011 16254 34011 16254 34012 13063 34012 13064 34012 16256 34013 13089 34013 13065 34013 16257 34014 13065 34014 13057 34014 16258 34015 13057 34015 13058 34015 16260 34016 13060 34016 13059 34016 16261 34017 13059 34017 13061 34017 16262 34018 13061 34018 13081 34018 16263 34019 13081 34019 13082 34019 16235 34020 13082 34020 13091 34020 16252 34021 13091 34021 13090 34021 16250 34022 16252 34022 13090 34022 16255 34023 13089 34023 16256 34023 16256 34024 13065 34024 16257 34024 16257 34025 13057 34025 16258 34025 16259 34026 13060 34026 16260 34026 16262 34027 13081 34027 16263 34027 16251 34028 13062 34028 13090 34028 16251 34029 13063 34029 13062 34029 16251 34030 16249 34030 13063 34030 13064 34031 16249 34031 16247 34031 13089 34032 16247 34032 16245 34032 13065 34033 16243 34033 13057 34033 13060 34034 13099 34034 13059 34034 13059 34035 13098 34035 13061 34035 13081 34036 13097 34036 13082 34036 16250 34037 16264 34037 16252 34037 16250 34038 16253 34038 16264 34038 16264 34039 16253 34039 16265 34039 16265 34040 16253 34040 16254 34040 16266 34041 16255 34041 16256 34041 16267 34042 16257 34042 16258 34042 16268 34043 16263 34043 16235 34043 16268 34044 16269 34044 16263 34044 16258 34045 16259 34045 16267 34045 16261 34046 16270 34046 16260 34046 16260 34047 16270 34047 16259 34047 16266 34048 16265 34048 16255 34048 16227 34049 16223 34049 16271 34049 16273 34050 16264 34050 16274 34050 16272 34051 16267 34051 16223 34051 16223 34052 16267 34052 16271 34052 16271 34053 16270 34053 16269 34053 16269 34054 16268 34054 16227 34054 16235 34055 16236 34055 16239 34055 16238 34056 16236 34056 16237 34056 16252 34057 16241 34057 16250 34057 16248 34058 16242 34058 16244 34058 16275 34059 16227 34059 16273 34059 16276 34060 16272 34060 16223 34060 16277 34061 16225 34061 16278 34061 16220 34062 16219 34062 16189 34062 16189 34063 16219 34063 16277 34063 16226 34064 16220 34064 16191 34064 16225 34065 16226 34065 16278 34065 16222 34066 16276 34066 16224 34066 16203 34067 16215 34067 16217 34067 16215 34068 16209 34068 16211 34068 16211 34069 16209 34069 16212 34069 16212 34070 16209 34070 16207 34070 16204 34071 16212 34071 16207 34071 16212 34072 16217 34072 16233 34072 16233 34073 16279 34073 16222 34073 16275 34074 16280 34074 16228 34074 16228 34075 16280 34075 16221 34075 16195 34076 16234 34076 16276 34076 16195 34077 16194 34077 16234 34077 16231 34078 16197 34078 16234 34078 16200 34079 16202 34079 16280 34079 16275 34080 16200 34080 16280 34080 16202 34081 16200 34081 16231 34081 16202 34082 16231 34082 16229 34082 16197 34083 16273 34083 16272 34083 12834 34084 16197 34084 16272 34084 16281 34085 16282 34085 16283 34085 16281 3 16284 3 16282 3 16283 34086 16287 34086 16281 34086 16281 3 16285 3 16284 3 16281 34087 16286 34087 16285 34087 16281 34088 16287 34088 16286 34088 16289 6 16287 6 16283 6 16288 34089 16286 34089 16287 34089 16288 8 16287 8 16290 8 16290 34090 16287 34090 16289 34090 16290 34091 16292 34091 16291 34091 16293 34092 16290 34092 16291 34092 16290 34093 16289 34093 16292 34093 16293 34094 16288 34094 16290 34094 16293 34095 16294 34095 16297 34095 16291 34096 16294 34096 16293 34096 16295 34097 16288 34097 16293 34097 16293 34098 16296 34098 16295 34098 16297 34099 16296 34099 16293 34099 16294 34100 16298 34100 16297 34100 16297 34101 16298 34101 16299 34101 16300 34102 16296 34102 16297 34102 16300 34103 16297 34103 16299 34103 16299 34104 16301 34104 16300 34104 16301 34105 16302 34105 16300 34105 16302 34106 16303 34106 16300 34106 16300 34107 16303 34107 16296 34107 16303 34108 16302 34108 16304 34108 16296 34109 16303 34109 16307 34109 16305 34110 16303 34110 16304 34110 16303 34111 16305 34111 16306 34111 16303 34112 16306 34112 16307 34112 16307 34113 16308 34113 16295 34113 16308 34114 16307 34114 16310 34114 16309 34115 16307 34115 16306 34115 16309 34116 16311 34116 16307 34116 16307 34117 16311 34117 16310 34117 16295 34118 16296 34118 16307 34118 16311 34119 16304 34119 16302 34119 16310 34120 16311 34120 16302 34120 16304 34121 16311 34121 16312 34121 16309 34122 16312 34122 16311 34122 16313 34123 16314 34123 16312 34123 16313 34124 16312 34124 16309 34124 16316 34125 16304 34125 16312 34125 16312 6 16314 6 16315 6 16316 34126 16312 34126 16315 34126 16316 34127 16317 34127 16319 34127 16316 34128 16315 34128 16317 34128 16318 34129 16304 34129 16316 34129 16316 34130 16320 34130 16318 34130 16319 34131 16321 34131 16316 34131 16316 34132 16321 34132 16320 34132 16319 34133 16323 34133 16321 34133 16322 34134 16321 34134 16323 34134 16301 34135 16321 34135 16322 34135 16321 34136 16324 34136 16320 34136 16321 34137 16301 34137 16324 34137 16325 34138 16324 34138 16299 34138 16325 34139 16326 34139 16324 34139 16324 34140 16301 34140 16299 34140 16326 34141 16320 34141 16324 34141 16327 34142 16326 34142 16329 34142 16328 34143 16326 34143 16327 34143 16326 34144 16328 34144 16320 34144 16325 34145 16330 34145 16326 34145 16326 34146 16330 34146 16329 34146 16331 34147 16330 34147 16332 34147 16329 34148 16330 34148 16331 34148 16330 34149 16325 34149 16334 34149 16332 34150 16330 34150 16333 34150 16333 34151 16330 34151 16334 34151 16335 34152 16334 34152 16298 34152 16335 34153 16333 34153 16334 34153 16298 34154 16334 34154 16325 34154 16331 34155 16335 34155 16294 34155 16294 34156 16335 34156 16298 34156 16335 34157 16331 34157 16337 34157 16335 34158 16337 34158 16336 34158 16336 34159 16333 34159 16335 34159 16338 34160 16337 34160 16331 34160 16338 34161 16339 34161 16337 34161 16339 34162 16341 34162 16337 34162 16336 34163 16337 34163 16340 34163 16337 34164 16342 34164 16340 34164 16341 34165 16342 34165 16337 34165 16341 53 16344 53 16342 53 16342 53 16344 53 16343 53 16342 34166 16343 34166 16340 34166 16344 53 16341 53 16345 53 16352 34167 16344 34167 16345 34167 16346 53 16353 53 16344 53 16346 53 16344 53 16348 53 16344 34168 16350 34168 16347 34168 16349 53 16344 53 16347 53 16348 53 16344 53 16349 53 16344 34169 16351 34169 16350 34169 16351 34170 16344 34170 16352 34170 16343 53 16344 53 16353 53 16354 34171 16343 34171 16353 34171 16354 34172 16353 34172 16355 34172 16355 34173 16353 34173 16346 34173 16318 34174 16355 34174 16304 34174 16304 34175 16355 34175 16357 34175 16356 34176 16354 34176 16355 34176 16318 6 16356 6 16355 6 16357 34177 16355 34177 16346 34177 16357 34178 16346 34178 16358 34178 16358 34179 16304 34179 16357 34179 16305 34180 16304 34180 16358 34180 16305 34181 16358 34181 16306 34181 16346 34182 16359 34182 16358 34182 16358 34183 16359 34183 16306 34183 16348 34184 16359 34184 16346 34184 16348 34185 16360 34185 16359 34185 16359 34186 16360 34186 16306 34186 16360 53 16348 53 16361 53 16360 34187 16361 34187 16313 34187 16306 34188 16360 34188 16313 34188 16314 34189 16361 34189 16362 34189 16313 34190 16361 34190 16314 34190 16361 53 16348 53 16362 53 16314 34191 16362 34191 16315 34191 16315 34192 16362 34192 16363 34192 16348 53 16363 53 16362 53 16364 34193 16315 34193 16363 34193 16364 34194 16363 34194 16366 34194 16363 34195 16348 34195 16365 34195 16363 34196 16365 34196 16366 34196 16367 34197 16317 34197 16366 34197 16366 34198 16317 34198 16364 34198 16367 34199 16366 34199 16368 34199 16366 34200 16365 34200 16368 34200 16369 34201 16368 34201 16371 34201 16369 34202 16373 34202 16368 34202 16367 34203 16368 34203 16373 34203 16368 34204 16372 34204 16370 34204 16371 34205 16368 34205 16370 34205 16365 34206 16372 34206 16368 34206 16373 34207 16374 34207 16317 34207 16374 34208 16373 34208 16375 34208 16377 34209 16375 34209 16373 34209 16373 34210 16376 34210 16377 34210 16373 34211 16369 34211 16376 34211 16367 34212 16373 34212 16317 34212 16377 34213 16380 34213 16378 34213 16377 34214 16378 34214 16379 34214 16377 34215 16376 34215 16380 34215 16377 34216 16379 34216 16375 34216 16380 34217 16383 34217 16378 34217 16380 34218 16376 34218 16381 34218 16381 34219 16384 34219 16380 34219 16382 34220 16284 34220 16380 34220 16380 34221 16384 34221 16382 34221 16380 34222 16284 34222 16383 34222 16381 34223 16385 34223 16384 34223 16385 34224 16387 34224 16384 34224 16387 34225 16386 34225 16384 34225 16386 34226 16382 34226 16384 34226 16385 34227 16390 34227 16387 34227 16391 34228 16387 34228 16388 34228 16387 34229 16390 34229 16388 34229 16387 34230 16391 34230 16389 34230 16387 34231 16389 34231 16386 34231 16391 34232 16392 34232 16389 34232 16391 34233 16388 34233 16392 34233 16392 34234 16396 34234 16389 34234 16388 34235 16393 34235 16392 34235 16392 6 16393 6 16395 6 16395 34236 16394 34236 16392 34236 16394 34237 16396 34237 16392 34237 16349 53 16396 53 16394 53 16396 53 16349 53 16397 53 16396 34238 16397 34238 16389 34238 16397 53 16349 53 16398 53 16397 34239 16398 34239 16399 34239 16389 34240 16397 34240 16399 34240 16399 34241 16398 34241 16400 34241 16399 6 16400 6 16401 6 16399 34242 16401 34242 16402 34242 16402 34243 16389 34243 16399 34243 16402 34244 16403 34244 16386 34244 16402 34245 16401 34245 16403 34245 16402 34246 16386 34246 16389 34246 16403 34247 16390 34247 16404 34247 16405 34248 16403 34248 16404 34248 16403 34249 16388 34249 16390 34249 16403 34250 16401 34250 16388 34250 16386 34251 16403 34251 16405 34251 16406 34252 16405 34252 16408 34252 16406 34253 16386 34253 16405 34253 16405 34254 16404 34254 16407 34254 16408 34255 16405 34255 16407 34255 16409 34256 16408 34256 16412 34256 16410 34257 16408 34257 16409 34257 16382 34258 16408 34258 16410 34258 16382 34259 16406 34259 16408 34259 16411 34260 16408 34260 16407 34260 16411 34261 16412 34261 16408 34261 16411 34262 16413 34262 16412 34262 16409 34263 16412 34263 16413 34263 16411 34264 16414 34264 16413 34264 16413 34265 16414 34265 16417 34265 16413 34266 16416 34266 16415 34266 16413 34267 16415 34267 16409 34267 16419 34268 16416 34268 16413 34268 16418 34269 16413 34269 16417 34269 16413 34270 16418 34270 16419 34270 16420 34271 16419 34271 16424 34271 16420 34272 16416 34272 16419 34272 16419 34273 16418 34273 16423 34273 16421 34274 16422 34274 16419 34274 16421 34275 16419 34275 16423 34275 16419 34276 16422 34276 16424 34276 16422 34277 16425 34277 16424 34277 16424 34278 16425 34278 16426 34278 16427 6 16424 6 16426 6 16424 159 16427 159 16420 159 16427 6 16426 6 16428 6 16427 6 16428 6 16429 6 16427 34279 16429 34279 16430 34279 16427 34280 16430 34280 16417 34280 16420 34281 16427 34281 16431 34281 16431 34282 16427 34282 16417 34282 16420 34283 16431 34283 16416 34283 16431 34284 16417 34284 16414 34284 16432 34285 16431 34285 16414 34285 16416 34286 16431 34286 16432 34286 16433 34287 16415 34287 16432 34287 16415 34288 16416 34288 16432 34288 16414 34289 16434 34289 16432 34289 16432 34290 16434 34290 16433 34290 16434 34291 16435 34291 16433 34291 16436 34292 16435 34292 16434 34292 16436 34293 16434 34293 16414 34293 16407 34294 16436 34294 16411 34294 16437 34295 16436 34295 16407 34295 16436 34296 16437 34296 16438 34296 16436 34297 16438 34297 16435 34297 16436 34298 16414 34298 16411 34298 16430 34299 16435 34299 16438 34299 16438 34300 16439 34300 16430 34300 16439 34301 16438 34301 16323 34301 16441 34302 16438 34302 16437 34302 16438 34303 16440 34303 16323 34303 16441 34304 16440 34304 16438 34304 16441 34305 16404 34305 16390 34305 16441 34306 16437 34306 16404 34306 16442 34307 16441 34307 16385 34307 16440 34308 16441 34308 16442 34308 16441 34309 16390 34309 16385 34309 16442 34310 16381 34310 16376 34310 16442 34311 16376 34311 16443 34311 16443 34312 16440 34312 16442 34312 16385 34313 16381 34313 16442 34313 16444 34314 16443 34314 16374 34314 16444 34315 16440 34315 16443 34315 16443 34316 16445 34316 16374 34316 16443 34317 16376 34317 16445 34317 16369 34318 16445 34318 16376 34318 16369 34319 16446 34319 16445 34319 16374 34320 16445 34320 16446 34320 16371 34321 16446 34321 16369 34321 16317 34322 16446 34322 16319 34322 16317 34323 16374 34323 16446 34323 16370 34324 16447 34324 16446 34324 16370 34325 16446 34325 16371 34325 16446 34326 16447 34326 16448 34326 16319 34327 16446 34327 16448 34327 16319 34328 16448 34328 16393 34328 16393 34329 16448 34329 16395 34329 16447 34330 16449 34330 16448 34330 16448 34331 16449 34331 16394 34331 16395 34332 16448 34332 16394 34332 16450 287 16349 287 16449 287 16447 34333 16450 34333 16449 34333 16449 290 16349 290 16394 290 16370 34334 16450 34334 16447 34334 16372 34335 16450 34335 16370 34335 16349 56 16450 56 16372 56 16451 34336 16322 34336 16444 34336 16322 34337 16440 34337 16444 34337 16444 34338 16374 34338 16451 34338 16451 34339 16453 34339 16452 34339 16452 34340 16322 34340 16451 34340 16451 34341 16375 34341 16453 34341 16451 34342 16374 34342 16375 34342 16308 34343 16452 34343 16453 34343 16295 34344 16308 34344 16453 34344 16379 34345 16453 34345 16375 34345 16295 34346 16453 34346 16379 34346 16310 34347 16322 34347 16452 34347 16452 34348 16308 34348 16310 34348 16323 34349 16440 34349 16322 34349 16439 34350 16323 34350 16319 34350 16319 6 16393 6 16439 6 16430 34351 16439 34351 16417 34351 16439 34352 16454 34352 16417 34352 16439 6 16393 6 16401 6 16439 6 16401 6 16454 6 16454 34353 16456 34353 16455 34353 16457 34354 16454 34354 16455 34354 16417 34355 16454 34355 16457 34355 16401 34356 16400 34356 16454 34356 16400 34357 16456 34357 16454 34357 16457 34358 16455 34358 16423 34358 16423 34359 16417 34359 16457 34359 16455 53 16456 53 16349 53 16398 34360 16349 34360 16456 34360 16400 34361 16398 34361 16456 34361 16347 34362 16421 34362 16455 34362 16421 34363 16423 34363 16455 34363 16455 53 16349 53 16347 53 16404 34364 16437 34364 16407 34364 16433 34365 16435 34365 16458 34365 16458 34366 16435 34366 16459 34366 16328 34367 16459 34367 16435 34367 16429 34368 16435 34368 16430 34368 16429 34369 16328 34369 16435 34369 16460 34370 16459 34370 16328 34370 16461 34371 16459 34371 16460 34371 16459 34372 16461 34372 16458 34372 16462 34373 16461 34373 16460 34373 16458 34374 16461 34374 16463 34374 16461 34375 16462 34375 16466 34375 16461 34376 16464 34376 16463 34376 16464 34377 16461 34377 16465 34377 16465 34378 16461 34378 16466 34378 16468 34379 16465 34379 16466 34379 16467 34380 16466 34380 16462 34380 16469 34381 16466 34381 16467 34381 16469 34382 16468 34382 16466 34382 16467 34383 16471 34383 16469 34383 16469 34384 16471 34384 16470 34384 16470 34385 16468 34385 16469 34385 16474 34386 16472 34386 16471 34386 16472 34387 16350 34387 16471 34387 16471 34388 16350 34388 16470 34388 16464 34389 16471 34389 16467 34389 16473 34390 16471 34390 16464 34390 16473 34391 16474 34391 16471 34391 16474 34392 16465 34392 16476 34392 16473 34393 16465 34393 16474 34393 16475 34394 16472 34394 16474 34394 16476 34395 16475 34395 16474 34395 16476 34396 16465 34396 16428 34396 16476 34397 16428 34397 16475 34397 16347 53 16475 53 16477 53 16428 34398 16477 34398 16475 34398 16475 410 16347 410 16472 410 16425 53 16347 53 16477 53 16426 34399 16425 34399 16477 34399 16426 34400 16477 34400 16428 34400 16473 34401 16464 34401 16465 34401 16350 34402 16472 34402 16347 34402 16470 6 16478 6 16468 6 16350 34403 16351 34403 16470 34403 16470 34404 16351 34404 16478 34404 16478 34405 16351 34405 16352 34405 16478 34406 16352 34406 16479 34406 16468 6 16478 6 16479 6 16429 34407 16479 34407 16332 34407 16332 34408 16479 34408 16480 34408 16479 176 16352 176 16345 176 16429 6 16468 6 16479 6 16480 34409 16479 34409 16345 34409 16480 34410 16345 34410 16339 34410 16339 34411 16332 34411 16480 34411 16429 34412 16465 34412 16468 34412 16467 34413 16481 34413 16482 34413 16467 34414 16462 34414 16481 34414 16482 34415 16463 34415 16467 34415 16463 34416 16464 34416 16467 34416 16486 34417 16482 34417 16483 34417 16482 34418 16487 34418 16483 34418 16482 34419 16481 34419 16485 34419 16488 34420 16484 34420 16482 34420 16484 34421 16487 34421 16482 34421 16482 34422 16485 34422 16488 34422 16482 34423 16489 34423 16463 34423 16486 34424 16489 34424 16482 34424 16458 34425 16463 34425 16489 34425 16458 34426 16489 34426 16433 34426 16486 34427 16415 34427 16489 34427 16415 34428 16433 34428 16489 34428 16488 34429 16292 34429 16484 34429 16291 34430 16292 34430 16488 34430 16488 34431 16485 34431 16291 34431 16484 427 16490 427 16487 427 16487 427 16490 427 16491 427 16487 34432 16491 34432 16483 34432 16490 6 16492 6 16491 6 16483 34433 16491 34433 16492 34433 16483 14 16492 14 16494 14 16493 6 16492 6 16495 6 16494 34434 16492 34434 16493 34434 16495 34435 16492 34435 16490 34435 16292 34436 16289 34436 16495 34436 16493 34437 16495 34437 16289 34437 16292 34438 16495 34438 16484 34438 16484 34439 16495 34439 16490 34439 16483 34440 16494 34440 16486 34440 16494 34441 16493 34441 16496 34441 16409 34442 16494 34442 16496 34442 16486 34443 16494 34443 16409 34443 16282 34444 16410 34444 16496 34444 16282 34445 16496 34445 16283 34445 16496 356 16493 356 16283 356 16410 34446 16409 34446 16496 34446 16493 6 16289 6 16283 6 16409 34447 16415 34447 16486 34447 16327 34448 16485 34448 16481 34448 16485 34449 16329 34449 16497 34449 16291 34450 16485 34450 16497 34450 16329 34451 16485 34451 16327 34451 16291 34452 16497 34452 16331 34452 16329 34453 16331 34453 16497 34453 16460 34454 16481 34454 16462 34454 16327 34455 16481 34455 16460 34455 16429 34456 16428 34456 16465 34456 16460 34457 16328 34457 16327 34457 16429 34458 16332 34458 16318 34458 16318 34459 16328 34459 16429 34459 16422 53 16347 53 16425 53 16418 34460 16417 34460 16423 34460 16347 34461 16422 34461 16421 34461 16282 34462 16382 34462 16410 34462 16386 34463 16406 34463 16382 34463 16393 34464 16388 34464 16401 34464 16284 348 16285 348 16383 348 16383 347 16285 347 16498 347 16383 243 16498 243 16378 243 16498 6 16285 6 16500 6 16378 243 16498 243 16499 243 16498 34465 16500 34465 16499 34465 16501 247 16499 247 16500 247 16501 34466 16500 34466 16502 34466 16502 34467 16500 34467 16286 34467 16285 34468 16286 34468 16500 34468 16295 34469 16501 34469 16502 34469 16502 34470 16286 34470 16288 34470 16502 252 16288 252 16295 252 16378 34471 16501 34471 16379 34471 16378 246 16499 246 16501 246 16379 34472 16501 34472 16295 34472 16282 34473 16284 34473 16382 34473 16365 282 16348 282 16372 282 16349 34474 16372 34474 16348 34474 16317 34475 16315 34475 16364 34475 16332 34476 16356 34476 16318 34476 16333 34477 16356 34477 16332 34477 16340 34478 16356 34478 16336 34478 16340 6 16354 6 16356 6 16336 34479 16356 34479 16333 34479 16340 34480 16343 34480 16354 34480 16345 34481 16341 34481 16339 34481 16338 34482 16332 34482 16339 34482 16338 34483 16331 34483 16332 34483 16331 34484 16294 34484 16291 34484 16318 34485 16320 34485 16328 34485 16298 34486 16325 34486 16299 34486 16301 34487 16322 34487 16302 34487 16302 34488 16322 34488 16310 34488 16309 34489 16306 34489 16313 34489 16503 34490 16504 34490 16505 34490 16503 34491 16506 34491 16504 34491 16505 34492 16509 34492 16503 34492 16503 34493 16507 34493 16506 34493 16503 6 16508 6 16507 6 16503 34494 16509 34494 16508 34494 16512 34495 16509 34495 16505 34495 16510 34496 16508 34496 16509 34496 16510 34497 16509 34497 16511 34497 16511 34498 16509 34498 16512 34498 16513 34499 16512 34499 16515 34499 16511 34499 16512 34499 16513 34499 16514 34500 16515 34500 16512 34500 16514 6 16512 6 16505 6 16513 34501 16515 34501 16516 34501 16516 34502 16515 34502 16517 34502 16515 6 16518 6 16517 6 16514 6 16518 6 16515 6 16521 34503 16518 34503 16519 34503 16519 34503 16518 34503 16514 34503 16517 34504 16518 34504 16520 34504 16521 34505 16520 34505 16518 34505 16522 34506 16520 34506 16521 34506 16524 34507 16522 34507 16521 34507 16521 34508 16519 34508 16523 34508 16523 34509 16524 34509 16521 34509 16524 34510 16525 34510 16528 34510 16526 34511 16525 34511 16524 34511 16524 34512 16527 34512 16526 34512 16524 34513 16529 34513 16527 34513 16524 34514 16528 34514 16530 34514 16516 34515 16522 34515 16524 34515 16530 34516 16516 34516 16524 34516 16523 34517 16529 34517 16524 34517 16530 34518 16513 34518 16516 34518 16531 34519 16513 34519 16530 34519 16530 34520 16528 34520 16531 34520 16531 34521 16532 34521 16535 34521 16531 34522 16528 34522 16532 34522 16511 34523 16513 34523 16531 34523 16533 34524 16511 34524 16531 34524 16531 34525 16534 34525 16533 34525 16535 34526 16534 34526 16531 34526 16536 34527 16537 34527 16535 34527 16536 34528 16535 34528 16532 34528 16535 34529 16537 34529 16539 34529 16535 34530 16538 34530 16534 34530 16538 34531 16535 34531 16541 34531 16540 34532 16535 34532 16539 34532 16540 34533 16541 34533 16535 34533 16540 34534 16543 34534 16541 34534 16544 34535 16541 34535 16542 34535 16541 34536 16546 34536 16542 34536 16543 34537 16545 34537 16541 34537 16538 34538 16541 34538 16544 34538 16545 34539 16546 34539 16541 34539 16546 34540 16547 34540 16542 34540 16545 53 16548 53 16546 53 16546 53 16548 53 16547 53 16551 53 16548 53 16549 53 16548 34541 16552 34541 16549 34541 16550 53 16548 53 16551 53 16557 53 16548 53 16550 53 16548 53 16545 53 16556 53 16548 34542 16553 34542 16552 34542 16553 34170 16548 34170 16554 34170 16547 53 16548 53 16555 53 16554 34543 16548 34543 16556 34543 16557 59 16555 59 16548 59 16560 34544 16557 34544 16558 34544 16557 34545 16561 34545 16558 34545 16559 34546 16555 34546 16557 34546 16560 34547 16559 34547 16557 34547 16550 34548 16561 34548 16557 34548 16550 34549 16562 34549 16561 34549 16561 34550 16562 34550 16563 34550 16558 34551 16561 34551 16563 34551 16568 34552 16564 34552 16563 34552 16564 34553 16558 34553 16563 34553 16563 34554 16562 34554 16565 34554 16567 34555 16563 34555 16565 34555 16568 34556 16563 34556 16566 34556 16567 34557 16566 34557 16563 34557 16572 34558 16568 34558 16566 34558 16569 34559 16571 34559 16568 34559 16569 34560 16568 34560 16572 34560 16564 34561 16568 34561 16570 34561 16568 34562 16571 34562 16570 34562 16574 34563 16572 34563 16566 34563 16569 34564 16572 34564 16573 34564 16573 34565 16572 34565 16533 34565 16533 34566 16572 34566 16574 34566 16575 34567 16576 34567 16574 34567 16574 34568 16579 34568 16575 34568 16574 34569 16576 34569 16577 34569 16577 34570 16510 34570 16574 34570 16566 34571 16578 34571 16574 34571 16574 34572 16578 34572 16579 34572 16574 34573 16510 34573 16533 34573 16580 34574 16581 34574 16579 34574 16580 34575 16579 34575 16582 34575 16578 34576 16582 34576 16579 34576 16575 34577 16579 34577 16581 34577 16582 34578 16578 34578 16583 34578 16583 34579 16584 34579 16582 34579 16582 34580 16584 34580 16580 34580 16588 34581 16584 34581 16583 34581 16584 34582 16586 34582 16585 34582 16585 34583 16589 34583 16584 34583 16588 34584 16586 34584 16584 34584 16580 34585 16584 34585 16587 34585 16584 34586 16589 34586 16587 34586 16590 34587 16589 34587 16591 34587 16589 34588 16590 34588 16593 34588 16591 34589 16589 34589 16585 34589 16587 34590 16589 34590 16592 34590 16592 34591 16589 34591 16593 34591 16593 34592 16594 34592 16592 34592 16593 34593 16596 34593 16594 34593 16593 34594 16590 34594 16595 34594 16595 34595 16596 34595 16593 34595 16596 34596 16595 34596 16597 34596 16598 34597 16594 34597 16596 34597 16596 34598 16597 34598 16598 34598 16599 34599 16506 34599 16598 34599 16598 34600 16597 34600 16599 34600 16600 34601 16594 34601 16598 34601 16600 34602 16598 34602 16602 34602 16598 34603 16506 34603 16601 34603 16598 34217 16601 34217 16602 34217 16601 243 16603 243 16602 243 16602 243 16603 243 16604 243 16602 34604 16604 34604 16576 34604 16602 34471 16576 34471 16575 34471 16600 6 16602 6 16575 6 16576 247 16604 247 16605 247 16603 6 16605 6 16604 6 16576 34605 16605 34605 16577 34605 16577 34606 16605 34606 16508 34606 16507 34607 16508 34607 16605 34607 16603 34608 16507 34608 16605 34608 16601 34609 16507 34609 16603 34609 16506 34610 16507 34610 16601 34610 16600 34611 16575 34611 16581 34611 16600 34612 16581 34612 16606 34612 16606 34613 16594 34613 16600 34613 16606 34614 16607 34614 16609 34614 16607 34615 16606 34615 16581 34615 16606 34616 16608 34616 16594 34616 16608 34617 16606 34617 16611 34617 16610 34618 16606 34618 16609 34618 16610 34619 16611 34619 16606 34619 16610 34620 16612 34620 16611 34620 16612 34621 16615 34621 16611 34621 16614 34622 16611 34622 16613 34622 16611 34623 16616 34623 16613 34623 16608 34624 16611 34624 16614 34624 16615 34625 16616 34625 16611 34625 16615 282 16550 282 16616 282 16551 34542 16617 34542 16616 34542 16616 34626 16617 34626 16613 34626 16551 34627 16616 34627 16550 34627 16613 34628 16617 34628 16618 34628 16618 34629 16617 34629 16619 34629 16617 287 16551 287 16619 287 16618 34630 16619 34630 16620 34630 16620 34631 16619 34631 16621 34631 16619 34632 16551 34632 16621 34632 16622 34633 16620 34633 16621 34633 16622 34634 16621 34634 16624 34634 16551 53 16623 53 16621 53 16621 34635 16623 34635 16624 34635 16625 34636 16628 34636 16624 34636 16626 34637 16625 34637 16624 34637 16626 34638 16624 34638 16627 34638 16624 34639 16623 34639 16627 34639 16624 6 16628 6 16622 6 16629 6 16620 6 16628 6 16628 34640 16620 34640 16622 34640 16629 6 16628 6 16630 6 16630 34641 16628 34641 16631 34641 16628 34642 16625 34642 16632 34642 16628 34643 16632 34643 16631 34643 16634 34644 16632 34644 16633 34644 16633 34645 16632 34645 16635 34645 16634 34646 16631 34646 16632 34646 16635 34647 16632 34647 16625 34647 16625 34648 16636 34648 16635 34648 16636 34649 16638 34649 16635 34649 16633 34650 16635 34650 16637 34650 16637 34651 16635 34651 16638 34651 16637 34652 16638 34652 16640 34652 16641 34653 16638 34653 16639 34653 16639 34654 16638 34654 16591 34654 16590 34655 16591 34655 16638 34655 16638 34656 16641 34656 16640 34656 16590 34657 16638 34657 16636 34657 16640 34658 16641 34658 16642 34658 16641 34659 16643 34659 16642 34659 16639 34660 16644 34660 16641 34660 16641 34661 16645 34661 16643 34661 16641 34662 16644 34662 16645 34662 16643 34663 16645 34663 16646 34663 16646 34664 16645 34664 16647 34664 16645 34665 16644 34665 16647 34665 16647 34666 16648 34666 16646 34666 16648 34667 16647 34667 16529 34667 16647 34668 16644 34668 16649 34668 16649 34669 16529 34669 16647 34669 16649 34670 16644 34670 16650 34670 16650 34671 16651 34671 16649 34671 16649 34672 16651 34672 16527 34672 16649 34673 16527 34673 16529 34673 16651 34674 16652 34674 16527 34674 16652 34675 16651 34675 16653 34675 16653 34676 16651 34676 16654 34676 16651 34677 16655 34677 16654 34677 16655 34678 16651 34678 16656 34678 16651 34679 16650 34679 16656 34679 16656 34680 16525 34680 16655 34680 16657 34681 16525 34681 16656 34681 16656 34682 16658 34682 16657 34682 16656 34683 16650 34683 16658 34683 16658 34684 16661 34684 16657 34684 16658 34685 16659 34685 16660 34685 16659 34686 16658 34686 16644 34686 16661 34687 16658 34687 16660 34687 16658 34688 16650 34688 16644 34688 16657 34689 16661 34689 16536 34689 16661 34690 16537 34690 16536 34690 16662 34691 16537 34691 16661 34691 16662 34692 16661 34692 16663 34692 16661 34693 16660 34693 16663 34693 16662 34694 16663 34694 16664 34694 16663 34695 16588 34695 16664 34695 16586 34696 16663 34696 16660 34696 16586 34697 16588 34697 16663 34697 16573 34698 16665 34698 16664 34698 16665 34699 16662 34699 16664 34699 16664 34700 16588 34700 16569 34700 16569 34701 16573 34701 16664 34701 16665 34702 16666 34702 16662 34702 16534 34703 16665 34703 16573 34703 16538 34704 16666 34704 16665 34704 16534 34705 16538 34705 16665 34705 16537 34706 16662 34706 16666 34706 16667 34707 16537 34707 16666 34707 16538 34708 16667 34708 16666 34708 16539 34709 16537 34709 16667 34709 16667 34710 16668 34710 16539 34710 16544 34711 16668 34711 16667 34711 16544 34712 16667 34712 16538 34712 16539 34713 16668 34713 16670 34713 16542 390 16669 390 16668 390 16542 34714 16668 34714 16544 34714 16668 34715 16669 34715 16559 34715 16670 6 16668 6 16559 6 16671 34716 16539 34716 16670 34716 16670 34717 16659 34717 16671 34717 16670 34718 16570 34718 16672 34718 16672 34719 16660 34719 16670 34719 16670 34720 16660 34720 16659 34720 16670 34721 16559 34721 16570 34721 16672 34722 16673 34722 16674 34722 16672 34723 16570 34723 16673 34723 16672 34724 16674 34724 16609 34724 16629 34725 16586 34725 16672 34725 16672 34726 16609 34726 16629 34726 16672 34727 16586 34727 16660 34727 16675 34728 16676 34728 16674 34728 16673 6 16675 6 16674 6 16674 34729 16676 34729 16677 34729 16678 34730 16674 34730 16677 34730 16609 34731 16674 34731 16678 34731 16612 34732 16609 34732 16678 34732 16678 34733 16677 34733 16612 34733 16677 34734 16615 34734 16612 34734 16550 53 16677 53 16676 53 16677 34735 16550 34735 16615 34735 16679 53 16550 53 16676 53 16675 34736 16679 34736 16676 34736 16562 53 16550 53 16679 53 16562 34737 16679 34737 16565 34737 16565 34738 16679 34738 16675 34738 16565 34739 16675 34739 16673 34739 16565 34740 16673 34740 16567 34740 16567 34741 16673 34741 16680 34741 16570 34742 16680 34742 16673 34742 16567 34743 16680 34743 16566 34743 16566 34744 16680 34744 16583 34744 16583 34745 16680 34745 16571 34745 16680 34746 16570 34746 16571 34746 16671 34747 16685 34747 16539 34747 16671 34748 16683 34748 16653 34748 16671 34749 16653 34749 16682 34749 16671 34750 16639 34750 16681 34750 16684 34751 16671 34751 16681 34751 16671 34752 16659 34752 16644 34752 16671 34753 16644 34753 16639 34753 16671 6 16682 6 16685 6 16684 34754 16683 34754 16671 34754 16539 34755 16685 34755 16687 34755 16682 34756 16686 34756 16685 34756 16686 34757 16554 34757 16685 34757 16685 34758 16554 34758 16556 34758 16687 34759 16685 34759 16556 34759 16543 34760 16539 34760 16687 34760 16687 34761 16556 34761 16543 34761 16686 34762 16553 34762 16554 34762 16688 34763 16553 34763 16686 34763 16688 6 16686 6 16682 6 16688 34764 16682 34764 16689 34764 16689 34765 16690 34765 16688 34765 16690 34766 16552 34766 16688 34766 16552 34767 16553 34767 16688 34767 16691 34768 16552 34768 16690 34768 16693 34769 16691 34769 16690 34769 16526 34770 16690 34770 16689 34770 16652 34771 16690 34771 16526 34771 16692 34772 16690 34772 16652 34772 16692 34773 16693 34773 16690 34773 16693 34774 16653 34774 16695 34774 16692 34775 16653 34775 16693 34775 16694 34776 16691 34776 16693 34776 16695 34777 16694 34777 16693 34777 16695 34778 16653 34778 16683 34778 16695 34779 16683 34779 16694 34779 16549 53 16694 53 16696 53 16683 34780 16696 34780 16694 34780 16694 410 16549 410 16691 410 16697 53 16549 53 16696 53 16698 34781 16697 34781 16696 34781 16698 34782 16696 34782 16683 34782 16699 34783 16697 34783 16698 34783 16684 6 16698 6 16683 6 16684 6 16699 6 16698 6 16699 159 16684 159 16700 159 16700 34784 16701 34784 16699 34784 16701 34785 16702 34785 16699 34785 16702 34786 16697 34786 16699 34786 16702 53 16549 53 16697 53 16549 34787 16702 34787 16703 34787 16703 34788 16702 34788 16701 34788 16703 34789 16701 34789 16704 34789 16703 34790 16704 34790 16705 34790 16549 34791 16703 34791 16705 34791 16705 34792 16706 34792 16551 34792 16707 34793 16706 34793 16705 34793 16708 34794 16707 34794 16705 34794 16708 34795 16705 34795 16704 34795 16705 53 16551 53 16549 53 16704 34796 16709 34796 16708 34796 16709 34797 16707 34797 16708 34797 16630 34798 16707 34798 16709 34798 16681 34799 16630 34799 16709 34799 16710 34800 16711 34800 16709 34800 16710 34801 16709 34801 16704 34801 16684 34802 16681 34802 16709 34802 16712 34803 16709 34803 16643 34803 16711 34804 16643 34804 16709 34804 16712 34805 16684 34805 16709 34805 16700 34806 16712 34806 16713 34806 16713 34807 16712 34807 16646 34807 16646 34808 16712 34808 16643 34808 16700 34809 16684 34809 16712 34809 16711 34810 16713 34810 16648 34810 16648 34811 16713 34811 16646 34811 16700 34812 16713 34812 16701 34812 16701 34813 16713 34813 16711 34813 16642 34814 16711 34814 16714 34814 16643 34815 16711 34815 16642 34815 16715 34816 16714 34816 16711 34816 16711 34817 16648 34817 16715 34817 16711 34818 16710 34818 16701 34818 16715 34819 16519 34819 16717 34819 16523 34820 16519 34820 16715 34820 16715 34821 16648 34821 16523 34821 16716 34822 16718 34822 16715 34822 16716 34823 16715 34823 16717 34823 16715 34824 16718 34824 16714 34824 16718 34825 16637 34825 16640 34825 16642 34826 16718 34826 16640 34826 16642 34827 16714 34827 16718 34827 16599 34828 16719 34828 16718 34828 16719 34829 16637 34829 16718 34829 16599 34830 16718 34830 16716 34830 16719 34831 16633 34831 16637 34831 16633 34832 16719 34832 16599 34832 16504 34833 16716 34833 16717 34833 16504 34834 16717 34834 16505 34834 16519 34835 16514 34835 16717 34835 16717 34836 16514 34836 16505 34836 16504 34837 16599 34837 16716 34837 16701 34838 16710 34838 16704 34838 16631 34839 16720 34839 16707 34839 16720 34840 16706 34840 16707 34840 16630 34841 16631 34841 16707 34841 16720 34842 16721 34842 16706 34842 16722 34843 16721 34843 16720 34843 16722 6 16720 6 16631 6 16634 34844 16627 34844 16722 34844 16722 304 16631 304 16634 304 16627 34845 16723 34845 16722 34845 16723 34846 16721 34846 16722 34846 16623 53 16551 53 16723 53 16623 34847 16723 34847 16627 34847 16723 53 16551 53 16721 53 16721 53 16551 53 16706 53 16692 34848 16652 34848 16653 34848 16552 34402 16691 34402 16549 34402 16689 34849 16654 34849 16526 34849 16689 34850 16682 34850 16654 34850 16682 34851 16653 34851 16654 34851 16591 34852 16630 34852 16681 34852 16591 34853 16681 34853 16639 34853 16542 34854 16547 34854 16669 34854 16669 34855 16547 34855 16555 34855 16669 34856 16555 34856 16559 34856 16657 34857 16528 34857 16525 34857 16536 34858 16528 34858 16657 34858 16526 34859 16655 34859 16525 34859 16526 34860 16654 34860 16655 34860 16527 34861 16652 34861 16526 34861 16523 34862 16648 34862 16529 34862 16590 34863 16636 34863 16595 34863 16636 34864 16625 34864 16595 34864 16634 34865 16633 34865 16627 34865 16724 34866 16633 34866 16597 34866 16724 34867 16627 34867 16633 34867 16633 34868 16599 34868 16597 34868 16595 34869 16625 34869 16724 34869 16595 34870 16724 34870 16597 34870 16626 34871 16724 34871 16625 34871 16724 34872 16626 34872 16627 34872 16630 34873 16591 34873 16585 34873 16630 34874 16585 34874 16629 34874 16629 34875 16725 34875 16620 34875 16609 34876 16725 34876 16629 34876 16629 34877 16585 34877 16586 34877 16607 34878 16726 34878 16725 34878 16609 34879 16607 34879 16725 34879 16613 34880 16618 34880 16725 34880 16613 34881 16725 34881 16614 34881 16725 34882 16618 34882 16620 34882 16614 34883 16725 34883 16608 34883 16608 34884 16725 34884 16726 34884 16592 34885 16726 34885 16607 34885 16592 34886 16594 34886 16726 34886 16608 34887 16726 34887 16594 34887 16610 34888 16609 34888 16612 34888 16580 34889 16607 34889 16581 34889 16587 34890 16607 34890 16580 34890 16587 34891 16592 34891 16607 34891 16504 34892 16506 34892 16599 34892 16571 34893 16588 34893 16583 34893 16569 34894 16588 34894 16571 34894 16578 34895 16566 34895 16583 34895 16577 34896 16508 34896 16510 34896 16533 34897 16534 34897 16573 34897 16558 34898 16570 34898 16560 34898 16570 34899 16559 34899 16560 34899 16564 34900 16570 34900 16558 34900 16556 34901 16545 34901 16543 34901 16540 34902 16539 34902 16543 34902 16528 34903 16536 34903 16532 34903 16533 34904 16510 34904 16511 34904 16516 427 16517 427 16522 427 16522 427 16517 427 16520 427 16727 34905 16730 34905 16728 34905 16727 34085 16728 34085 16729 34085 16729 2 16733 2 16727 2 16727 34906 16731 34906 16730 34906 16727 34907 16732 34907 16731 34907 16727 34908 16733 34908 16732 34908 16736 8 16733 8 16734 8 16734 34090 16733 34090 16735 34090 16735 6 16733 6 16729 6 16736 34909 16732 34909 16733 34909 16737 34910 16736 34910 16739 34910 16737 34470 16732 34470 16736 34470 16738 34911 16736 34911 16734 34911 16739 34912 16736 34912 16738 34912 16739 34913 16744 34913 16740 34913 16739 34914 16740 34914 16742 34914 16738 34915 16741 34915 16739 34915 16739 34916 16741 34916 16745 34916 16742 34917 16743 34917 16739 34917 16739 34918 16743 34918 16737 34918 16745 34919 16744 34919 16739 34919 16744 34920 16745 34920 16750 34920 16746 34921 16749 34921 16745 34921 16741 34922 16746 34922 16745 34922 16745 34923 16747 34923 16750 34923 16748 34924 16747 34924 16745 34924 16748 34925 16745 34925 16749 34925 16750 34926 16752 34926 16751 34926 16751 34927 16744 34927 16750 34927 16753 34928 16752 34928 16750 34928 16754 34929 16753 34929 16750 34929 16747 34930 16755 34930 16750 34930 16750 34931 16755 34931 16754 34931 16746 34932 16754 34932 16755 34932 16756 34933 16746 34933 16755 34933 16756 34934 16755 34934 16757 34934 16755 34935 16758 34935 16757 34935 16758 34936 16755 34936 16747 34936 16757 6 16758 6 16760 6 16758 34937 16759 34937 16760 34937 16761 6 16759 6 16758 6 16761 34938 16758 34938 16762 34938 16762 34939 16758 34939 16747 34939 16762 34940 16766 34940 16761 34940 16762 34941 16763 34941 16765 34941 16762 34942 16764 34942 16763 34942 16762 34943 16747 34943 16764 34943 16765 34944 16767 34944 16762 34944 16762 34945 16767 34945 16766 34945 16753 34946 16767 34946 16752 34946 16767 34947 16768 34947 16752 34947 16765 34948 16769 34948 16767 34948 16768 34949 16767 34949 16769 34949 16767 34950 16770 34950 16766 34950 16767 34951 16753 34951 16770 34951 16771 34952 16773 34952 16770 34952 16771 34953 16770 34953 16772 34953 16770 34954 16753 34954 16772 34954 16773 34955 16766 34955 16770 34955 16774 34956 16773 34956 16776 34956 16775 34957 16773 34957 16774 34957 16773 34958 16775 34958 16766 34958 16771 34959 16777 34959 16773 34959 16773 34960 16777 34960 16776 34960 16776 34961 16777 34961 16778 34961 16778 34962 16777 34962 16779 34962 16777 34963 16771 34963 16781 34963 16779 34964 16777 34964 16780 34964 16780 34965 16777 34965 16781 34965 16782 34966 16781 34966 16783 34966 16782 34967 16780 34967 16781 34967 16783 34968 16781 34968 16771 34968 16784 34969 16783 34969 16785 34969 16784 34970 16782 34970 16783 34970 16783 34971 16771 34971 16772 34971 16785 34972 16783 34972 16772 34972 16786 34973 16741 34973 16785 34973 16786 34974 16785 34974 16772 34974 16738 34975 16784 34975 16785 34975 16785 34976 16741 34976 16738 34976 16786 34977 16746 34977 16741 34977 16786 34978 16754 34978 16746 34978 16786 34979 16753 34979 16754 34979 16772 34980 16753 34980 16786 34980 16778 34981 16782 34981 16784 34981 16787 34982 16784 34982 16738 34982 16778 34983 16784 34983 16787 34983 16787 34984 16789 34984 16788 34984 16788 34985 16791 34985 16787 34985 16738 34986 16734 34986 16787 34986 16734 34987 16789 34987 16787 34987 16787 34988 16790 34988 16778 34988 16787 34989 16791 34989 16790 34989 16791 34990 16776 34990 16790 34990 16776 34991 16791 34991 16774 34991 16793 34992 16792 34992 16791 34992 16774 34993 16791 34993 16792 34993 16793 34994 16791 34994 16788 34994 16793 34995 16800 34995 16794 34995 16799 34996 16793 34996 16794 34996 16796 34997 16792 34997 16793 34997 16793 34998 16795 34998 16796 34998 16793 34999 16798 34999 16795 34999 16797 35000 16800 35000 16793 35000 16788 35001 16797 35001 16793 35001 16799 35002 16798 35002 16793 35002 16797 427 16801 427 16800 427 16800 427 16801 427 16802 427 16800 35003 16802 35003 16794 35003 16794 35004 16802 35004 16803 35004 16801 6 16803 6 16802 6 16794 34434 16803 34434 16804 34434 16804 14 16803 14 16805 14 16805 2 16803 2 16806 2 16806 6 16803 6 16801 6 16805 35005 16806 35005 16735 35005 16789 35006 16735 35006 16806 35006 16789 13 16806 13 16797 13 16797 34438 16806 34438 16801 34438 16805 6 16735 6 16729 6 16804 34441 16805 34441 16807 34441 16807 356 16805 356 16729 356 16728 35007 16809 35007 16807 35007 16728 35008 16807 35008 16729 35008 16808 35009 16804 35009 16807 35009 16809 35010 16808 35010 16807 35010 16809 35011 16810 35011 16808 35011 16811 35012 16810 35012 16809 35012 16728 35013 16811 35013 16809 35013 16813 35014 16812 35014 16811 35014 16815 35015 16811 35015 16812 35015 16811 35016 16814 35016 16810 35016 16811 35017 16730 35017 16813 35017 16728 35018 16730 35018 16811 35018 16815 35019 16814 35019 16811 35019 16814 35020 16815 35020 16821 35020 16816 35021 16820 35021 16815 35021 16816 35022 16815 35022 16812 35022 16817 35023 16815 35023 16820 35023 16817 35024 16818 35024 16815 35024 16815 35025 16818 35025 16819 35025 16815 35026 16819 35026 16821 35026 16821 35027 16819 35027 16822 35027 16821 35028 16822 35028 16823 35028 16810 35029 16821 35029 16823 35029 16814 35030 16821 35030 16810 35030 16822 35031 16824 35031 16823 35031 16824 35032 16825 35032 16823 35032 16823 35033 16825 35033 16826 35033 16826 35034 16810 35034 16823 35034 16825 35035 16827 35035 16826 35035 16826 35036 16827 35036 16828 35036 16826 35037 16828 35037 16829 35037 16826 35038 16829 35038 16810 35038 16808 35039 16810 35039 16829 35039 16808 35040 16829 35040 16828 35040 16828 35041 16827 35041 16832 35041 16828 35042 16831 35042 16830 35042 16828 35043 16830 35043 16808 35043 16834 35044 16831 35044 16828 35044 16833 35045 16828 35045 16832 35045 16828 35046 16833 35046 16834 35046 16835 35047 16834 35047 16839 35047 16835 35048 16831 35048 16834 35048 16834 35049 16836 35049 16839 35049 16837 35050 16836 35050 16834 35050 16834 35051 16833 35051 16838 35051 16837 35052 16834 35052 16838 35052 16836 35053 16841 35053 16839 35053 16840 35054 16839 35054 16842 35054 16839 35055 16840 35055 16835 35055 16839 35056 16841 35056 16842 35056 16840 35057 16842 35057 16844 35057 16842 35058 16841 35058 16843 35058 16842 35059 16843 35059 16844 35059 16844 35060 16843 35060 16845 35060 16846 35061 16844 35061 16845 35061 16846 35062 16848 35062 16844 35062 16847 35063 16844 35063 16848 35063 16840 6 16844 6 16847 6 16848 35064 16849 35064 16853 35064 16854 35065 16849 35065 16848 35065 16850 35066 16854 35066 16848 35066 16850 35067 16848 35067 16851 35067 16851 35068 16848 35068 16846 35068 16852 35069 16848 35069 16853 35069 16847 35070 16848 35070 16852 35070 16849 35071 16854 35071 16795 35071 16795 35072 16854 35072 16796 35072 16854 35073 16855 35073 16796 35073 16850 35074 16855 35074 16854 35074 16796 35075 16855 35075 16856 35075 16856 35076 16855 35076 16859 35076 16857 35077 16858 35077 16855 35077 16851 35078 16857 35078 16855 35078 16855 35079 16858 35079 16859 35079 16850 35080 16851 35080 16855 35080 16859 6 16861 6 16852 6 16859 35081 16852 35081 16856 35081 16858 35082 16860 35082 16859 35082 16859 35083 16860 35083 16861 35083 16852 35084 16861 35084 16863 35084 16861 35085 16860 35085 16862 35085 16861 35086 16862 35086 16863 35086 16847 6 16852 6 16863 6 16863 35087 16862 35087 16865 35087 16779 35088 16863 35088 16864 35088 16864 35089 16863 35089 16865 35089 16847 35090 16863 35090 16779 35090 16862 34543 16867 34543 16865 34543 16864 35091 16865 35091 16868 35091 16867 53 16866 53 16865 53 16865 35092 16866 35092 16868 35092 16869 35093 16779 35093 16868 35093 16868 35094 16779 35094 16864 35094 16869 35095 16868 35095 16870 35095 16868 35096 16866 35096 16870 35096 16866 35097 16871 35097 16870 35097 16870 35098 16871 35098 16872 35098 16782 35099 16870 35099 16873 35099 16782 35100 16778 35100 16870 35100 16869 35101 16870 35101 16778 35101 16873 35102 16870 35102 16872 35102 16873 35103 16780 35103 16782 35103 16872 35104 16874 35104 16873 35104 16873 35105 16874 35105 16780 35105 16780 35106 16874 35106 16779 35106 16779 35107 16874 35107 16761 35107 16872 35108 16875 35108 16874 35108 16874 35109 16875 35109 16759 35109 16761 6 16874 6 16759 6 16872 35110 16876 35110 16875 35110 16875 35111 16876 35111 16877 35111 16875 35112 16877 35112 16759 35112 16759 35113 16877 35113 16878 35113 16878 53 16877 53 16867 53 16876 53 16867 53 16877 53 16760 35114 16759 35114 16878 35114 16760 35115 16878 35115 16757 35115 16880 35116 16879 35116 16878 35116 16878 35117 16879 35117 16757 35117 16878 53 16867 53 16880 53 16887 53 16880 53 16881 53 16880 53 16882 53 16881 53 16882 35118 16880 35118 16883 35118 16880 53 16867 53 16886 53 16880 35119 16884 35119 16879 35119 16883 35120 16880 35120 16885 35120 16884 53 16880 53 16887 53 16886 34627 16885 34627 16880 34627 16884 35121 16887 35121 16888 35121 16888 35122 16887 35122 16889 35122 16889 35123 16887 35123 16881 35123 16888 35124 16889 35124 16747 35124 16747 35125 16889 35125 16764 35125 16889 35126 16881 35126 16764 35126 16888 35127 16747 35127 16748 35127 16748 35128 16749 35128 16888 35128 16749 35129 16884 35129 16888 35129 16890 35130 16886 35130 16892 35130 16897 35131 16886 35131 16890 35131 16893 53 16891 53 16886 53 16898 53 16886 53 16891 53 16886 53 16894 53 16892 53 16893 53 16886 53 16895 53 16886 35132 16867 35132 16895 35132 16894 53 16886 53 16896 53 16886 56 16897 56 16885 56 16896 53 16886 53 16898 53 16896 35133 16898 35133 16900 35133 16899 35134 16898 35134 16891 35134 16900 35135 16898 35135 16899 35135 16817 35136 16820 35136 16900 35136 16820 35137 16896 35137 16900 35137 16900 35138 16901 35138 16817 35138 16900 35139 16899 35139 16901 35139 16817 35140 16901 35140 16818 35140 16902 35141 16818 35141 16901 35141 16904 309 16902 309 16901 309 16901 35142 16899 35142 16903 35142 16904 35143 16901 35143 16903 35143 16904 35144 16903 35144 16832 35144 16765 6 16902 6 16904 6 16904 35145 16769 35145 16765 35145 16824 35146 16769 35146 16904 35146 16824 35147 16904 35147 16905 35147 16905 35148 16904 35148 16832 35148 16847 35149 16906 35149 16905 35149 16905 35150 16906 35150 16824 35150 16840 6 16847 6 16905 6 16840 35151 16905 35151 16832 35151 16910 35152 16906 35152 16907 35152 16907 35153 16906 35153 16908 35153 16775 35154 16908 35154 16906 35154 16909 35155 16906 35155 16910 35155 16825 35156 16906 35156 16909 35156 16847 35157 16775 35157 16906 35157 16825 35158 16824 35158 16906 35158 16910 35159 16830 35159 16911 35159 16830 35160 16910 35160 16798 35160 16911 35161 16909 35161 16910 35161 16907 35162 16798 35162 16910 35162 16830 35163 16831 35163 16911 35163 16831 35164 16912 35164 16911 35164 16911 35165 16912 35165 16827 35165 16827 35166 16909 35166 16911 35166 16912 35167 16840 35167 16832 35167 16835 35168 16840 35168 16912 35168 16835 35169 16912 35169 16831 35169 16912 35170 16832 35170 16827 35170 16825 35171 16909 35171 16827 35171 16908 35172 16849 35172 16907 35172 16849 35173 16908 35173 16913 35173 16913 35174 16908 35174 16775 35174 16914 35175 16849 35175 16913 35175 16774 35176 16792 35176 16913 35176 16913 35177 16792 35177 16914 35177 16913 35178 16775 35178 16774 35178 16796 35179 16914 35179 16792 35179 16796 35180 16853 35180 16914 35180 16849 35181 16914 35181 16853 35181 16907 35182 16849 35182 16795 35182 16907 35183 16795 35183 16798 35183 16899 35184 16891 35184 16903 35184 16903 35185 16891 35185 16893 35185 16915 35186 16903 35186 16893 35186 16832 35187 16903 35187 16915 35187 16915 35188 16893 35188 16838 35188 16838 35189 16832 35189 16915 35189 16916 35190 16902 35190 16918 35190 16919 35191 16902 35191 16916 35191 16902 34640 16917 34640 16918 34640 16765 6 16917 6 16902 6 16902 35192 16919 35192 16818 35192 16819 35193 16818 35193 16919 35193 16919 35194 16921 35194 16819 35194 16920 35195 16919 35195 16816 35195 16921 35196 16919 35196 16920 35196 16922 35197 16919 35197 16916 35197 16922 35198 16816 35198 16919 35198 16922 34638 16916 34638 16820 34638 16816 35199 16922 35199 16820 35199 16769 35200 16822 35200 16921 35200 16921 35201 16822 35201 16819 35201 16769 35202 16921 35202 16920 35202 16920 35203 16924 35203 16923 35203 16923 35204 16769 35204 16920 35204 16920 35205 16816 35205 16812 35205 16924 35206 16920 35206 16812 35206 16923 35207 16924 35207 16925 35207 16813 35208 16925 35208 16924 35208 16924 35209 16812 35209 16813 35209 16930 35210 16925 35210 16926 35210 16927 35211 16926 35211 16925 35211 16923 35212 16925 35212 16930 35212 16929 35213 16927 35213 16925 35213 16928 35214 16925 35214 16813 35214 16929 35215 16925 35215 16928 35215 16931 35216 16930 35216 16932 35216 16931 35217 16768 35217 16930 35217 16930 35218 16926 35218 16932 35218 16930 35219 16768 35219 16923 35219 16933 35220 16932 35220 16934 35220 16931 35221 16932 35221 16933 35221 16932 35222 16929 35222 16934 35222 16929 35223 16932 35223 16763 35223 16932 35224 16926 35224 16935 35224 16763 35225 16932 35225 16935 35225 16763 35226 16935 35226 16765 35226 16927 35227 16935 35227 16926 35227 16937 35228 16935 35228 16927 35228 16936 35229 16938 35229 16935 35229 16936 35230 16935 35230 16937 35230 16935 35231 16938 35231 16917 35231 16765 35232 16935 35232 16917 35232 16936 35233 16897 35233 16938 35233 16938 35234 16897 35234 16890 35234 16938 35235 16890 35235 16917 35235 16927 35236 16939 35236 16937 35236 16937 35237 16939 35237 16936 35237 16927 35238 16929 35238 16939 35238 16940 35239 16941 35239 16939 35239 16940 35240 16939 35240 16929 35240 16941 35241 16883 35241 16939 35241 16939 35242 16885 35242 16936 35242 16883 35243 16885 35243 16939 35243 16941 35244 16763 35244 16942 35244 16940 35245 16763 35245 16941 35245 16942 35246 16882 35246 16941 35246 16882 35247 16883 35247 16941 35247 16763 35248 16764 35248 16942 35248 16942 35249 16764 35249 16882 35249 16940 35250 16929 35250 16763 35250 16885 35251 16897 35251 16936 35251 16933 35252 16934 35252 16740 35252 16742 35253 16740 35253 16934 35253 16928 35254 16742 35254 16934 35254 16928 35255 16934 35255 16929 35255 16933 35256 16740 35256 16751 35256 16751 35257 16752 35257 16933 35257 16933 35258 16752 35258 16931 35258 16752 35259 16768 35259 16931 35259 16928 35260 16813 35260 16943 35260 16928 6 16943 6 16742 6 16946 243 16944 243 16943 243 16943 243 16944 243 16945 243 16943 34471 16743 34471 16742 34471 16813 35261 16946 35261 16943 35261 16943 246 16945 246 16743 246 16813 35262 16730 35262 16946 35262 16730 35263 16731 35263 16946 35263 16946 35264 16731 35264 16944 35264 16944 6 16947 6 16945 6 16743 247 16945 247 16947 247 16944 35265 16731 35265 16947 35265 16743 34605 16947 34605 16737 34605 16737 34606 16947 34606 16732 34606 16731 34607 16732 34607 16947 34607 16768 35266 16769 35266 16923 35266 16918 35267 16892 35267 16916 35267 16918 35268 16917 35268 16892 35268 16917 35269 16890 35269 16892 35269 16892 35270 16894 35270 16916 35270 16916 35271 16894 35271 16820 35271 16894 35272 16896 35272 16820 35272 16895 53 16845 53 16843 53 16845 35273 16895 35273 16857 35273 16895 35274 16837 35274 16893 35274 16895 35275 16836 35275 16837 35275 16858 35276 16857 35276 16895 35276 16867 35277 16858 35277 16895 35277 16836 53 16895 53 16841 53 16841 53 16895 53 16843 53 16837 35278 16838 35278 16893 35278 16879 35279 16884 35279 16749 35279 16764 35280 16881 35280 16882 35280 16757 35281 16879 35281 16749 35281 16871 35282 16876 35282 16872 35282 16871 53 16867 53 16876 53 16866 53 16867 53 16871 53 16869 35283 16778 35283 16779 35283 16860 34170 16867 34170 16862 34170 16867 35284 16860 35284 16858 35284 16845 35285 16857 35285 16851 35285 16856 35286 16852 35286 16853 35286 16856 35287 16853 35287 16796 35287 16846 35288 16845 35288 16851 35288 16847 35289 16779 35289 16761 35289 16761 35290 16775 35290 16847 35290 16833 35291 16832 35291 16838 35291 16799 35292 16830 35292 16798 35292 16808 35293 16830 35293 16799 35293 16769 35294 16824 35294 16822 35294 16799 35295 16804 35295 16808 35295 16794 35296 16804 35296 16799 35296 16788 34429 16789 34429 16797 34429 16776 35297 16778 35297 16790 35297 16734 35298 16735 35298 16789 35298 16761 35299 16766 35299 16775 35299 16756 35300 16757 35300 16749 35300 16746 35301 16756 35301 16749 35301 16744 35302 16751 35302 16740 35302

+
+
+
+
+ + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + +
\ No newline at end of file diff --git a/libraries/SITL/examples/Webots_Python/protos/meshes/iris_prop_ccw.dae b/libraries/SITL/examples/Webots_Python/protos/meshes/iris_prop_ccw.dae new file mode 100644 index 0000000000..eb6fe937f9 --- /dev/null +++ b/libraries/SITL/examples/Webots_Python/protos/meshes/iris_prop_ccw.dae @@ -0,0 +1,160 @@ + + + + + Blender User + Blender 2.73.0 commit date:2015-01-07, commit time:13:17, hash:b4d8fb5 + + 2015-01-13T10:39:42 + 2015-01-13T10:39:42 + + Z_UP + + + + + + + 49.13434 + 1.777778 + 0.1 + 100 + + + + + + 0 + 0 + 0 + + + + + + + + + 1 1 1 + 1 + 0 + 0.00111109 + + + + + 0.000999987 + 1 + 0.1 + 0.1 + 1 + 1 + 1 + 2 + 0 + 1 + 1 + 1 + 1 + 1 + 0 + 2880 + 2 + 30.002 + 1.000799 + 0.04999995 + 29.99998 + 1 + 2 + 0 + 0 + 1 + 1 + 1 + 1 + 8192 + 1 + 1 + 0 + 1 + 1 + 1 + 3 + 0 + 0 + 0 + 0 + 0 + 1 + 1 + 1 + 3 + 0.15 + 75 + 1 + 1 + 0 + 1 + 1 + 0 + + + + + + + + + + -0.02474421 -0.009030222 0.001063168 -0.02472132 -0.009507477 0.001745283 -0.03064876 -0.009583294 0.001823306 -0.01391255 -0.007299661 7.68584e-4 -0.01373481 -0.007612466 0.001165688 -0.0188229 -0.008168458 7.50335e-4 -0.01350039 -0.008025228 0.001689732 -0.01344203 -0.008127927 0.001820087 -0.01583349 -0.008392989 0.00162363 -0.1036482 -0.01206469 0.003112256 -0.1047858 -0.01192915 0.003069281 -0.1048365 -0.009166002 0.002676308 -0.03799527 -0.004446864 -6.20823e-4 -0.03673583 -0.004557311 -7.63553e-4 -0.03668981 -0.005653262 -2.73687e-4 -0.01890033 -0.005614221 -0.00109595 -0.01892387 -0.004559278 -0.001545608 -0.01741349 -0.004354834 -0.001478314 -0.0154401 -0.003988504 -0.001394808 -0.01508492 -0.004796922 -9.6907e-4 -0.0149216 -0.00514543 -7.27075e-4 -0.02486616 -0.005928635 -0.001436769 -0.02488899 -0.005218088 -0.001709878 -0.02321702 -0.005140483 -0.0017367 -0.02108848 -0.004852354 -0.001641929 -0.03236478 -0.004940509 -0.001258909 -0.03081458 -0.005063354 -0.001387 -0.03078955 -0.005821704 -0.001070201 -0.02739506 -0.005334436 -0.001669645 -0.02690917 -0.005311846 -0.001677453 -0.03259092 -0.004920661 -0.001233279 -0.04099917 -0.00418353 -2.80403e-4 -0.04849886 -0.005617916 0.001220166 -0.04856514 -0.003877639 6.01548e-4 -0.0544883 -0.003917276 0.001142621 -0.05447131 -0.003917098 0.001141071 -0.05441784 -0.005656123 0.001803338 -0.04912036 -0.003855168 6.66275e-4 -0.04888397 -0.003864765 6.38717e-4 -0.06035238 -0.005690991 0.002091765 -0.0601806 -0.003984451 0.00143069 -0.05708217 -0.003947257 0.001372814 -0.09543347 -0.00398457 0.00169295 -0.08417183 -0.0040977 0.001643061 -0.08411026 -0.005816221 0.002355456 -0.08381026 -0.004101336 0.001641452 -0.07857316 -0.004153907 0.001618206 -0.06601512 -0.004054486 0.001539766 -0.06041771 -0.003987312 0.00143516 -0.09597903 -0.005976617 0.002500414 -0.09604221 -0.00395745 0.001686155 -0.09562134 -0.003976225 0.001690864 -0.1073617 -0.003453433 0.001559972 -0.1019833 -0.003692924 0.001619935 -0.1019214 -0.006139993 0.002317607 -0.1064046 -0.009213507 0.002590715 -0.10654 -0.008398234 0.002444803 -0.1059779 -0.01178711 0.00302428 -0.1059784 -0.01178407 0.003024458 -0.105979 -0.01178032 0.003024637 -0.1059798 -0.01177513 0.00302422 -0.1059815 -0.01176464 0.003023445 -0.1059902 -0.01171189 0.003016948 -0.1060199 -0.01153159 0.002989768 -0.1060836 -0.01114732 0.002926766 -0.1061127 -0.01097208 0.002896547 -0.1063444 -0.009575545 0.002655506 -0.08397161 -0.01360756 0.003714621 -0.09330481 -0.01329708 0.003502786 -0.09586352 -0.01181745 0.003568768 -0.09403049 -0.01321059 0.003475427 -0.09585398 -0.01299333 0.003406524 -0.07271194 -0.01398211 0.003970205 -0.08200186 -0.01367306 0.003759324 -0.08398461 -0.01159542 0.003693401 -0.06996804 -0.01386535 0.00402671 -0.06022268 -0.01131051 0.00375384 -0.06021928 -0.01345032 0.004227519 -0.05255347 -0.01312398 0.004385471 -0.05514186 -0.01323419 0.004332125 -0.05794948 -0.0133537 0.004274308 -0.04673331 -0.01259672 0.004381 -0.04836601 -0.01274466 0.004382252 -0.04836505 -0.01215839 0.00406742 -0.0495308 -0.01285016 0.004383146 -0.04837089 -0.01102381 0.00347501 -0.05232954 -0.01310372 0.004385292 -0.03474849 -0.01151102 0.004371941 -0.03557425 -0.01158583 0.004372537 -0.03652346 -0.01158958 0.004316687 -0.03652095 -0.01167154 0.004373252 -0.04115116 -0.01209104 0.004376769 -0.03376066 -0.0114215 0.004371166 -0.03653794 -0.01065444 0.00319159 -0.03059685 -0.01110213 0.004187762 -0.03061598 -0.01052504 0.003116428 -0.03032863 -0.01107507 0.004172265 -0.02430778 -0.01014548 0.003413081 -0.02446347 -0.0101695 0.003432691 -0.02467989 -0.0102818 0.003310263 -0.02468544 -0.01020377 0.003460645 -0.03001815 -0.01102709 0.004133105 -0.01877152 -0.009290695 0.002714991 -0.01878106 -0.009100496 0.002128899 -0.01758152 -0.009106993 0.002564907 -0.01638269 -0.008828222 0.002354979 -0.01396083 -0.007196545 6.97001e-4 -0.1000049 -0.01249879 0.003249824 -0.1018092 -0.0119974 0.00328505 -0.1018561 -0.009033679 0.003011882 -0.01880139 -0.008677423 0.001391887 -0.01582223 -0.008697867 0.00225687 -0.01343375 -0.008142471 0.001838624 -0.04244536 -0.01188433 0.004147112 -0.04244279 -0.01220804 0.004377782 -0.01888126 -0.009307622 0.002728819 -0.03656172 -0.009581983 0.002180457 -0.01433461 -0.006398618 1.43015e-4 -0.01886534 -0.006962954 -2.9415e-4 -0.02481716 -0.007293641 -6.08156e-4 -0.02476805 -0.008499026 4.45179e-4 -0.03068906 -0.00847274 7.03805e-4 -0.03659504 -0.00838232 0.001273453 -0.04841393 -0.008489012 0.002333283 -0.05433392 -0.008563399 0.002788245 -0.1018046 -0.01228433 0.003181874 -0.1048963 -0.006248593 0.002126634 -0.1068881 -0.006304025 0.002070069 -0.09590762 -0.008860528 0.003321588 -0.08403134 -0.00871706 0.00325793 -0.06026703 -0.008616447 0.003026306 0.006227552 0.003932952 -9.6907e-4 0.006582736 0.003124535 -0.001394808 0.001841366 0.001988649 -0.001514196 0.0010432 -0.003134012 -0.001976072 0.003526926 -0.002516388 -0.00221312 0.003614664 -0.00284332 -0.002070307 -0.00227338 0.005348622 4.68758e-4 -3.32296e-5 0.006082057 0.001041352 7.75754e-5 0.005923211 7.29228e-4 4.53591e-4 6.46605e-4 -0.001830875 1.37374e-4 0.001454651 -0.001602947 -0.004427134 0.00456798 -1.21407e-5 -0.004428684 0.00456798 -4.2906e-6 -6.24061e-5 0.006097912 0.001173913 -0.00443536 0.00456798 3.02703e-5 -0.004304647 0.004566431 -1.22628e-4 -0.004387557 0.004567801 -6.74091e-5 -0.004413187 0.004567921 -3.3706e-5 -0.004423856 0.00456798 -1.96593e-5 -0.003815293 0.004512786 -2.6496e-4 -0.003935754 0.004543662 -2.39569e-4 -0.004303395 0.004566371 -1.23021e-4 -0.002172529 0.00517106 1.82812e-4 -0.002467513 0.004167318 -5.48942e-4 5.11631e-4 0.005065619 -3.74308e-5 -0.002316713 0.004074156 -5.9416e-4 -0.001957118 0.00385195 -7.01931e-4 -1.02103e-4 0.002066612 -0.001430332 -1.11118e-4 0.002089619 -0.001423835 -0.001192629 0.003379583 -9.31091e-4 2.41861e-4 -0.002149939 -0.002070665 3.24771e-4 -0.001982629 -0.002100527 6.73264e-4 -0.00202763 -0.002125203 4.22031e-4 -0.001370906 -0.002071559 0.003134846 -0.001352727 -0.002275109 5.7131e-4 -4.31974e-4 -0.002027153 4.95523e-4 4.35314e-4 -0.001877129 -3.15592e-4 -0.003274917 -0.001869857 -1.36346e-4 -0.002913177 -0.001934409 -9.98452e-4 -0.004068255 -0.001434564 -8.89212e-4 -0.00396353 -0.001524984 0.001127421 -0.003434419 -0.001814424 -6.44654e-4 -0.003700137 -0.001689016 -5.88953e-4 -0.003628134 -0.001719594 -0.001049697 -0.004117369 -0.001392066 0.001145184 -0.003521263 -0.001718342 -0.001132667 -0.0041911 -0.001296579 -0.001166403 -0.004221081 -0.001257777 0.001179993 -0.00363779 -0.001517832 -0.001205384 -0.004254341 -0.001173257 0.003632426 -0.002942264 -0.001977741 0.003635168 -0.00300318 -0.00187242 0.001183092 -0.003636956 -0.001518249 0.008578658 -0.001933217 -0.002750515 0.00852257 -0.001768171 -0.002758562 0.00827521 -0.00104016 -0.002794027 0.006869256 0.00245881 -0.001710534 0.007163643 0.001761496 -0.002008557 0.008058488 -4.93959e-4 -0.002640902 0.004499673 0.007327556 0.0021829 -4.42713e-5 0.006084978 0.001297831 0.004497349 0.00731945 0.002212762 0.0044896 0.007292747 0.002311229 -7.29412e-5 0.006075084 0.001289844 -7.48038e-5 0.006074428 0.001289308 -0.004428684 0.00456798 7.26292e-5 0.00450176 0.007334828 0.002156198 0.004542648 0.007304012 0.00198239 0.004576385 0.007278561 0.001838624 0.00458467 0.007263958 0.001820087 0.004643023 0.007161259 0.001689732 0.004877448 0.006748497 0.001165688 0.005055189 0.006435692 7.68584e-4 0.008668005 -0.00228089 -0.00256735 0.008675932 -0.00234586 -0.002482533 0.003669023 -0.002994418 -0.001877307 0.008597433 -0.00198847 -0.002747833 0.00866425 -0.002250492 -0.002607047 0.008666038 -0.002264976 -0.002588152 0.003637194 -0.003002643 -0.001872718 0.005103468 0.006332576 6.97001e-4 0.005477249 0.005534708 1.43013e-4 0.006064295 0.004281461 -7.27076e-4 0.09877568 9.57641e-4 0.001263737 0.09903967 -6.29955e-4 9.74386e-4 0.08737832 -5.75968e-4 8.84881e-4 0.02787846 0.003694474 -7.61878e-4 0.02982789 0.00119102 -0.001743972 0.02373403 0.00406903 -0.001227438 0.02440965 0.001993834 -0.002372324 0.02296799 0.004138231 -0.001313507 0.02159827 0.002410411 -0.002698361 0.01872426 0.002519011 -0.002726793 0.01865696 0.004468798 -0.001663386 0.02195805 0.004215657 -0.001395463 0.0397076 0.003003239 6.02855e-4 0.03989797 0.002994954 6.25092e-4 0.04077285 -1.03873e-4 -5.60261e-4 0.04002642 0.002996265 6.36823e-4 0.04642254 -3.7199e-4 -5.39995e-5 0.04561358 0.003053665 0.001147091 0.05072021 -5.75942e-4 3.31108e-4 0.04563075 0.003053843 0.0011487 0.0521875 -5.71233e-4 3.60831e-4 0.04786229 0.003076732 0.001352488 0.05132347 0.003119111 0.001425147 0.02913779 0.003580689 -6.20401e-4 0.03166115 0.003352642 -3.36923e-4 0.03526192 3.85902e-4 -0.001113772 0.03752821 5.01042e-5 -8.51005e-4 0.09850436 0.002589464 0.001559972 0.09312593 0.00282818 0.001619338 0.08718496 0.003091871 0.001684904 0.07565081 -5.21672e-4 7.94868e-4 0.08646899 0.0031237 0.001692831 0.08676385 0.003110587 0.001689553 0.01288181 0.002423286 -0.002564013 0.00881797 0.003535866 -0.001492023 0.01006579 0.003701031 -0.001545965 0.01223111 0.00398761 -0.001639604 0.01494282 0.002661883 -0.002764225 0.0145381 0.004292964 -0.001739382 0.01577508 0.002630412 -0.002755999 0.01603144 0.004356741 -0.001711845 0.01805186 0.004442989 -0.001674532 0.05156064 0.003122031 0.001430153 0.05654823 0.003183066 0.001534819 0.06391376 -5.33619e-4 5.98372e-4 0.06952637 0.003289699 0.001617372 0.07237118 -5.06491e-4 7.69696e-4 0.0749529 0.003236532 0.001641511 0.07531476 0.003232955 0.001643121 0.1243261 1.23191e-4 3.63415e-4 0.1243407 -0.00100857 2.18558e-4 0.1240586 9.22027e-4 4.8614e-4 0.1235713 -0.00543195 -1.43171e-4 0.1241253 -0.003236114 -6.16163e-6 0.1238467 -0.004340171 -7.50502e-5 0.1243552 -0.00213468 7.44308e-5 0.1243575 -0.00231564 5.12702e-5 0.1202312 0.005052983 0.001117587 0.1205749 0.004916787 0.001079201 0.1211776 0.004457414 0.001003682 0.1170688 0.006306111 0.001470983 0.1191774 0.005470573 0.001235365 0.114885 0.006898224 0.001700818 0.1015666 0.009941041 0.002708435 0.09712231 0.01092159 0.003024339 0.09712052 0.01092314 0.00302428 0.1120304 0.007629632 0.001965105 0.1148834 0.006913065 0.001688718 0.1104617 0.007976174 0.002076566 0.1060146 0.008958518 0.00239247 0.09712469 0.01091152 0.003023505 0.09712374 0.01092028 0.003024339 0.1064066 -0.001029789 7.48721e-4 0.09803062 0.005439698 0.002072155 0.1061472 0.006115734 0.00195384 0.09775513 0.007097005 0.002369999 0.09768259 0.007534027 0.002445876 0.1239656 -0.00187087 1.38422e-4 0.1222706 -0.003443241 2.43834e-5 0.1235511 -5.75492e-5 3.90538e-4 0.1218906 -0.003272473 5.29028e-5 0.1223238 0.001476168 6.15474e-4 0.1205768 -0.00268203 1.51508e-4 0.120599 0.002597272 8.00386e-4 0.1166682 0.006464838 0.001515746 0.1211974 0.004419803 9.98148e-4 0.1216283 0.004113852 9.47187e-4 0.1229755 0.003034889 7.75631e-4 0.1220801 0.003769457 8.90554e-4 0.1229796 0.003083825 7.77803e-4 0.1191871 0.00545156 0.001223564 0.1210814 0.004066169 9.62739e-4 0.123246 0.002880752 7.44406e-4 0.1236167 0.002189755 6.4625e-4 0.12415 0.001195728 5.0505e-4 0.1243163 8.85866e-4 4.61029e-4 0.1228492 0.002732455 7.47162e-4 0.1239385 -0.003688395 -6.76187e-5 0.09715276 0.01072824 0.002998828 0.09712922 0.0108757 0.003019332 0.09712684 0.01089042 0.003021419 0.1060446 0.00889039 0.002394676 0.1148705 0.00679183 0.001689255 0.09754717 0.008350193 0.002587556 0.09725528 0.01010882 0.002892851 0.1060644 0.008351802 0.002313435 0.09715992 0.01068359 0.00299263 0.1190871 0.005058288 0.001181006 0.1148091 0.006343245 0.001631736 0.1233729 -0.004919052 -1.50792e-4 0.1232405 -0.004741787 -1.29756e-4 0.1226837 -0.003996312 -4.12655e-5 0.1193339 -0.002123415 2.44795e-4 0.1190643 -0.002089917 2.58254e-4 0.1186708 0.003425002 9.87589e-4 0.1173345 -0.001874744 3.44632e-4 0.1145535 0.00448054 0.001374304 0.1137419 -0.001427948 5.24026e-4 0.08699727 0.01218676 0.003427684 0.08517569 0.01236295 0.003481388 0.08518242 0.01234447 0.003502726 0.00996834 0.008538603 0.002934634 0.04067605 0.01199871 0.004414796 0.0406726 0.0120002 0.004419445 0.04347151 0.01223957 0.004396319 0.03506851 0.01148861 0.004529654 0.03786903 0.0117278 0.004486262 0.03786844 0.01174008 0.004475831 0.03506892 0.01145941 0.004554629 0.03226661 0.01122456 0.004606366 0.03226619 0.01120799 0.004621207 0.02665406 0.01069104 0.004693627 0.0266602 0.01072239 0.004651427 0.02106624 0.01017814 0.004424691 0.04380065 0.0117287 0.004382252 0.04921859 0.01194983 0.004269599 0.04915654 0.01232433 0.004322528 0.03229302 0.01092326 0.004654526 0.03793448 0.01131814 0.004521071 0.03789728 0.01153522 0.004524648 0.0929479 0.01155817 0.003232598 0.09199243 0.01170355 0.003280282 0.0911678 0.0117833 0.0033046 0.09521728 0.01121276 0.003119289 0.09592831 0.01110458 0.003083825 0.09712082 0.0109207 0.003028154 0.03788483 0.01160961 0.004520058 0.04911661 0.01250541 0.004339694 0.0266546 0.01052767 0.004785478 0.02668434 0.01053076 0.004787266 0.02665102 0.01064813 0.004730343 0.03227245 0.01110792 0.004667758 0.02104014 0.0101186 0.004528462 0.02108651 0.01007854 0.004509568 0.02661991 0.0105884 0.004754841 0.009967327 0.008316397 0.003193199 0.01544755 0.009340524 0.004075586 0.01545262 0.00943607 0.003993809 0.01579827 0.009406089 0.004132032 0.02104389 0.009948015 0.004447758 0.0155121 0.009501636 0.003731131 0.009941279 0.008536994 0.003078639 0.0154758 0.009485065 0.003874301 0.009926736 0.008507132 0.003202378 0.02105158 0.01015323 0.004479527 0.02946066 0.01093357 0.004691183 0.02946293 0.01097023 0.00465697 0.03507578 0.01138871 0.004582822 0.03787595 0.01166844 0.004510283 0.0434823 0.01217025 0.00442475 0.03787279 0.01169204 0.004503488 0.03507035 0.01143944 0.004565298 0.03226768 0.01116472 0.004647076 0.03787046 0.01171183 0.004495501 0.03506833 0.0114758 0.004542768 0.03226792 0.01123774 0.004590272 0.02667534 0.01074761 0.004578113 0.03226995 0.01124763 0.004572987 0.03506952 0.01149785 0.00451529 0.03786861 0.01174867 0.004464268 0.06111377 0.01306134 0.004062652 0.04909008 0.01263052 0.004333317 0.04909336 0.01261413 0.004336953 0.04347318 0.01222378 0.00441122 0.04347532 0.01221001 0.004416942 0.04207146 0.01210927 0.004424691 0.04067099 0.01198005 0.00444585 0.04066997 0.01199144 0.004437565 0.03926891 0.01187098 0.004450559 0.04066979 0.01199901 0.004428148 0.03926932 0.01187723 0.004439532 0.04347163 0.01223707 0.004400491 0.04628241 0.01245099 0.004373669 0.04628175 0.01245516 0.004370629 0.04908776 0.01264268 0.004328548 0.0490849 0.0126475 0.004322171 0.04908359 0.01264977 0.004319369 0.04628157 0.01245522 0.004365026 0.04628133 0.01245844 0.004367351 0.04347187 0.01223582 0.004393994 0.04066997 0.01200139 0.004423022 0.04207068 0.01211804 0.004416644 0.04347193 0.01223361 0.004404306 0.03358656 0.01136147 0.004431903 0.03228598 0.01125413 0.004491746 0.03573763 0.01155972 0.004440367 0.03787153 0.01175051 0.004439592 0.03787559 0.01173406 0.004419922 0.03951001 0.01186734 0.004404246 0.0406751 0.01196235 0.0043931 0.03786963 0.01175361 0.004451513 0.03507137 0.01150363 0.004499852 0.03227281 0.01125419 0.00455445 0.0266819 0.01075017 0.004551053 0.02110505 0.01019823 0.004297673 0.02666443 0.01073372 0.00462836 0.0266695 0.01074212 0.004603862 0.02766412 0.01081556 0.004408597 0.02671635 0.01072818 0.004404902 0.02669745 0.01074653 0.004493117 0.02570062 0.01063454 0.004400908 0.02560234 0.01062422 0.004394173 0.01581948 0.009469509 0.003561079 0.01557415 0.009432554 0.003529727 0.01470464 0.009301424 0.003418684 0.02174031 0.01021867 0.00413078 0.02116256 0.010158 0.004091322 0.01860314 0.009889245 0.00391674 0.04067289 0.01196479 0.004453003 0.0322808 0.01125741 0.0045138 0.03229254 0.01124215 0.004426836 0.09712302 0.01090592 0.003035068 0.09712105 0.01091921 0.003029048 0.09712082 0.01092052 0.003028452 0.09117478 0.01177114 0.003326952 0.07167333 0.01301598 0.003772318 0.063232 0.01307272 0.003986835 0.07314842 0.01294869 0.003741204 0.06110662 0.01308697 0.004040837 0.06110852 0.01308989 0.004053652 0.0844559 0.01243257 0.003502607 0.07511359 0.01285898 0.003699719 0.07315552 0.01293557 0.003756165 0.04347836 0.01219213 0.004421412 0.04910296 0.01256859 0.004340708 0.06113511 0.01295101 0.004068613 0.07317423 0.01282882 0.003762006 0.08519858 0.01224368 0.003507316 0.097126 0.0108866 0.003038644 0.09712833 0.0108723 0.00303924 0.09118992 0.01167464 0.003331243 0.09713953 0.0108022 0.003042221 0.09123259 0.01110798 0.003240704 0.09719997 0.0104314 0.003019154 0.08526152 0.01178491 0.003462493 0.06122654 0.0124399 0.004019916 0.0631653 0.01251906 0.003979623 0.0732485 0.0122233 0.003750324 0.08423745 0.01190102 0.003500521 0.01198053 0.008890688 0.003070592 0.01002264 0.008464395 0.002744853 0.009914994 0.008440971 0.002726912 0.006968259 0.007799327 0.002236604 0.007677972 0.007953882 0.002354681 0.05136048 0.01274979 0.004265248 0.06036478 0.01309198 0.004059672 0.04943299 0.01267653 0.004309237 0.04908645 0.01264828 0.004312574 0.04628443 0.01241976 0.004339396 0.04543322 0.01235038 0.004347562 0.04347598 0.01219075 0.004366278 0.03227639 0.01125741 0.004534721 0.03507393 0.01150602 0.004483163 0.03787046 0.01175475 0.004444718 0.04964941 0.01015585 0.003883063 0.05037164 0.007014453 0.003110408 0.06227421 0.007307052 0.003040254 0.09725534 0.01009595 0.002973198 0.01164996 0.003525257 0.001948058 0.01408159 0.003657996 0.001990318 0.01590347 0.007345557 0.003911972 0.0172106 0.003403186 0.001982688 0.02266019 0.002959489 0.001969337 0.02148765 0.007526099 0.004205107 0.02282249 0.002934634 0.001963078 0.0272684 0.007510006 0.004178285 0.0286687 0.00203979 0.001735866 0.03550219 9.93798e-4 0.001470386 0.03883546 0.007104218 0.003481805 0.04042357 3.1143e-4 0.001248478 0.0446186 0.006963253 0.003210663 0.04630267 -5.03738e-4 9.83398e-4 0.04653674 -5.36197e-4 9.72843e-4 0.03825247 0.009775757 0.00422132 0.02682805 0.009461224 0.00473833 0.02104324 0.009680569 0.004695355 0.02102738 0.009874224 0.004665791 0.01544529 0.009239256 0.004165589 0.004497408 0.007228314 0.002395749 0.004499375 0.007212042 0.002417027 0.009955763 0.008246064 0.003466546 0.01554417 0.008657872 0.004238188 0.01546269 0.009084343 0.004217028 0.009933292 0.008364379 0.003395318 0.004500985 0.007198631 0.002434611 0.004567146 0.006938517 0.002575516 0.01004284 0.007909774 0.003546833 0.0211237 0.009148895 0.004663765 0.02670818 0.01010918 0.004823386 0.02667337 0.01034682 0.004819571 0.09768271 0.007506132 0.002618849 0.09791666 0.006088733 0.002424895 0.09202027 0.006627559 0.002632617 0.08608579 0.006990134 0.002746939 0.07418668 0.007305562 0.002887904 0.01039522 0.006836533 0.003415107 0.004585862 0.006883382 0.002578318 0.004643023 0.00671494 0.00258702 0.00488609 0.005998492 0.002623856 0.005107104 0.00544095 0.002468764 0.005988955 0.003216207 0.001849651 0.09903967 -6.87086e-4 0.001322209 0.09212255 -6.09429e-4 0.001399219 0.08737254 -6.40505e-4 0.001362562 0.0756511 -7.1719e-4 0.001272141 0.06391793 -7.93953e-4 0.001181602 0.05888658 -8.2687e-4 0.001142799 0.05218893 -6.69231e-4 0.001050591 0.1238566 -0.004342138 -7.86078e-5 0.1009581 -0.01220178 -9.10667e-4 0.1009584 -0.01220327 -9.13081e-4 0.1125763 -0.009721577 -5.43405e-4 0.1209225 -0.006765365 -2.46351e-4 0.1222484 -0.006097912 -1.94703e-4 0.119214 0.005560457 0.001238882 0.09768176 0.01081866 0.002995312 0.09824192 0.01071536 0.002960324 0.09740144 0.01086938 0.003012478 0.09743648 0.01086306 0.003010332 0.1082556 0.008535563 0.002260863 0.111161 0.007837355 0.002040982 0.1112993 0.007803916 0.002029836 0.1060388 0.009048104 0.002422571 0.1060368 0.009040594 0.002420067 0.1015926 0.01004636 0.002735376 0.09754163 0.01084411 0.003003895 0.09747153 0.01085674 0.003008186 0.0993607 0.0105012 0.002887845 0.10604 0.009015858 0.002428293 0.1060448 0.008885443 0.002429723 0.106065 0.008341133 0.002388536 0.1061483 0.006092131 0.00211656 0.1110228 0.007870793 0.002052068 0.1104696 0.008004546 0.002095699 0.1115758 0.00773698 0.002007246 0.1126813 0.007468819 0.001913428 0.113747 -0.001460671 7.74491e-4 0.1186736 0.00341171 0.001109898 0.1145564 0.004463374 0.001510858 0.1190884 0.005052328 0.001237452 0.1148105 0.006335496 0.001694798 0.1170683 0.006304204 0.001471042 0.1173539 0.006255924 0.001444697 0.1172185 0.006298243 0.001459598 0.1148887 0.006923258 0.00170958 0.1148874 0.006920635 0.001704514 0.1148712 0.006788253 0.00171864 0.1191878 0.005448758 0.001249909 0.1148853 0.006896495 0.001714944 0.1210824 0.004061162 0.001014471 0.1211979 0.004417479 0.001022279 0.1192111 0.00554347 0.001244425 0.1205442 0.004933357 0.001083731 0.1205286 0.00494188 0.00108546 0.1229953 0.003096997 7.87078e-4 0.122085 0.003776967 8.91082e-4 0.1212273 0.004518091 0.001010775 0.1212316 0.004523456 0.001011312 0.122976 0.003032922 7.96889e-4 0.1230056 0.00310564 7.91098e-4 0.1212251 0.004502534 0.001016438 0.120552 0.004929065 0.001082897 0.1205559 0.004926919 0.001082479 0.1204974 0.004958808 0.001088857 0.1205598 0.004924833 0.001082003 0.1206219 0.004890441 0.001075267 0.1207457 0.004820823 0.001061737 0.1171168 0.006329476 0.001470744 0.1171507 0.006319105 0.001467049 0.1192166 0.005566835 0.00123912 0.1181609 0.005985617 0.001354992 0.1176241 0.00616914 0.001414835 0.1170998 0.006334602 0.001472651 0.1170913 0.006337225 0.001473546 0.1190707 -0.002084076 4.63631e-4 0.1206589 -0.002527296 3.54694e-4 0.1223256 0.001466691 7.14242e-4 0.1235537 -6.53127e-5 4.70449e-4 0.1240598 9.18533e-4 5.23021e-4 0.1243542 -0.001215577 2.19168e-4 0.1244468 -0.001056075 2.17058e-4 0.1242041 -0.003282666 -3.77819e-5 0.1232066 0.002916455 7.56073e-4 0.1232537 0.002863287 7.48328e-4 0.1232886 0.002823054 7.4248e-4 0.1233001 0.002809584 7.40523e-4 0.123277 0.002836525 7.44433e-4 0.1232712 0.002843201 7.45409e-4 0.1236143 0.00218594 6.47157e-4 0.1232654 0.002849936 7.46383e-4 0.1237351 0.002227783 6.569e-4 0.1237304 0.002235233 6.57961e-4 0.1238727 0.002000987 6.24585e-4 0.1238009 0.002122879 6.41938e-4 0.1243212 8.52223e-4 4.61406e-4 0.1243222 8.47927e-4 4.60801e-4 0.1243591 6.79816e-4 4.3716e-4 0.1243129 8.86562e-4 4.66251e-4 0.1242956 9.55085e-4 4.75934e-4 0.1244578 -0.001017093 2.13299e-4 0.1241952 0.00120908 5.1592e-4 0.1244686 -0.001017987 2.12772e-4 0.1242097 0.001212954 5.18431e-4 0.1243279 1.2084e-4 3.63603e-4 0.1243252 8.35034e-4 4.58983e-4 0.1243232 8.43628e-4 4.60195e-4 0.1237447 0.002212882 6.54775e-4 0.1237637 0.00218302 6.50513e-4 0.1240046 0.001751065 5.89048e-4 0.117354 -0.001781642 5.68245e-4 0.1206009 0.002586066 9.1258e-4 0.1228501 0.002728164 7.92748e-4 0.1241812 0.00115621 5.2374e-4 0.1243697 -0.002135038 7.66697e-5 0.1243704 -0.002134978 7.64206e-5 0.1243451 -0.002380192 4.96432e-5 0.1243457 -0.002375841 5.01252e-5 0.1241874 -0.003273189 -3.10489e-5 0.1243005 -0.002704322 1.4904e-5 0.124344 -0.002388954 4.86802e-5 0.1243394 -0.002424061 4.48404e-5 0.1243576 -0.002283751 6.03246e-5 0.1243486 -0.002353906 5.2541e-5 0.1243463 -0.00237143 5.06076e-5 0.1243292 8.17834e-4 4.5656e-4 0.1129353 -0.00736922 -7.58306e-5 0.1160324 -0.006962895 -7.54767e-5 0.1177205 -0.008377194 -3.71079e-4 0.1182717 -0.008099734 -3.49611e-4 0.1183072 -0.008021712 -3.31601e-4 0.1195959 -0.007433116 -2.98026e-4 0.1232601 -0.004730165 -8.55527e-5 0.1225807 -0.005768656 -1.55519e-4 0.1215083 -0.006052494 -1.37799e-4 0.1189913 -0.006512701 -8.72775e-5 0.1219442 -0.003179907 2.14288e-4 0.1239678 -0.001875877 1.93665e-4 0.1241528 -0.003361821 -3.46587e-5 0.1009587 -0.01220512 -9.16135e-4 0.1009588 -0.01220536 -9.19384e-4 0.1027026 -0.01188278 -8.63651e-4 0.1109333 -0.01015096 -5.98448e-4 0.1067822 -0.01102435 -7.32199e-4 0.1009585 -0.01220405 -9.14406e-4 0.1009538 -0.01217794 -8.95779e-4 0.1009558 -0.01218968 -9.01083e-4 0.1009569 -0.01219558 -9.05788e-4 0.1154501 -0.008970558 -4.47136e-4 0.1126168 -0.009666204 -4.87837e-4 0.1009267 -0.01201826 -8.48369e-4 0.1009382 -0.01208674 -8.63552e-4 0.1009448 -0.01212602 -8.72252e-4 0.100951 -0.01216208 -8.88588e-4 0.100595 -0.01003599 -4.09108e-4 0.1008239 -0.01140362 -7.12169e-4 0.1126789 -0.009223401 -3.91598e-4 0.1008724 -0.01169365 -7.76444e-4 0.1239391 -0.003690063 -3.92622e-5 0.1227388 -0.00396645 5.09908e-5 0.1203331 -0.006287455 -1.0857e-4 0.1184657 -0.007764101 -2.61186e-4 0.09958362 -0.003962874 7.52347e-4 0.1003968 -0.008850514 -1.52638e-4 0.1004252 -0.009021461 -1.84291e-4 0.106412 -0.001020967 0.001071274 0.09930795 -0.002303123 0.001043975 0.1060145 0.008958518 0.00239247 0.109363 0.008271038 0.002179801 0.1237279 0.002238929 6.58491e-4 0.123391 0.002700507 7.24729e-4 0.1129324 -0.007352054 -2.12388e-4 0.1189895 -0.006503224 -1.86046e-4 0.1225801 -0.005767047 -1.83875e-4 0.121119 -0.006705284 -2.42175e-4 0.1126162 -0.009662628 -5.17235e-4 0.1009544 -0.01217865 -9.12348e-4 0.1009511 -0.0121594 -9.0824e-4 0.1096886 -0.0104075 -6.40134e-4 0.1009587 -0.0122044 -9.1838e-4 0.1009584 -0.01220279 -9.17682e-4 0.1009582 -0.0122019 -9.173e-4 0.1009578 -0.01219898 -9.1668e-4 0.1009569 -0.01219427 -9.15677e-4 0.1009403 -0.01209485 -8.94497e-4 0.1009324 -0.01204794 -8.84502e-4 0.1183387 -0.008061349 -3.38965e-4 0.1184648 -0.007759809 -3.06772e-4 0.1126775 -0.009215652 -4.54633e-4 0.121506 -0.006047487 -1.93042e-4 0.1203305 -0.006279706 -1.88481e-4 0.1160295 -0.006949603 -1.97796e-4 0.1009268 -0.01201432 -8.7841e-4 0.1008813 -0.01174074 -8.28858e-4 0.1008241 -0.01139622 -7.71753e-4 0.1003968 -0.008819937 -3.44677e-4 0.1001656 -0.007426023 -1.13598e-4 0.09518694 -0.01231068 -0.001021265 0.05400604 -0.008459627 -0.001714289 0.04809266 -0.007996618 -0.00215429 0.03674471 -0.005897343 -0.003453671 0.04233425 -0.007168114 -0.002770543 0.04292005 -0.009837269 -0.003558874 0.03741848 -0.008987426 -0.004321753 0.03725957 -0.008207201 -0.004149258 0.03180241 -0.006966352 -0.004807233 0.03751891 -0.009466588 -0.004376947 0.04329335 -0.01121193 -0.003928244 0.04686796 -0.01229232 -0.003650486 0.04875093 -0.01095986 -0.003001391 0.01457011 -0.002150952 -0.0040766 0.0144822 -0.001812458 -0.004155755 0.01753586 -0.00236845 -0.004722595 0.01744771 -0.001986861 -0.004772722 0.02050709 -0.002841353 -0.005153596 0.0204249 -0.002414047 -0.005170524 0.02340596 -0.003725469 -0.005288124 0.02333235 -0.003248095 -0.005273222 0.02619779 -0.004858314 -0.005195558 0.02611589 -0.004328131 -0.00515455 0.03168094 -0.006322026 -0.004705309 0.01460427 -0.002489447 -0.003893673 0.0145927 -0.002269864 -0.00400567 0.01703208 -0.002548217 -0.0044716 0.0175575 -0.002505064 -0.004660785 0.01755994 -0.002656459 -0.004540443 0.02052468 -0.002996027 -0.005104005 0.02621418 -0.00505042 -0.005170762 0.02340143 -0.004063606 -0.005137443 0.0234186 -0.00389868 -0.005251646 0.02234256 -0.003637254 -0.005164265 0.02051097 -0.003261625 -0.00492537 0.03693926 -0.00929141 -0.004422008 0.03185743 -0.007375478 -0.004768013 0.03183794 -0.007201194 -0.004812359 0.02822446 -0.006005823 -0.005015373 0.02621376 -0.005196154 -0.005066275 0.09443378 -0.007830142 -2.09129e-4 0.0666089 -0.013839 -0.002325534 0.06556117 -0.008680045 -0.001172065 0.06728667 -0.0138548 -0.002282917 0.0771178 -0.008425652 -7.18996e-4 0.07804679 -0.01336151 -0.001770257 0.08948636 -0.01283705 -0.001225233 0.08866691 -0.008036553 -3.49353e-4 0.09030145 -0.01279968 -0.00118643 0.01412642 -7.30787e-4 -0.004019081 0.03123641 -0.004369854 -0.004118561 0.02574789 -0.002701461 -0.004678845 0.02298086 -0.001781821 -0.004855453 0.02006238 -0.001094996 -0.004834294 0.01708233 -7.92828e-4 -0.004535198 0.06088483 -0.01370519 -0.002685487 0.05977964 -0.008665978 -0.001433432 0.05644088 -0.0136013 -0.002964973 0.05472862 -0.0115993 -0.002549171 0.05517196 -0.01342779 -0.00305587 0.04915434 -0.01260495 -0.003486752 -3.80918e-4 -0.003367185 -6.37968e-4 -7.7039e-4 -0.003808379 -8.08898e-4 0.001013398 -0.003376066 -0.001091241 -0.001013755 -0.00408411 -9.15717e-4 -0.001105964 -0.004167139 -9.78364e-4 0.001114249 -0.003553688 -0.001377224 -0.001208186 -0.004256665 -0.00110352 -0.001210868 -0.00425893 -0.001132249 0.001140296 -0.003579735 -0.001502692 -0.001154839 -0.004211068 -0.00101155 -0.001192331 -0.004243254 -0.001060247 -0.001195311 -0.004245758 -0.001068353 -1.53899e-4 -0.002904653 -4.73654e-4 0.001719474 0.001086175 9.30187e-4 3.61845e-4 8.01361e-4 8.09904e-4 0.003049314 -0.001990735 -5.46843e-4 5.7131e-4 -4.31974e-4 4.13705e-4 3.69415e-4 -0.001838445 -9.49092e-5 -7.79331e-6 -0.002606987 -3.67907e-4 6.13153e-4 -0.002493441 -4.24951e-4 -0.0018211 0.003817856 0.001211285 -0.001720607 0.003771185 0.001236319 4.25935e-4 0.004427671 0.001691281 -5.57631e-4 0.002732634 0.001259803 -3.97727e-4 0.002526283 0.00123316 -1.43781e-4 0.002044141 0.001126527 2.9096e-4 0.001218736 9.43998e-4 -0.00194025 0.003873229 0.001181542 3.38703e-5 0.005591392 0.001629352 -0.002962052 0.004348039 9.26914e-4 -5.38826e-5 0.005918323 0.001486599 -0.004027724 0.004551887 4.40097e-4 -0.003488004 0.004448652 6.8665e-4 -7.16299e-5 0.006017327 0.001394033 -0.004246652 0.004564702 2.88947e-4 -0.004146575 0.004558861 3.58023e-4 -0.004421174 0.00456798 9.27364e-5 -0.004365921 0.004567623 1.76793e-4 -0.00433737 0.004566907 2.03619e-4 0.003623425 -0.003023028 -0.001758337 0.006289899 0.002502977 0.001545965 0.008668363 -0.002372682 -0.002385079 0.008665978 -0.002381205 -0.002354323 0.003594219 -0.003007173 -0.001625716 0.00866419 -0.002387702 -0.00233072 0.008623778 -0.0023579 -0.002157151 0.008590757 -0.002333581 -0.002015352 0.003483414 -0.002848327 -0.001313567 0.008522331 -0.002213656 -0.001861393 0.008461475 -0.002106964 -0.001724541 0.008288979 -0.001804649 -0.001336574 0.008122444 -0.001512587 -9.61902e-4 0.008061826 -0.001383423 -8.71699e-4 0.007806181 -8.38411e-4 -4.91219e-4 0.006951153 9.84247e-4 7.8119e-4 0.006582736 0.001822292 0.001223504 -0.008875966 -0.002717018 0.001105606 -0.008736014 -0.002915918 0.0011366 -0.008758783 -0.002931952 0.005023539 -0.006928682 -0.004762053 0.005023539 -0.006926178 -0.004756152 0.001197338 -0.004428684 -0.00543195 0.005023539 -0.005688548 -0.0052706 8.51093e-4 -0.005371451 -0.00532031 6.92711e-4 -0.004709422 -0.005424082 3.62117e-4 -0.00452739 -0.005430161 2.04954e-4 -0.008081316 -0.003846347 0.001281678 -0.007033646 -0.004686892 0.001213669 -0.006969988 -0.004737973 0.001209557 -0.009235858 -0.001668274 8.1272e-4 -0.009428679 -4.31974e-4 0.005023539 -0.009341895 -0.001359224 7.26399e-4 -0.008902132 0.001748204 -3.73641e-4 -0.008993327 0.00160861 -3.246e-4 -0.008758783 0.002067983 0.005023539 -0.009180605 0.001123249 -1.49132e-4 -0.009428679 -4.31974e-4 4.13705e-4 -0.0078547 0.00320971 -0.001434504 -0.006928682 0.003898143 -0.004976391 -0.007854819 0.00320959 -0.001434564 -0.008277118 0.00273478 -0.001710772 -0.007726132 0.003325521 -0.001296699 -0.007693648 0.003354787 -0.001261949 -0.007651925 0.003390371 -0.001173257 -0.00768882 0.00335896 -0.001026272 -0.007734179 0.003319442 -9.83757e-4 -0.007647037 0.003394484 -0.001144945 -0.007649123 0.003392755 -0.00110352 -0.006928682 0.003898143 0.005023539 -0.007659792 0.003383755 -0.001070678 -0.007661402 0.003382325 -0.001068174 -0.007745742 0.003308951 -9.76565e-4 -0.007842719 0.003220975 -9.16169e-4 -0.007972598 0.00309509 -8.5494e-4 -0.008131206 0.002928256 -7.88247e-4 -0.008712768 0.002038002 -4.75475e-4 -0.009108185 0.001294255 -0.002080321 -0.009085416 0.001388549 -0.002080261 -0.008758783 0.002067983 -0.004976391 -0.008721113 0.002047121 -0.001932561 -0.008445322 0.002545654 -0.001820802 -0.009292185 5.32548e-4 -0.002081215 -0.009428679 -4.31974e-4 -0.004976391 -0.009403049 7.3432e-5 -0.002081751 -0.008710563 -0.002907574 -0.001423835 -0.009005069 -0.002322971 -0.001606702 -0.008758783 -0.002931952 -0.004976391 -0.009192049 -0.001951813 -0.001722812 -0.009428679 -4.31974e-4 -0.002027153 -0.008485019 -0.003355264 -0.001283764 -0.006928682 -0.004762053 -0.004976391 -0.007255613 -0.004556059 -7.90424e-4 -0.001928687 -0.004762053 -0.004976391 -0.004428684 -0.00543195 -1.94507e-6 -0.004428684 -0.00543195 -0.004976391 -0.004433453 -0.00543195 -1.96593e-5 -0.004442334 -0.00543195 -3.43327e-5 -0.004447162 -0.00543189 -4.23552e-5 -0.00449115 -0.005431532 -8.52346e-5 -0.004563927 -0.005429327 -1.19918e-4 -0.004670858 -0.005426049 -1.70906e-4 -0.004860818 -0.005413234 -2.25047e-4 -0.005039453 -0.005392193 -2.64206e-4 -0.005167365 -0.005377054 -2.92257e-4 -0.005647599 -0.00528109 -3.87105e-4 -0.005841314 -0.005228221 -4.26483e-4 -0.00651586 -0.004907667 -6.00063e-4 -0.006908953 -0.004720807 -7.01225e-4 -0.004482805 -0.005431652 1.66456e-4 -0.004428684 -0.00543195 7.26292e-5 -0.001928687 -0.004762053 0.005023539 -0.004426121 -0.00543195 6.3499e-5 -0.004422366 -0.00543195 2.13087e-5 -0.004428684 0.00456798 0.005023539 -0.001928687 0.003898143 0.005023539 -9.85563e-5 0.002067983 0.005023539 5.7131e-4 -4.31974e-4 0.005023539 -9.85563e-5 -0.002931952 0.005023539 -9.85563e-5 -0.002931952 -0.004976391 5.7131e-4 -4.31974e-4 -0.004976391 -9.85563e-5 0.002067983 -0.004976391 -0.001928687 0.003898143 -0.004976391 -0.004428684 0.00456798 -0.004976391 -0.03555476 -0.0116105 0.004493117 -0.0188257 -0.009402573 0.002934634 -0.01340001 -0.008167982 0.00198239 -0.01335912 -0.008198797 0.002156198 -0.02436947 -0.0103656 0.003731131 -0.04672884 -0.01261895 0.004437625 -0.0439257 -0.01233971 0.004542768 -0.04672783 -0.01257574 0.004495501 -0.0467264 -0.01259177 0.004486262 -0.03551143 -0.01155501 0.004693627 -0.03551757 -0.01158636 0.004651427 -0.02992361 -0.01104205 0.004424691 -0.03547728 -0.01145237 0.004754841 -0.03550839 -0.0115121 0.004730343 -0.02989751 -0.01098257 0.004528462 -0.02994382 -0.01094245 0.004509568 -0.02990126 -0.01081198 0.004447758 -0.03551197 -0.01139163 0.004785478 -0.04392772 -0.01230341 0.004565298 -0.04112356 -0.0120719 0.004621207 -0.04112505 -0.01202869 0.004647076 -0.03831803 -0.01179754 0.004691183 -0.04393315 -0.01225262 0.004582822 -0.0467422 -0.01247358 0.004520058 -0.04673331 -0.01253235 0.004510283 -0.09403598 -0.01318621 0.003482103 -0.1059782 -0.01178449 0.003027975 -0.105978 -0.01178592 0.003026843 -0.05807596 -0.0128138 0.004269599 -0.05801391 -0.01318824 0.004322528 -0.05265802 -0.01259267 0.004382252 -0.04675465 -0.01239919 0.004524648 -0.04112982 -0.01197189 0.004667758 -0.01882469 -0.009180366 0.003193199 -0.02430492 -0.01020449 0.004075586 -0.02430999 -0.01030004 0.003993809 -0.02465564 -0.01027005 0.004132032 -0.03554171 -0.01139467 0.004787266 -0.04115039 -0.01178723 0.004654526 -0.04679185 -0.01218211 0.004521071 -0.01879864 -0.009400963 0.003078639 -0.02433317 -0.01034903 0.003874301 -0.0187841 -0.009371042 0.003202378 -0.01335471 -0.008183419 0.002212762 -0.01334697 -0.008156657 0.002311229 -0.02990895 -0.01101714 0.004479527 -0.0383203 -0.0118342 0.00465697 -0.05233967 -0.01303416 0.00442475 -0.05233573 -0.01305609 0.004421412 -0.05233269 -0.01307392 0.004416942 -0.04112398 -0.01208847 0.004606366 -0.04392629 -0.01232337 0.004554629 -0.04673016 -0.01255595 0.004503488 -0.04952836 -0.01284396 0.00444585 -0.04953026 -0.0128287 0.004453003 -0.05233055 -0.01308774 0.00441122 -0.05092883 -0.01297324 0.004424691 -0.0523293 -0.01309758 0.004404306 -0.05092805 -0.01298201 0.004416644 -0.04112529 -0.0121017 0.004590272 -0.04392588 -0.01235252 0.004529654 -0.0467258 -0.01260405 0.004475831 -0.04812628 -0.01273488 0.004450559 -0.04952734 -0.01285541 0.004437565 -0.04952716 -0.01286298 0.004428148 -0.04952776 -0.01286679 0.004417598 -0.05232888 -0.01310348 0.004396319 -0.04952841 -0.01286727 0.004411876 -0.05232918 -0.01310348 0.004391789 -0.052329 -0.01310104 0.004400491 -0.04952734 -0.0128653 0.004423022 -0.04114335 -0.0121181 0.004491746 -0.04113817 -0.01212137 0.0045138 -0.0439313 -0.01236993 0.004483163 -0.04113376 -0.01212137 0.004534721 -0.04392874 -0.0123676 0.004499852 -0.046727 -0.01261758 0.004451513 -0.04672783 -0.01261872 0.004444718 -0.04672598 -0.01261264 0.004464268 -0.04812669 -0.0127412 0.004439532 -0.03553926 -0.01161408 0.004551053 -0.03553271 -0.01161152 0.004578113 -0.04112732 -0.01211154 0.004572987 -0.02996242 -0.01106214 0.004297673 -0.0355218 -0.01159763 0.00462836 -0.03552687 -0.01160603 0.004603862 -0.04113018 -0.0121181 0.00455445 -0.04392689 -0.01236182 0.00451529 -0.1059858 -0.01173609 0.003037989 -0.1059826 -0.01175594 0.00303626 -0.1059934 -0.01168817 0.003042161 -0.1059803 -0.01177006 0.003035008 -0.1059798 -0.01177358 0.003033697 -0.1059787 -0.01178091 0.003030896 -0.1059784 -0.01178312 0.003029108 -0.06999248 -0.01381492 0.004068613 -0.1060574 -0.01129537 0.003019154 -0.1060496 -0.01134252 0.003023326 -0.10009 -0.01197189 0.003240704 -0.10601 -0.01158595 0.003036618 -0.1059969 -0.01166623 0.003040969 -0.09405595 -0.01310765 0.003507316 -0.09411889 -0.01264882 0.003462493 -0.07008391 -0.01330387 0.004019916 -0.07202267 -0.01338303 0.003979623 -0.08210587 -0.01308727 0.003750324 -0.09309482 -0.01276493 0.003500521 -0.01335704 -0.008191525 0.0021829 -0.1148881 -0.009864032 0.002387702 -0.1332639 -9.91036e-4 3.59554e-4 -0.1332105 1.37593e-4 2.22868e-4 -0.1329159 -0.001785933 4.8614e-4 -0.1325061 -0.003080189 6.49733e-4 -0.1318026 -0.003914415 7.74422e-4 -0.1323622 -0.003428637 6.98899e-4 -0.1259226 -0.007164001 0.001471459 -0.1237345 -0.007758498 0.001661658 -0.1255561 -0.007319986 0.001512467 -0.1104441 -0.01088839 0.00272417 -0.1122122 -0.01053255 0.002605378 -0.1148852 -0.009889006 0.00238645 -0.1150046 -0.006979703 0.00195384 -0.1152644 1.62548e-4 7.53977e-4 -0.1078971 -2.33994e-4 9.74386e-4 -0.1076331 -0.001821577 0.001263737 -0.1294564 -0.003461241 8.00386e-4 -0.1279217 0.001227974 2.58072e-4 -0.1275281 -0.004288971 9.87589e-4 -0.126191 0.001025199 3.43305e-4 -0.1234109 -0.00534445 0.001374304 -0.1300822 -0.005367636 0.001004815 -0.1309464 -0.004657685 8.89974e-4 -0.1300888 -0.005387961 0.001005649 -0.1305189 -0.005028843 9.47673e-4 -0.1300894 -0.005390882 0.001005053 -0.1301138 -0.005380451 0.001002311 -0.1280074 -0.006276845 0.001238107 -0.1300548 -0.005283772 9.98148e-4 -0.1299388 -0.004930138 9.62739e-4 -0.1317065 -0.003596425 7.47162e-4 -0.1332747 -0.001219511 3.8723e-4 -0.1329362 -0.002039074 5.02851e-4 -0.1290518 -0.005832374 0.001121163 -0.1329752 0.002486169 -3.54494e-5 -0.1331571 0.001267969 8.59662e-5 -0.1331155 0.002147495 -2.05478e-5 -0.1330479 0.002385914 -3.26261e-5 -0.1324287 0.00456798 -1.43171e-4 -0.1327374 0.003479957 -8.80514e-5 -0.114902 -0.0097543 0.002394676 -0.1193101 -0.008823752 0.002024054 -0.1237279 -0.007655739 0.001689255 -0.1149218 -0.009215772 0.002313435 -0.1279444 -0.005922257 0.001181006 -0.1236665 -0.007207214 0.001631736 -0.1321804 0.003968119 -1.45526e-4 -0.1327959 0.002824485 -6.76187e-5 -0.1321039 0.003873646 -1.33568e-4 -0.1328229 0.001006901 1.38422e-4 -0.1315203 0.003152251 -4.22588e-5 -0.1324084 -8.064e-4 3.90538e-4 -0.1308894 0.002372562 5.64312e-5 -0.1311812 -0.002340137 6.15474e-4 -0.1294562 0.001781225 1.56497e-4 -0.1281922 0.001259684 2.44747e-4 -0.1218572 5.17401e-4 5.5674e-4 -0.1225944 6.03794e-4 5.2043e-4 -0.01069885 -0.002852618 -0.001514196 -0.0100404 0.002773046 -0.001518249 -0.01003748 0.002773761 -0.001517832 -0.01000267 0.002657294 -0.001718342 -0.006584048 -0.006212651 4.68793e-4 -0.008824229 -0.006946027 0.001041352 -0.008935034 -0.00678718 7.29248e-4 -0.008795022 -0.006961882 0.001173973 -0.006684899 -0.006035029 1.82845e-4 -0.009369075 -0.005929589 -3.74145e-5 -0.01199233 4.88772e-4 -0.002275109 -0.009900689 0.002269983 -0.001976132 -0.01238441 0.001652419 -0.00221312 -0.009530723 0.001163661 -0.002125203 -0.00998491 0.00257039 -0.001814424 -0.01247215 0.001979351 -0.002070307 -0.01248985 0.002078294 -0.001977801 -0.01249259 0.00213921 -0.00187242 -0.01737993 9.04224e-4 -0.002758562 -0.01743602 0.001069307 -0.002750515 -0.01713258 1.76265e-4 -0.002794027 -0.01572662 -0.00332278 -0.001710534 -0.01602101 -0.002625405 -0.002008557 -0.01691585 -3.69989e-4 -0.002640902 -0.008784353 -0.006938993 0.001289844 -0.008782625 -0.006938397 0.001289308 -0.008813083 -0.006948947 0.001297831 -0.01752537 0.001416981 -0.00256735 -0.0175333 0.00148189 -0.002482533 -0.01252639 0.002130448 -0.001877307 -0.0174548 0.001124501 -0.002747833 -0.01752161 0.001386523 -0.002607047 -0.0175234 0.001401007 -0.002588152 -0.0124945 0.002138733 -0.001872718 -0.09623551 -3.03549e-4 8.94644e-4 -0.04412949 -0.00132811 -0.001149415 -0.03867334 -0.001943707 -0.001795113 -0.06105434 -3.37088e-4 2.26767e-4 -0.04962778 -7.07814e-4 -4.98748e-4 -0.05527329 -4.48548e-4 -8.83625e-5 -0.05123585 -5.26396e-4 -3.08446e-4 -0.02757334 -0.003402888 -0.002746045 -0.02522969 -0.00358659 -0.002829849 -0.02464205 -0.003529369 -0.002777636 -0.03050011 -0.00317347 -0.002641439 -0.03155136 -0.003091096 -0.002603888 -0.03326356 -0.002800107 -0.002410948 -0.03757143 -0.002067983 -0.001925528 -0.08450812 -3.73499e-4 8.14451e-4 -0.02174514 -0.00324732 -0.002520084 -0.01699668 -0.002785086 -0.002098023 -0.06593555 -2.42976e-4 4.92844e-4 -0.07277083 -2.94198e-4 6.13775e-4 -0.08386486 -3.77336e-4 8.10052e-4 -0.1096815 0.01053231 -7.71753e-4 -0.1097387 0.01087677 -8.28858e-4 -0.1040436 0.01143556 -0.001022458 -0.03183823 9.17881e-4 -0.004855453 -0.02891975 2.31094e-4 -0.004834294 -0.0259397 -7.11204e-5 -0.004535198 -0.03460526 0.001837491 -0.004678845 -0.04009377 0.003505885 -0.004118561 -0.05177742 0.0089733 -0.003558874 -0.05119162 0.006304144 -0.002770543 -0.0576083 0.01009589 -0.003001391 -0.05695003 0.007132649 -0.00215429 -0.06358599 0.01073533 -0.002549171 -0.0628634 0.007595717 -0.001714289 -0.06863701 0.007802009 -0.001433432 -0.04560208 0.005033433 -0.003453671 -0.04611694 0.007343292 -0.004149258 -0.04627585 0.008123457 -0.004321753 -0.04065978 0.006102383 -0.004807233 -0.04638272 0.008583486 -0.004375219 -0.05213338 0.01041114 -0.003928065 -0.05434948 0.01111543 -0.003755748 -0.02630507 0.001122891 -0.004772722 -0.02928227 0.001550078 -0.005170524 -0.03218966 0.002384126 -0.005273222 -0.03497326 0.003464162 -0.00515455 -0.04053831 0.005458116 -0.004705309 -0.02639323 0.00150448 -0.004722595 -0.02936446 0.001977384 -0.005153596 -0.03226333 0.002861499 -0.005288124 -0.03505516 0.003994345 -0.005195558 -0.02938205 0.002132058 -0.005104005 -0.02641791 0.001846611 -0.004498004 -0.02641487 0.001641094 -0.004660785 -0.0248956 0.001592993 -0.004257977 -0.02345001 0.001405894 -0.00400567 -0.02345943 0.001571297 -0.003911614 -0.02342748 0.001286983 -0.0040766 -0.02333956 9.48525e-4 -0.004155755 -0.03507155 0.004186451 -0.005170762 -0.03224337 0.00324285 -0.005107462 -0.03227597 0.00303471 -0.005251646 -0.03033494 0.002499163 -0.005115628 -0.0293802 0.002340137 -0.004965066 -0.04520004 0.008207559 -0.004467189 -0.04071849 0.006500542 -0.00475955 -0.0406953 0.006337285 -0.004812359 -0.03560584 0.004553139 -0.005093097 -0.03506797 0.004343569 -0.005095362 -0.1032912 0.006966233 -2.09129e-4 -0.1090229 0.006562054 -1.13598e-4 -0.1092542 0.007956027 -3.44677e-4 -0.08690679 0.01260727 -0.001724421 -0.08434474 0.01274716 -0.00183767 -0.08597517 0.007561683 -7.18996e-4 -0.07677692 0.01298135 -0.00224626 -0.07441854 0.007816135 -0.001172065 -0.07546734 0.01294666 -0.002328813 -0.09834384 0.01198256 -0.001219093 -0.09752428 0.007172584 -3.49353e-4 -0.09862643 0.01196712 -0.001206636 -0.02298378 -1.33165e-4 -0.004019081 -0.06974405 0.0127952 -0.002689719 -0.06417953 0.01264792 -0.003040611 -0.06402117 0.01262325 -0.003052115 -0.05802249 0.01168805 -0.00348854 -0.01752334 0.001517236 -0.002354323 -0.01752156 0.001523733 -0.00233072 -0.01245152 0.002143263 -0.001625716 -0.009971559 0.002689719 -0.001377224 -0.01234072 0.001984417 -0.001313567 -0.009470403 0.001629471 -4.24946e-4 -0.009870707 0.002512156 -0.001091241 -0.009997546 0.002715826 -0.001502633 -0.01190662 0.001126825 -5.46841e-4 -0.01057678 -0.001950144 9.30183e-4 -0.009283244 -0.00529164 0.001691281 -0.008891165 -0.006455302 0.001629352 -0.008803427 -0.006782233 0.001486599 -0.008785665 -0.006881237 0.001394033 -0.01336407 -0.00803411 0.002458751 -0.01248073 0.002159059 -0.001758337 -0.0134536 -0.007705986 0.002601623 -0.01407712 -0.005981326 0.002468645 -0.01396554 -0.006290018 0.002492487 -0.01375472 -0.00687313 0.002537429 -0.01349818 -0.007582724 0.002592146 -0.01484632 -0.004080176 0.001849651 -0.01514726 -0.003366887 0.001545965 -0.01752573 0.001508772 -0.002385079 -0.01714634 9.40709e-4 -0.001336574 -0.01697981 6.48695e-4 -9.61902e-4 -0.01731884 0.001242995 -0.001724541 -0.01748114 0.00149393 -0.002157151 -0.01744806 0.001469612 -0.002015352 -0.0173797 0.001349687 -0.001861393 -0.01691919 5.19483e-4 -8.71699e-4 -0.01335638 -0.008089125 0.00239259 -0.01335877 -0.008071959 0.002413213 -0.01666355 -2.55378e-5 -4.91219e-4 -0.01580852 -0.001848161 7.8119e-4 -0.0154401 -0.002686262 0.001223504 -0.108441 0.003098905 7.52347e-4 -0.1092541 0.007984399 -1.6395e-4 -0.1217927 0.00650531 -7.58306e-5 -0.10973 0.01083499 -7.52204e-4 -0.1097748 0.01110166 -8.21133e-4 -0.1214742 0.008802294 -4.87837e-4 -0.1284956 0.006648778 -3.06223e-4 -0.1298412 0.006020009 -2.60055e-4 -0.1271665 0.007269322 -3.37836e-4 -0.1243097 0.008124828 -4.47038e-4 -0.1269356 0.007377743 -3.59751e-4 -0.1271505 0.007277309 -3.52377e-4 -0.1321175 0.003866195 -8.55527e-5 -0.1327965 0.002826094 -3.92622e-5 -0.1330102 0.002497911 -3.46587e-5 -0.1300889 -0.005389213 0.001007437 -0.1150057 -0.0069561 0.00211656 -0.1152694 1.57028e-4 0.001071274 -0.1226043 5.96776e-4 7.74491e-4 -0.1237427 -0.007760465 0.001714944 -0.1237864 -0.007738828 0.001656234 -0.1148974 -0.009879767 0.002428293 -0.1149022 -0.009749412 0.002429723 -0.1078971 -1.76863e-4 0.001322209 -0.106774 -0.006952643 0.002424895 -0.1065401 -0.008370101 0.002618849 -0.1061127 -0.01095992 0.002973198 -0.1237286 -0.007652163 0.00171864 -0.1234138 -0.005327284 0.001510858 -0.1236679 -0.007199466 0.001694798 -0.1149224 -0.009205102 0.002388536 -0.1315962 0.00310254 5.09908e-5 -0.127531 -0.004275679 0.001109898 -0.1262113 9.17713e-4 5.68245e-4 -0.1294583 -0.003450036 9.1258e-4 -0.127928 0.001220107 4.63631e-4 -0.131183 -0.00233066 7.14242e-4 -0.1295163 0.001663327 3.54694e-4 -0.132411 -7.98636e-4 4.70449e-4 -0.1290518 -0.005832254 0.001121401 -0.1300889 -0.005387425 0.001011312 -0.1300824 -0.005366504 0.001016438 -0.1317074 -0.003592133 7.92748e-4 -0.1299397 -0.004925072 0.001014471 -0.1300552 -0.005281448 0.001022279 -0.1279458 -0.005916297 0.001237452 -0.1329172 -0.001782476 5.23021e-4 -0.1311475 0.005318522 -2.04695e-4 -0.1303788 0.005768775 -2.41608e-4 -0.127323 0.006900131 -2.61186e-4 -0.1299774 0.005843579 -2.1668e-4 -0.1291904 0.005423545 -1.0857e-4 -0.1303656 0.005188584 -1.37799e-4 -0.1314381 0.004904747 -1.55519e-4 -0.1214557 0.008929967 -5.32167e-4 -0.1214548 0.00893563 -5.3736e-4 -0.1214544 0.00893712 -5.41952e-4 -0.1156352 0.01013928 -7.30673e-4 -0.1098158 0.01133984 -9.13249e-4 -0.1098159 0.01134026 -9.14303e-4 -0.1098162 0.01134145 -9.1744e-4 -0.1098162 0.01134139 -9.19384e-4 -0.1098157 0.01133954 -9.12974e-4 -0.109815 0.01133519 -9.08841e-4 -0.1098141 0.01133036 -9.04205e-4 -0.1214594 0.008905649 -5.19941e-4 -0.1098042 0.01127415 -8.76882e-4 -0.1098111 0.01131379 -8.96145e-4 -0.1298838 0.006000161 -2.43876e-4 -0.1271965 0.007199347 -3.17707e-4 -0.1094525 0.00917679 -3.87582e-4 -0.1096814 0.01054573 -6.84778e-4 -0.1215363 0.008359432 -3.91598e-4 -0.1097112 0.01072341 -7.23355e-4 -0.1248897 0.006098926 -7.54767e-5 -0.1278486 0.005648732 -8.72775e-5 -0.1308016 0.002315998 2.14288e-4 -0.1328251 0.001011908 1.93665e-4 -0.1081653 0.001439154 0.001043975 -0.1314374 0.004903137 -1.83875e-4 -0.1214547 0.008934915 -5.41202e-4 -0.1278468 0.005639255 -1.86046e-4 -0.1214736 0.008798718 -5.17235e-4 -0.1215348 0.008351683 -4.54633e-4 -0.1273221 0.006895899 -3.06772e-4 -0.109816 0.01134043 -9.1838e-4 -0.1098157 0.01133882 -9.17682e-4 -0.1098156 0.01133799 -9.173e-4 -0.1098143 0.01133036 -9.15677e-4 -0.1098117 0.01131474 -9.12348e-4 -0.1214591 0.00890398 -5.34046e-4 -0.1098085 0.01129543 -9.0824e-4 -0.1097977 0.01123094 -8.94497e-4 -0.1217898 0.006488084 -2.12388e-4 -0.1248869 0.006085634 -1.97796e-4 -0.1268981 0.007391154 -3.60133e-4 -0.1268113 0.007424414 -3.62866e-4 -0.1264634 0.007554113 -3.73878e-4 -0.1257619 0.007798373 -3.96373e-4 -0.1269846 0.007357597 -3.57408e-4 -0.126963 0.007366001 -3.58088e-4 -0.1243094 0.008123695 -4.46968e-4 -0.1214556 0.008929133 -5.39067e-4 -0.1271591 0.007285416 -3.50925e-4 -0.1271663 0.007268428 -3.48036e-4 -0.1296899 0.006132721 -2.67826e-4 -0.1297724 0.006090164 -2.64771e-4 -0.1298401 0.006018161 -2.59803e-4 -0.1298341 0.006058096 -2.62462e-4 -0.1298136 0.006068825 -2.63233e-4 -0.1295245 0.006217062 -2.73863e-4 -0.1291922 0.006382942 -2.85659e-4 -0.1299763 0.005841314 -2.42175e-4 -0.1271961 0.00719738 -3.38965e-4 -0.1097898 0.01118403 -8.84502e-4 -0.1291878 0.005415737 -1.88481e-4 -0.1269413 0.007374405 -3.5877e-4 -0.1269522 0.007370233 -3.58429e-4 -0.1285219 0.006702601 -3.08366e-4 -0.1271569 0.007283091 -3.51283e-4 -0.1098151 0.01133507 -9.1668e-4 -0.1303634 0.005183577 -1.93042e-4 -0.1298444 0.006052732 -2.62075e-4 -0.1097842 0.01115036 -8.7841e-4 -0.05850678 -0.01101976 0.003883063 -0.05922901 -0.007878422 0.003110408 -0.07113158 -0.008171021 0.003040254 -0.02050727 -0.004389166 0.001948058 -0.02293896 -0.004521906 0.001990318 -0.02476084 -0.008209526 0.003911972 -0.02606791 -0.004267156 0.001982688 -0.03151756 -0.003823399 0.001969337 -0.03034502 -0.008390069 0.004205107 -0.03167986 -0.003798544 0.001963078 -0.03612577 -0.008373975 0.004178285 -0.03752607 -0.002903699 0.001735866 -0.04435956 -0.001857697 0.001470386 -0.04769283 -0.007968127 0.003481805 -0.04928094 -0.001175343 0.001248478 -0.05347597 -0.007827222 0.003210663 -0.05516004 -3.6021e-4 9.83398e-4 -0.05539411 -3.27752e-4 9.72843e-4 -0.04710984 -0.01063972 0.00422132 -0.03568542 -0.01032513 0.00473833 -0.02990061 -0.01054453 0.004695355 -0.02988475 -0.01073819 0.004665791 -0.0243026 -0.01010322 0.004165589 -0.01881307 -0.009110033 0.003466546 -0.02440154 -0.009521782 0.004238188 -0.02432006 -0.009948313 0.004217028 -0.01879066 -0.009228348 0.003395318 -0.02998107 -0.01001286 0.004663765 -0.03556555 -0.01097315 0.004823386 -0.03553074 -0.01121079 0.004819571 -0.1008777 -0.007491469 0.002632617 -0.09494322 -0.007854104 0.002746939 -0.08304405 -0.008169531 0.002887904 -0.01925259 -0.007700443 0.003415107 -0.01890021 -0.008773744 0.003546833 -0.1009799 -2.5452e-4 0.001399219 -0.09622991 -2.23444e-4 0.001362562 -0.08450847 -1.46759e-4 0.001272141 -0.0727753 -6.99954e-5 0.001181602 -0.06774395 -3.70787e-5 0.001142799 -0.0610463 -1.94718e-4 0.001050591 0.08799529 -0.004192054 6.64969e-4 0.01241469 0.00205177 0.001057565 0.09380561 -0.004077136 7.0878e-4 0.01230382 0.002047419 0.001060724 0.05972647 -0.00470674 1.43614e-4 0.064713 -0.004618167 2.50624e-4 0.07635879 -0.00441116 5.00542e-4 0.08186793 -0.00431323 6.18767e-4 0.01790672 0.001579761 8.26196e-4 0.02051836 0.00135529 7.16144e-4 0.02349424 7.13727e-4 6.2306e-4 0.02934223 -5.47026e-4 4.40139e-4 0.0408411 -0.003026008 8.04639e-5 0.04115468 -0.003074645 7.17281e-5 0.04712766 -0.00400108 -9.46657e-5 0.04952126 -0.004372298 -1.61346e-4 0.05306774 -0.004488527 -5.53671e-5 0.05888688 -0.004679262 1.18524e-4 0.01420485 -0.001952648 -0.002488613 0.0838629 -0.0137189 -0.001563966 0.08957314 -0.01332777 -0.001338303 0.08957368 -0.01335728 -0.001315236 0.09527814 -0.01291978 -0.001083791 0.09526115 -0.0128231 -0.001044094 0.08955109 -0.01323968 -0.001251339 0.09519028 -0.01240789 -9.2445e-4 0.05352795 -0.01388257 -0.003317117 0.05377668 -0.01389509 -0.003300607 0.0522632 -0.01364916 -0.003393352 0.05529218 -0.01397103 -0.003200054 0.04333198 -0.01167613 -0.003912985 0.04478287 -0.01216286 -0.003838121 0.04550957 -0.01238852 -0.003758788 0.04548138 -0.01239722 -0.003802061 0.04625821 -0.01254063 -0.003755211 0.04919797 -0.01309949 -0.003454864 0.05076372 -0.01337236 -0.003483712 0.05526483 -0.01387554 -0.003140389 0.05151247 -0.01351058 -0.003438591 0.05188751 -0.01357978 -0.003416001 0.04776012 -0.01281791 -0.003664731 0.04926335 -0.01309537 -0.003574132 0.0432763 -0.01172918 -0.003836989 0.03752791 -0.009728848 -0.004212498 0.03747636 -0.009711682 -0.004093825 0.03637355 -0.009341537 -0.004272043 0.03174442 -0.007498264 -0.004311859 0.03179633 -0.007568299 -0.004457533 0.02661526 -0.005561053 -0.00466746 0.02324575 -0.004250586 -0.00462383 0.02608478 -0.005354762 -0.004660606 0.02593082 -0.005166172 -0.004270672 0.03167527 -0.007373094 -0.004119217 0.03742414 -0.009586215 -0.003942072 0.04323863 -0.01161295 -0.003726959 0.02004206 -0.002771914 -0.003537297 0.01713454 -0.002245664 -0.003089487 0.01746511 -0.002807736 -0.003972351 0.01451581 -0.002484798 -0.003393948 0.01439183 -0.002257227 -0.002980113 0.01574701 -0.00251621 -0.003680408 0.020406 -0.003306686 -0.004472136 0.02113801 -0.003430902 -0.004596531 0.02288001 -0.003667831 -0.003740489 0.03017842 -0.003087162 -8.57812e-4 0.04265552 -0.009365439 -0.002518534 0.04196399 -0.006517827 -0.001287877 0.04865282 -0.0108124 -0.002472579 0.01367068 -9.31912e-4 -0.00132364 0.01656955 -0.001188039 -0.001810193 0.0194385 -0.001654565 -0.002186954 0.02224576 -0.002447724 -0.002367258 0.02508431 -0.003442108 -0.002376854 0.03092426 -0.005394756 -0.002383053 0.09489178 -0.01063388 -5.19804e-4 0.07767677 -0.01153492 -0.001079261 0.06619131 -0.01189213 -0.00158596 0.06044232 -0.01187402 -0.001891255 0.08915591 -0.01096463 -6.8147e-4 0.09528261 -0.01293987 -0.001104176 0.09528309 -0.01293671 -0.001112639 0.09570837 -0.01290762 -0.001095831 0.09528237 -0.01294225 -0.001098811 0.0895738 -0.01336306 -0.001310765 0.07814878 -0.01395231 -0.001859724 0.0810061 -0.01384371 -0.001708209 0.07814908 -0.01403623 -0.001815736 0.08333015 -0.01375538 -0.001585006 0.08386266 -0.01372218 -0.001554846 0.08947515 -0.0128085 -0.001121282 0.07803833 -0.013466 -0.001590311 0.08956933 -0.01333987 -0.001294434 0.07812386 -0.01391631 -0.001741945 0.06659609 -0.01385432 -0.002178668 0.07814913 -0.01404422 -0.001811563 0.07814419 -0.01402044 -0.001792371 0.06671404 -0.01441472 -0.002411603 0.06669151 -0.01431018 -0.002353727 0.06098157 -0.01417064 -0.002763271 0.0638597 -0.01445162 -0.002623558 0.06493985 -0.01445436 -0.002560019 0.06671953 -0.01443004 -0.002438426 0.06671977 -0.01438671 -0.002465665 0.06671947 -0.01443821 -0.002433538 0.06100851 -0.01425743 -0.002820849 0.06086874 -0.01381957 -0.002524197 0.05514776 -0.01350164 -0.002900481 0.04908949 -0.01266157 -0.003226995 0.04311305 -0.01116412 -0.003427624 0.03726989 -0.00913763 -0.003553748 0.0257073 -0.004789233 -0.003739118 0.03148752 -0.0069471 -0.00364536 0.05469924 -0.01160496 -0.00223118 0.08955407 -0.01324421 -0.001294434 0.07812672 -0.01391357 -0.001796722 0.08386176 -0.01371467 -0.001558482 0.01455819 -0.002444207 -0.003550529 0.03467786 -0.008692324 -0.00443989 0.03183054 -0.007588922 -0.004583477 0.03184264 -0.007582485 -0.004630506 0.04330468 -0.01177304 -0.003936886 0.04040026 -0.01082658 -0.004117667 0.04039931 -0.01082855 -0.004112303 0.03752708 -0.009786963 -0.004270493 0.04477137 -0.01219135 -0.003863215 0.04477185 -0.01220047 -0.0038594 0.04330319 -0.01175773 -0.003956258 0.04330182 -0.01174283 -0.003959894 0.04476791 -0.01216202 -0.003867447 0.04040187 -0.01081544 -0.004132091 0.04040098 -0.01082372 -0.004122793 0.03753042 -0.009784579 -0.004285931 0.03469222 -0.008579313 -0.004560232 0.0318607 -0.00749439 -0.004741311 0.03186058 -0.007442355 -0.004767894 0.04039436 -0.01072162 -0.004161536 0.04328787 -0.01164597 -0.003962755 0.04329651 -0.01170194 -0.003963708 0.0375207 -0.009579837 -0.004375278 0.04327577 -0.01157468 -0.003957033 0.03752899 -0.009647309 -0.004367113 0.04623645 -0.01249146 -0.003769516 0.02621042 -0.005246996 -0.00508368 0.02340036 -0.004116237 -0.005104362 0.02620238 -0.005289554 -0.005043268 0.02050435 -0.003257572 -0.0048846 0.02613931 -0.005364596 -0.004825532 0.02337187 -0.004169464 -0.004996955 0.0261771 -0.005346536 -0.004945516 0.02619129 -0.005322813 -0.004997193 0.03185778 -0.007535159 -0.004709482 0.0346933 -0.008626043 -0.004537522 0.03753405 -0.00970149 -0.004354 0.0145992 -0.002412259 -0.00381422 0.04918479 -0.01295781 -0.003535985 0.04040199 -0.01080369 -0.004140317 0.03753471 -0.009770035 -0.00431329 0.04040127 -0.01078844 -0.00414735 0.03753572 -0.009757816 -0.004325211 0.04039978 -0.01076972 -0.004153251 0.03753596 -0.009742379 -0.004335999 0.03469121 -0.008660435 -0.004509806 0.034689 -0.008673012 -0.00449413 0.03468602 -0.008682489 -0.004477202 0.03753292 -0.009778916 -0.004300177 0.04330378 -0.01176893 -0.003951549 0.05539196 -0.01375776 -0.003111958 0.05521827 -0.01374751 -0.003116965 0.0455085 -0.01240509 -0.003803789 0.04477292 -0.01220053 -0.003852546 0.04477155 -0.01220589 -0.003854513 0.04330253 -0.01178061 -0.003938674 0.04330354 -0.01177656 -0.003945648 0.03753757 -0.009777069 -0.004243373 0.03752303 -0.009786188 -0.004254043 0.04039686 -0.01083004 -0.004100799 0.04330378 -0.01177322 -0.003948748 0.03185176 -0.007564544 -0.004672527 0.02045881 -0.003254473 -0.004681289 0.01751309 -0.002723991 -0.004212915 0.01754295 -0.002713859 -0.004356205 0.01458483 -0.002442061 -0.003692269 0.0233305 -0.004187524 -0.00486648 0.02049458 -0.003238499 -0.004820466 0.01755446 -0.002679288 -0.004475653 0.0318154 -0.007583975 -0.004531562 0.04184693 -0.01128756 -0.00405097 0.04184758 -0.01130086 -0.004045069 0.0418474 -0.01131057 -0.004038095 0.04184705 -0.01131409 -0.004034221 0.04184645 -0.01131677 -0.004029989 0.09526383 -0.01282978 -0.001082599 0.09527891 -0.01291978 -0.001101851 0.060997 -0.01420575 -0.002808272 0.06669425 -0.01429855 -0.002419114 -0.007458627 -0.002181291 -0.004976391 -0.004428684 -0.003930628 -0.004976391 -0.001398682 -0.002181291 -0.004976391 -0.001398682 0.001317322 -0.004976391 -0.004428684 0.003066718 -0.004976391 -0.007458627 0.001317322 -0.004976391 -0.003129601 3.18027e-4 0.005023539 -0.003678679 8.67064e-4 0.005023539 -0.004428684 0.001067996 0.005023539 -0.005178689 8.67064e-4 0.005023539 -0.005727708 3.18027e-4 0.005023539 -0.005928635 -4.31974e-4 0.005023539 -0.005727708 -0.00118196 0.005023539 -0.005178689 -0.001730978 0.005023539 -0.004428684 -0.001931965 0.005023539 -0.003678679 -0.001730978 0.005023539 -0.003129601 -0.00118196 0.005023539 -0.002928674 -4.31974e-4 0.005023539 -0.005178689 -0.001730978 -0.002355098 -0.004428684 -0.003815174 -0.002355098 -0.005727708 -0.00118196 -0.002355098 -0.00735861 -0.002123534 -0.002355098 -0.001498699 0.001259624 -0.002355098 -0.001498699 -0.002123534 -0.002355098 -0.002928674 -4.31974e-4 -0.002355098 -0.00735861 0.001259624 -0.002355098 -0.005727708 3.18027e-4 -0.002355098 -0.005928635 -4.31974e-4 -0.002355098 -0.003129601 3.18027e-4 -0.002355098 -0.003678679 8.67064e-4 -0.002355098 -0.004428684 0.002951204 -0.002355098 -0.004428684 0.001067996 -0.002355098 -0.005178689 8.67064e-4 -0.002355098 -0.004428684 -0.001931965 -0.002355098 -0.003678679 -0.001730978 -0.002355098 -0.003129601 -0.00118196 -0.002355098 -0.001498699 -0.002123534 -0.004876375 -0.001498699 0.001259624 -0.004876375 -0.004428684 0.002951204 -0.004876375 -0.00735861 0.001259624 -0.004876375 -0.00735861 -0.002123534 -0.004876375 -0.004428684 -0.003815174 -0.004876375 -0.001491069 0.001264035 -0.004914641 -0.001483857 -0.002132117 -0.004925429 -0.001491069 -0.002127945 -0.004914641 -0.001485288 0.001267373 -0.004926383 -0.001466989 0.001277923 -0.004944682 -0.001469433 -0.002140462 -0.004947125 -0.00144869 0.001288473 -0.00496298 -0.001447737 -0.002152979 -0.00496155 -0.001436293 0.001295626 -0.004966318 -0.001436948 -0.002159178 -0.004968762 -0.004428684 0.002960026 -0.004914641 -0.004428684 0.00298506 -0.004947125 -0.004428684 0.003022491 -0.004968762 -0.00736624 0.001264035 -0.004914641 -0.007387936 0.001276552 -0.004947125 -0.007420361 0.001295268 -0.004968762 -0.00736624 -0.002127945 -0.004914641 -0.007387936 -0.002140462 -0.004947125 -0.007420361 -0.002159178 -0.004968762 -0.004428684 -0.003823995 -0.004914641 -0.004428684 -0.003849029 -0.004947125 -0.004428684 -0.003886461 -0.004968762 -0.02341556 0.001580238 -0.003550529 -0.04353523 0.007828354 -0.00443989 -0.04068791 0.006725013 -0.004583477 -0.04070001 0.006718516 -0.004630506 -0.05216205 0.01090908 -0.003936886 -0.05218935 0.01081216 -0.003912985 -0.04638528 0.008864879 -0.004212498 -0.04925763 0.009962618 -0.004117667 -0.04925668 0.009964644 -0.004112303 -0.04638445 0.008923053 -0.004270493 -0.05362874 0.01132738 -0.003863215 -0.05511558 0.01167672 -0.003755211 -0.05362921 0.0113365 -0.0038594 -0.05216056 0.01089376 -0.003956258 -0.05215919 0.01087886 -0.003959894 -0.05362528 0.01129806 -0.003867447 -0.04925924 0.009951472 -0.004132091 -0.04925835 0.009959757 -0.004122793 -0.04638779 0.008920609 -0.004285931 -0.02937394 0.002350389 -0.004933655 -0.05214524 0.010782 -0.003962755 -0.05213314 0.01071071 -0.003957033 -0.05804216 0.01209384 -0.003535985 -0.04637807 0.008715867 -0.004375278 -0.04071795 0.006578445 -0.004767894 -0.03225773 0.003252327 -0.005104362 -0.03506779 0.004383087 -0.00508368 -0.03505975 0.004425644 -0.005043268 -0.03499668 0.004500627 -0.004825532 -0.03222918 0.003305494 -0.004996955 -0.03503447 0.004482567 -0.004945516 -0.03504866 0.004458844 -0.004997193 -0.04071515 0.00667119 -0.004709482 -0.04071807 0.00663042 -0.004741311 -0.04355067 0.007762074 -0.004537522 -0.04354959 0.007715404 -0.004560232 -0.04639142 0.008837521 -0.004354 -0.04638636 0.00878334 -0.004367113 -0.04925173 0.009857654 -0.004161536 -0.02345657 0.00154829 -0.00381422 -0.05509382 0.01162755 -0.003769516 -0.05812072 0.0122314 -0.003574132 -0.05661749 0.01195394 -0.003664731 -0.04925936 0.00993973 -0.004140317 -0.04639208 0.008906066 -0.00431329 -0.04925864 0.00992453 -0.00414735 -0.04639309 0.008893907 -0.004325211 -0.04925715 0.009905755 -0.004153251 -0.04639333 0.008878409 -0.004335999 -0.04354858 0.007796466 -0.004509806 -0.04354637 0.007809042 -0.00449413 -0.04354339 0.007818579 -0.004477202 -0.04639029 0.008914947 -0.004300177 -0.05216115 0.01090502 -0.003951549 -0.06424933 0.01289379 -0.003111958 -0.06414955 0.01310706 -0.003200054 -0.06263405 0.01303112 -0.003300607 -0.06074488 0.01271581 -0.003416001 -0.06112056 0.01278519 -0.003393352 -0.06238532 0.01301866 -0.003317117 -0.06036984 0.01264661 -0.003438591 -0.05962109 0.01250839 -0.003483712 -0.05436587 0.01154112 -0.003803789 -0.05363029 0.01133662 -0.003852546 -0.05362892 0.01134192 -0.003854513 -0.0521599 0.0109167 -0.003938674 -0.05216091 0.01091259 -0.003945648 -0.04639494 0.008913159 -0.004243373 -0.0463804 0.008922219 -0.004254043 -0.04925423 0.009966075 -0.004100799 -0.05364024 0.01129895 -0.003838121 -0.05433875 0.01153331 -0.003802061 -0.05216115 0.01090925 -0.003948748 -0.04070913 0.006700575 -0.004672527 -0.02931618 0.002390563 -0.004681289 -0.02637046 0.001860022 -0.004212915 -0.02640026 0.001849889 -0.004356205 -0.0234422 0.001578152 -0.003692269 -0.03218787 0.003323554 -0.00486648 -0.02935194 0.002374589 -0.004820466 -0.02641373 0.001849234 -0.004461586 -0.03210312 0.003386676 -0.00462383 -0.03494215 0.004490792 -0.004660606 -0.03547263 0.004697144 -0.00466746 -0.04067277 0.006720006 -0.004531562 -0.02632248 0.001943767 -0.003972351 -0.02926337 0.002442717 -0.004472136 -0.02999538 0.002566933 -0.004596531 -0.05215388 0.01083797 -0.003963708 -0.0507043 0.01042366 -0.00405097 -0.05070495 0.01043689 -0.004045069 -0.05070477 0.0104466 -0.004038095 -0.05070441 0.01045018 -0.004034221 -0.05070382 0.0104528 -0.004029989 -0.04523092 0.008477568 -0.004272043 -0.0406537 0.00670433 -0.004457533 -0.1041212 0.01196581 -0.001082599 -0.1041363 0.01205587 -0.001101851 -0.1041405 0.0120728 -0.001112639 -0.1045657 0.01204365 -0.001095831 -0.08698409 0.01304966 -0.001796722 -0.09841144 0.01238024 -0.001294434 -0.09271913 0.01285076 -0.001558482 -0.09843051 0.01246386 -0.001338303 -0.09272027 0.01285493 -0.001563966 -0.06986594 0.01339346 -0.002820849 -0.06985527 0.01334124 -0.002809405 -0.07379722 0.01359045 -0.002560019 -0.07555162 0.01343458 -0.002419114 -0.07557713 0.0135228 -0.002465665 -0.08700615 0.01308834 -0.001859724 -0.08986347 0.01297974 -0.001708209 -0.09218752 0.01289141 -0.001585006 -0.02337318 0.001620829 -0.003393948 -0.02460438 0.0016523 -0.003680408 -0.06407564 0.01288354 -0.003116965 -0.02306222 0.001088738 -0.002488613 -0.06982672 0.01340663 -0.002709805 -0.06411123 0.01307636 -0.003094375 -0.09840846 0.01237571 -0.001251339 -0.09833258 0.01194459 -0.001121282 -0.0868957 0.01260203 -0.001590311 -0.1037492 0.009769976 -5.19804e-4 -0.1026629 0.003212034 7.14067e-4 -0.06414264 0.01319795 -0.003180384 -0.06414341 0.01318794 -0.003182411 -0.05436694 0.01152455 -0.003758788 -0.05213367 0.01086527 -0.003836989 -0.04633373 0.008847713 -0.004093825 -0.04060178 0.006634294 -0.004311859 -0.05805534 0.01223558 -0.003454864 -0.052096 0.01074904 -0.003726959 -0.04628151 0.008722245 -0.003942072 -0.04053264 0.006509184 -0.004119217 -0.03478819 0.004302203 -0.004270672 -0.02889943 0.001907944 -0.003537297 -0.02599191 0.001381754 -0.003089487 -0.0232492 0.001393318 -0.002980113 -0.03173738 0.002803862 -0.003740489 -0.06355661 0.01074099 -0.00223118 -0.0619294 0.003592252 -2.48128e-5 -0.05751019 0.009948432 -0.002472579 -0.0562067 0.003270089 -1.46416e-4 -0.0559709 0.003225028 -1.363e-4 -0.05082136 0.005653917 -0.001287877 -0.05151289 0.008501529 -0.002518534 -0.03903579 0.002223253 -8.57812e-4 -0.03978163 0.004530847 -0.002383053 -0.03394162 0.002578139 -0.002376854 -0.02116161 -0.002828001 0.001018524 -0.02252805 6.79633e-5 -0.00132364 -0.02318525 -0.002878129 9.46037e-4 -0.02542686 3.24144e-4 -0.001810193 -0.02675259 -0.002417981 8.55459e-4 -0.02829587 7.90655e-4 -0.002186954 -0.02951282 -0.002061963 7.85374e-4 -0.03110313 0.001583814 -0.002367258 -0.03137189 -0.001822173 7.3817e-4 -0.03236109 -0.001608908 7.08362e-4 -0.0500375 0.002091705 1.18265e-4 -0.04553979 0.001232624 3.11233e-4 -0.03820937 -3.47913e-4 5.32129e-4 -0.09801328 0.01010066 -6.8147e-4 -0.10414 0.0120759 -0.001104176 -0.1041398 0.01207834 -0.001098811 -0.09843105 0.01249337 -0.001315236 -0.09843116 0.01249909 -0.001310765 -0.08700644 0.01317232 -0.001815736 -0.09272003 0.01285821 -0.001554846 -0.1041355 0.01205587 -0.001083791 -0.1041185 0.01195919 -0.001044094 -0.1040477 0.01154398 -9.2445e-4 -0.09842669 0.0124759 -0.001294434 -0.08698123 0.0130524 -0.001741945 -0.07545346 0.01299035 -0.002178668 -0.0870065 0.01318031 -0.001811563 -0.07557684 0.01357424 -0.002433538 -0.0755769 0.01356607 -0.002438426 -0.07271707 0.01358771 -0.002623558 -0.07557141 0.01355075 -0.002411603 -0.07554888 0.01344621 -0.002353727 -0.08700156 0.01315647 -0.001792371 -0.0697261 0.0129556 -0.002524197 -0.06400513 0.01263767 -0.002900481 -0.05794686 0.0117976 -0.003226995 -0.05197042 0.01030015 -0.003427624 -0.04612725 0.008273661 -0.003553748 -0.03456467 0.003925263 -0.003739118 -0.04034489 0.00608319 -0.00364536 -0.09685248 0.00332576 6.75573e-4 -0.09258913 0.003409206 6.47329e-4 -0.08653414 0.01067095 -0.001079261 -0.08521628 0.003527939 4.84888e-4 -0.07504868 0.01102817 -0.00158596 -0.07357031 0.003715395 2.28303e-4 -0.06929969 0.01101011 -0.001891255 -0.0677433 0.003809213 9.99211e-5 -0.0662198 0.00383377 6.63563e-5 0.02175766 0.009653091 0.003143489 0.02767872 0.009785592 0.003249168 0.02770167 0.008710205 0.002262651 0.02178966 0.008705019 0.001870512 0.0158624 0.008632242 0.001778125 0.01582223 0.009415924 0.003316044 0.02766585 0.01072502 0.004324018 0.06323337 0.01063799 0.004159033 0.07512128 0.01076668 0.0039016 0.09597873 0.00830233 0.002690672 0.08711928 0.005122363 0.002584993 0.09306287 0.005278944 0.002356052 0.006976008 0.007528543 0.001625895 0.009964764 0.007299542 7.65139e-4 0.01004248 0.004747092 -0.001087248 0.01600801 0.005058586 -0.001420259 0.02193152 0.004952251 -0.001054048 0.02783125 0.004784524 -2.36966e-4 0.04555183 0.004821479 0.002133965 0.03963595 0.004772841 0.001417458 0.05148249 0.004859507 0.002536118 0.06337106 0.004897952 0.002488791 0.07524734 0.004979074 0.002551019 0.0960384 0.005385339 0.002142131 0.09299731 0.008172452 0.003057718 0.08700448 0.0109595 0.003627479 0.09295153 0.01113373 0.003294885 0.05134803 0.01049506 0.00436604 0.0454216 0.01038151 0.004083633 0.03950572 0.01019239 0.003722786 0.03359293 0.009974062 0.003442585 0.01000714 0.006093621 -2.78842e-4 0.01595789 0.006415128 -5.68075e-4 0.08704674 0.008009731 0.003443717 0.07516491 0.00790137 0.003577589 0.06327921 0.007848322 0.003668665 0.05138707 0.007814168 0.003823518 0.0454601 0.007764577 0.003362774 0.03954631 0.00766474 0.00267601 0.02773487 0.007508754 0.001359164 0.02182978 0.007592439 7.55129e-4 0.01590853 0.007618963 4.90575e-4 0.01588487 0.008151888 0.001104354 0.009943366 0.007809758 0.001403272 0.009923398 0.008234739 0.002134621 + + + + + + + + + + 0.002930998 -0.8193059 -0.5733491 0.1347938 -0.7482091 -0.6496259 0.1362775 -0.7477027 -0.6498993 0.02064645 -0.1404165 -0.9898772 -0.1380806 -0.4089931 -0.9020302 0.093414 -0.3886086 -0.9166554 0.1144 -0.4098325 -0.9049586 0.1200519 -0.4207988 -0.8991752 0.1393967 -0.5198535 -0.8428054 0.001666009 -0.3586892 -0.9334556 0.07540887 -0.4885674 -0.8692615 0.0934149 -0.3886068 -0.9166561 0.09341412 -0.3886086 -0.9166554 -0.1063424 -0.3862708 -0.9162348 -0.1063433 -0.3862707 -0.9162347 -0.0608012 -0.5777241 -0.8139645 0.001663684 -0.358694 -0.9334537 0.001665294 -0.3586893 -0.9334556 -0.1335444 -0.4090884 -0.9026697 -0.1390736 -0.4386962 -0.8878086 -0.1390731 -0.4386954 -0.887809 -0.1380809 -0.4089934 -0.9020301 -0.1185181 -0.3517539 -0.9285594 -0.1224438 -0.3365691 -0.9336642 -0.07853686 -0.356894 -0.9308376 -0.07847619 -0.3568941 -0.9308426 -0.09055256 -0.3274756 -0.9405105 -0.1224476 -0.3365693 -0.9336635 -0.1224458 -0.3365691 -0.9336639 -0.04324644 -0.3570898 -0.9330684 -0.01482242 -0.2659674 -0.963868 -0.07847636 -0.3568935 -0.9308429 -0.007941544 -0.383168 -0.9236446 -0.007943511 -0.383168 -0.9236446 -0.007941603 -0.3831683 -0.9236445 -0.00257951 -0.3982111 -0.9172902 -0.008587241 -0.346158 -0.938137 -0.01311403 -0.3600366 -0.932846 -0.01311963 -0.3600367 -0.9328458 -0.006321072 -0.3741589 -0.927343 -0.001488804 -0.274224 -0.9616647 0.05875802 -0.1663753 -0.9843103 0.04456609 0.05798506 -0.9973222 0.04458129 0.0581122 -0.9973142 0.02859598 -0.07001292 -0.9971361 0.02860909 -0.06991285 -0.9971428 0.02167105 -0.1190871 -0.9926473 0.01660805 -0.1462983 -0.9891011 0.01214116 -0.159762 -0.9870809 0.006371378 -0.1690669 -0.985584 0.02768421 -0.1402659 -0.9897268 0.05720156 -0.1605902 -0.9853623 0.05875802 -0.1663748 -0.9843105 0.02554732 0.08857947 -0.9957414 0.05365777 0.1368967 -0.989131 0.05365973 0.1368993 -0.9891306 0.02234375 -0.0104196 -0.999696 0.0212543 -0.0155602 -0.999653 0.003979504 -0.1211988 -0.9926203 0.02929884 -0.2160004 -0.9759536 0.02929896 -0.2159993 -0.9759538 0.02929884 -0.2159996 -0.9759538 0.02929806 -0.2160004 -0.9759536 0.04215824 -0.4727578 -0.8801834 0.04216116 -0.4727576 -0.8801832 0.03447824 -0.4624536 -0.8859729 0.0415337 -0.4658879 -0.8838685 0.05065709 -0.5661156 -0.8227678 0.05065828 -0.566084 -0.8227894 0.05065804 -0.5660842 -0.8227896 0.04381829 -0.7872376 -0.615091 0.01321721 -0.8802238 -0.4743747 0.06117892 -0.8782937 -0.4741912 0.1917471 -0.8682577 0.4575607 0.1917474 -0.8682577 0.4575604 0.02129155 -0.8871134 0.4610602 0.07511478 -0.8758451 -0.4767106 0.07510751 -0.8758475 -0.4767075 0.1070337 -0.9451921 -0.3084731 0.1405386 -0.905647 -0.4000656 0.09798365 -0.5361934 -0.8383888 0.05365967 0.1368993 -0.9891305 0.04014283 0.2130172 -0.9762234 0.05021518 -0.09087765 -0.9945952 0.09278804 -0.814356 -0.5729001 0.07881414 -0.8636125 -0.4979576 0.143971 -0.8564968 -0.4956669 0.1196416 -0.8900793 -0.4398235 0.1318392 -0.892216 -0.4319362 0.1343455 -0.8918953 -0.4318265 0.06746488 -0.7689008 -0.6357989 0.06796765 -0.7556658 -0.6514213 0.05385267 -0.7675901 -0.6386746 0.05649101 -0.7674614 -0.6386015 0.05210798 -0.5784211 -0.8140725 0.05186063 -0.5792958 -0.813466 0.1070771 -0.9451875 -0.3084722 0.1070334 -0.9451898 -0.3084803 0.08743506 -0.9229892 -0.3747615 0.4116932 -0.8124323 -0.4128711 0.005623459 -0.8962224 -0.4435694 0.05227929 -0.8066158 -0.5887594 -0.03567808 -0.8082683 -0.5877325 0.005753755 -0.6859155 -0.7276584 0.003985166 -0.6859422 -0.7276451 2.80004e-4 -0.6143394 -0.7890418 0.03333216 -0.4624762 -0.8860049 0.03779047 -0.5797353 -0.8139281 0.04215955 -0.4727544 -0.8801853 0.1457929 -0.5172306 -0.8433368 0.1211898 -0.6475639 -0.7523126 0.07601976 -0.651405 -0.7549123 0.07500773 -0.6544288 -0.752394 -0.03575938 -0.6584225 -0.7517986 0.1393969 -0.5198575 -0.8428028 0.1448528 -0.5028578 -0.8521454 0.07579237 -0.5081032 -0.8579549 0.07368367 -0.5155924 -0.8536599 -0.06211578 -0.5195641 -0.8521707 -0.07314079 -0.5565754 -0.8275712 -0.1268377 -0.5549756 -0.8221401 -0.09098607 -0.493519 -0.8649628 -0.1106387 -0.4930524 -0.862936 -0.07999944 -0.3623791 -0.9285911 -0.08907377 -0.3623341 -0.9277822 -0.06852281 -0.32187 -0.944301 -0.04407453 -0.3216796 -0.9458222 0.07573765 0.3384172 -0.9379432 0.07573741 0.3384172 -0.9379433 0.09642279 -0.08984118 -0.9912775 0.1157487 -0.1011633 -0.9881134 0.117985 -0.1815214 -0.9762836 0.05049103 -0.1839134 -0.9816448 0.03271722 -0.1707836 -0.9847652 0.03271722 -0.1707837 -0.9847652 0.06852489 -0.1398158 -0.9878035 0.07074034 -0.2312019 -0.9703307 0.05731034 -0.2316897 -0.9711002 0.05421417 -0.08237528 -0.9951257 0.01200562 -0.08311694 -0.9964675 0.01068419 -0.01049655 -0.9998878 0.02234387 -0.01041948 -0.999696 -0.001488983 -0.274224 -0.9616647 0.03876423 -0.3726717 -0.9271534 0.03707146 -0.2728291 -0.9613481 -0.001849293 -0.2739081 -0.9617541 -0.003494918 -0.1496415 -0.9887341 -0.009001731 -0.1497237 -0.9886869 0.005581974 -0.2606249 -0.965424 -0.01639908 -0.2609314 -0.965218 -0.01269394 -0.3763298 -0.9263988 0.04153925 -0.4658961 -0.8838638 -0.006325066 -0.3741583 -0.9273433 -0.00627011 -0.3741714 -0.9273384 -0.007644653 -0.2972444 -0.9547709 -0.009029328 -0.2972753 -0.9547491 -0.007993519 -0.3045047 -0.9524773 -0.03546071 -0.3050503 -0.9516758 -0.03454214 -0.3454746 -0.9377923 -0.06472921 -0.4107262 -0.9094582 -0.04962593 -0.4108685 -0.910343 -0.06585258 -0.6029493 -0.7950569 -0.04821962 -0.6032457 -0.7960965 -0.07843965 -0.7091728 -0.7006577 -0.0240603 -0.7101773 -0.7036116 -0.03179228 -0.7585822 -0.6508013 0.08081966 -0.7543355 -0.6514953 0.07525807 -0.7799698 -0.6212757 0.122676 -0.7754953 -0.6193202 0.1347499 -0.7453612 -0.6529006 0.136278 -0.7477064 -0.6498949 -0.08188498 0.4360059 -0.8962107 0.01134103 -0.3977034 -0.9174439 -0.1550419 0.8571161 -0.4912372 -0.03121137 0.259988 -0.9651073 -0.3153449 0.947011 -0.06105619 -0.3154065 0.9470056 -0.06082117 -0.2665501 0.9483711 -0.1718813 -0.2356131 0.8961576 -0.3760159 -0.2877918 0.9316263 -0.2219198 -0.385576 0.8816007 0.2722343 -0.2719348 0.9391146 -0.2100365 -0.2965286 0.9462315 -0.1292928 0.007336318 0.6519877 -0.7581942 -0.1365968 0.7982554 -0.5866256 -0.136514 0.7981566 -0.5867791 -0.0178681 0.5924478 -0.8054108 -0.04231524 0.5966815 -0.8013617 0.01520842 0.4562207 -0.8897367 0.01520723 0.4562234 -0.8897353 -0.03121167 0.2599889 -0.9651071 -0.03121262 0.2599706 -0.965112 -0.01984798 0.4256253 -0.9046818 0.07282292 0.4086159 -0.9097967 0.01520884 0.4562209 -0.8897366 -0.08716368 -0.1330005 -0.9872757 -0.06324237 0.05717039 -0.9963594 -0.0750519 0.05260616 -0.995791 -0.07506787 0.05900609 -0.9954311 -0.01691132 0.2157718 -0.9762974 0.06246823 0.1754374 -0.9825068 0.01336282 0.2165085 -0.9761893 -0.0620985 -0.1454447 -0.9874156 0.08133184 -0.6987314 -0.7107458 0.02203446 -0.5430983 -0.83938 0.008402109 -0.4720768 -0.8815175 -0.03438723 -0.3685696 -0.928964 -0.0343905 -0.3685604 -0.9289674 0.08133786 -0.6987437 -0.7107331 0.09734779 -0.7291582 -0.677386 0.1515976 -0.8417527 -0.5181413 0.151597 -0.8417516 -0.5181435 0.1523463 -0.8428764 -0.5160909 0.2029843 -0.9395073 -0.2759047 0.1489331 -0.8543983 -0.4978175 0.02070575 -0.4693117 -0.8827898 0.08415055 -0.6724432 -0.7353495 0.09901392 -0.7288809 -0.677443 0.1428909 -0.8448433 -0.5155792 0.1436875 -0.8446754 -0.5156331 -0.1192449 -0.08868628 -0.9888961 -0.03836101 -0.4086203 -0.911898 -0.096183 -0.08100807 -0.9920617 -0.0620985 -0.1454446 -0.9874156 -0.07933986 -0.1591623 -0.9840592 -0.05640691 -0.1518622 -0.9867908 -0.04223603 -0.0673148 -0.9968374 -0.09497398 -0.08481752 -0.9918598 -0.07319498 0.4014908 -0.9129335 -0.07051753 0.3667114 -0.9276583 -0.08271932 0.1907197 -0.9781531 -0.1114729 0.2270047 -0.9674929 -0.1114729 0.2270046 -0.9674931 -0.2979332 0.9268823 0.2283092 -0.2979298 0.9268908 0.2282791 -0.3601785 0.9209803 0.1485487 -0.360929 0.9207084 0.1484127 -0.3398241 0.9389677 0.05347335 -0.3601845 0.9209782 0.1485477 -0.2865342 0.9477046 0.1405496 -0.2228173 0.9610065 -0.1637654 -0.3106603 0.9231855 0.2263155 -0.2096549 0.953118 -0.2181989 -0.2096587 0.9531207 -0.218184 -0.08737206 0.7632129 -0.6402126 -0.1383485 0.8619414 -0.4877671 -0.07394069 0.7670777 -0.6372791 -0.07394152 0.7670793 -0.6372769 -0.1707578 0.8088634 -0.5626561 -0.1383299 0.818692 -0.5573224 -0.03611063 0.6558181 -0.7540548 -0.04363834 0.6534717 -0.7556921 -0.1132296 0.7552693 -0.6455597 0.02896791 -0.7923169 -0.6094218 -0.1192457 -0.08868241 -0.9888963 -0.03679209 -0.4801467 -0.8764163 0.002481281 -0.6827244 -0.7306719 0.03264594 -0.7920184 -0.6096237 0.03267592 -0.7921204 -0.6094897 0.05935031 -0.8769749 -0.476857 0.1489851 -0.8543949 -0.497808 0.1494169 -0.8543297 -0.4977903 -0.02314364 0.5628241 -0.8262526 -0.02314341 0.5628235 -0.826253 -0.007807493 0.4299376 -0.9028249 -0.1278879 0.524512 -0.8417433 -0.1278894 0.5245143 -0.8417418 0.008385121 0.1806572 -0.9835103 0.1398875 0.4541235 -0.8798883 0.1739182 0.5185168 -0.8371934 0.1414795 0.5131295 -0.8465706 0.174603 0.5278176 -0.8312174 0.02678883 0.4793654 -0.8772064 0.1097337 0.5672227 -0.8162211 0.1097329 0.5672229 -0.8162211 0.1235387 0.3847657 -0.9147095 0.08046656 0.3758467 -0.9231817 0.1004234 0.3793421 -0.9197906 0.08177417 0.34691 -0.9343267 0.1000729 0.3501778 -0.9313222 0.08265209 0.3278666 -0.9411016 0.01885151 0.2447831 -0.9693946 0.08161962 0.3504091 -0.9330336 0.01671153 0.2806883 -0.9596536 0.1398877 0.4541236 -0.8798882 0.1398877 0.4541235 -0.8798882 0.1670179 0.4344807 -0.8850601 0.1235166 0.3889807 -0.9129281 0.1578817 0.3399119 -0.9271101 0.1004177 0.3788215 -0.9200057 -0.002956449 0.1781327 -0.9840021 0.00533539 0.2022849 -0.9793122 -0.001329898 0.2130485 -0.9770407 0.008491933 0.2153447 -0.9765011 -0.001331329 0.2130481 -0.9770408 -0.001328289 0.2130486 -0.9770407 -0.1300454 0.3427439 -0.9303843 -0.1109544 0.386502 -0.9155902 -0.08612847 0.345418 -0.9344882 -0.1238947 0.436836 -0.8909683 -0.1006526 0.4747965 -0.8743211 -0.1384696 0.4605201 -0.8767824 -0.1044653 0.5103871 -0.8535761 0.02862489 0.5368768 -0.8431748 -0.006338417 0.5182279 -0.855219 0.02791005 0.5143104 -0.8571498 -0.004232048 0.4787075 -0.8779641 -0.00423038 0.478708 -0.877964 0.01671063 0.2806881 -0.9596536 0.01671147 0.2806882 -0.9596536 0.01855677 0.2787141 -0.9601947 0.004083275 0.251932 -0.9677364 0.01896136 0.2314066 -0.9726722 0.006523132 0.2225813 -0.9748923 0.008509099 0.2212771 -0.9751738 0.006509125 0.2209271 -0.9752686 0.006508588 0.2209271 -0.9752686 -0.07874649 0.1255603 -0.9889557 -0.004826486 -0.06105536 0.9981228 -0.2384213 0.1202794 -0.9636846 -0.09650272 0.03696846 -0.994646 -0.09065622 0.05168539 -0.9945401 -0.09978079 -0.1346765 -0.9858529 0.08910596 0.646933 -0.7573227 -0.06058049 0.04639863 -0.9970844 -0.05035334 0.09235501 -0.9944522 -0.1000988 -0.1361954 -0.985612 -0.0205965 0.17596 -0.9841819 -0.02869534 0.1721805 -0.9846475 -0.02869528 0.1721805 -0.9846474 -0.02944123 0.1662256 -0.9856481 -0.05043292 0.1262177 -0.9907197 -0.02244961 0.1158815 -0.9930093 -0.03137624 0.1204101 -0.9922283 -0.0207979 0.1194911 -0.9926174 -0.02702981 0.1220577 -0.992155 -0.09066385 0.05165743 -0.9945409 -0.04710227 0.09922367 -0.9939498 -0.08563095 0.0512849 -0.9950061 -0.08564281 0.0512706 -0.9950058 -0.05157971 0.1162384 -0.9918812 -0.08564186 0.05127054 -0.9950059 -0.04929709 0.1144943 -0.9922 -0.04930424 0.114489 -0.9922004 -0.07874834 0.1255596 -0.9889557 -0.0369383 0.111555 -0.9930715 -0.03883486 0.1097182 -0.9932037 -0.04574662 0.1125479 -0.9925927 -0.07960909 0.09514629 -0.9922749 -0.08313882 0.09629797 -0.9918743 0.4153531 -0.04811167 -0.9083871 0.05610436 0.1116374 -0.992164 -0.09954535 0.09326553 -0.9906525 -0.04158926 0.1311292 -0.9904925 -0.04157066 0.131212 -0.9904823 -0.05031847 0.09226346 -0.9944623 0.05428427 0.5199025 -0.8524991 -0.2170891 -0.631299 -0.7445359 -0.2301363 -0.6302331 -0.7415144 -0.08162313 -0.0680232 -0.9943392 -0.09451729 -0.0736562 -0.9927946 -0.05194759 0.11498 -0.9920087 -0.06848812 0.1171019 -0.9907555 0.08313816 0.5552827 -0.8274958 0.1358654 0.571172 -0.809508 -0.07012271 0.08063095 -0.9942743 -0.04121869 0.1241934 -0.9914016 -0.02178424 0.1343385 -0.990696 -0.03175145 0.1658421 -0.985641 -0.03175175 0.1658406 -0.9856413 -0.04895174 0.1197776 -0.9915931 -0.06700783 0.1241996 -0.9899922 -0.06456983 0.1355606 -0.9886628 -0.04656505 0.1332647 -0.989986 -0.0439291 0.1473905 -0.9881024 -0.0367102 0.1476945 -0.9883514 -0.04015165 0.1313665 -0.9905204 0.09691441 0.02270728 -0.9950337 -0.04216396 0.08665192 -0.9953459 -0.08310943 0.1134715 -0.9900591 -0.02516901 0.09927594 -0.9947416 -0.02516943 0.09927618 -0.9947416 -0.01962751 0.1220481 -0.9923301 -0.03386867 0.1257649 -0.9914818 -0.04121333 0.1281028 -0.9909041 -0.03348684 0.1286828 -0.9911202 -0.05837935 0.1347216 -0.9891623 -0.03114229 0.1465669 -0.9887104 -0.03941094 0.1476373 -0.988256 -0.02121818 0.165521 -0.985978 -0.02548086 0.165354 -0.9859051 -0.02079725 0.1752222 -0.9843093 -0.02944111 0.1662263 -0.985648 -0.03179353 0.1575551 -0.9869983 -0.03742957 0.1573206 -0.986838 -0.04429513 0.1427342 -0.9887694 -0.05583566 0.1442074 -0.987971 -0.06411546 0.1334728 -0.9889764 -0.04130655 0.1278911 -0.9909277 -0.04640722 0.1247837 -0.9910981 -0.02892422 0.1191918 -0.9924498 -0.0323382 0.1175659 -0.9925383 -0.03407323 0.1182765 -0.9923959 -0.03897315 0.1170395 -0.9923623 -0.05498391 0.1251626 -0.9906115 -0.07770645 0.1257209 -0.9890177 -0.07739633 0.1255897 -0.9890586 0.0929262 0.7670387 0.6348358 -0.1811425 0.9601694 -0.2127488 -0.08238518 0.9284213 -0.3622795 -0.04331958 0.6453375 0.7626683 -0.04220271 0.6673646 0.7435345 -0.1020342 0.8055254 0.5837104 0.02613228 -0.1356945 0.990406 0.02451187 -0.01227426 0.9996242 -0.005742132 -0.3455706 0.9383752 -0.005743622 -0.3455812 0.9383713 -0.005733668 -0.3455177 0.9383947 0.04317295 -0.02215117 0.998822 0.1537815 0.8396472 0.5209068 0.02451181 -0.01227426 0.9996241 0.02913022 -0.1630768 0.9861832 0.01343148 0.06391578 0.9978649 0.02310043 -0.08916682 0.9957488 -0.097121 0.411557 0.9061944 -0.02513426 0.4301578 0.9024037 -7.14712e-4 -0.4271517 0.9041797 -0.2372255 0.6389175 0.7317845 -0.2372211 0.6389181 0.7317855 -0.153038 0.8146129 0.5594509 -0.01019352 -0.4278687 0.9037834 -0.00132668 -0.4277306 0.9039053 -0.0105378 -0.4252493 0.9050149 -0.07825225 0.412694 0.9075021 -0.07820856 0.4127159 0.9074959 -0.07140588 0.4099209 0.9093217 -0.177999 0.9816474 0.06844532 -0.1941949 0.9585102 0.208678 -0.2484626 0.9395501 0.2356098 -0.09782248 0.8233599 0.5590255 -0.1578298 0.8234269 0.5450303 -0.1465374 0.9249733 0.3506442 -0.2028601 0.9192464 0.3373928 -0.1289878 -0.0751087 0.9887977 -0.1442085 -0.07823532 0.9864497 -0.05837792 0.6829808 0.7280997 0.02837055 -0.06820243 0.997268 0.03053623 -0.06795769 0.9972208 0.01001882 0.1965218 0.9804483 0.01723015 0.06454545 0.997766 0.009059011 0.1651506 0.9862267 0.002741396 0.1642249 0.9864192 0.01478558 0.005218565 0.999877 -0.02288371 0.4698205 0.8824653 -0.02119159 0.4699324 0.8824479 -0.02517849 0.5124149 0.8583689 -0.02870744 0.5122756 0.8583413 -0.02726423 0.4972734 0.8671654 -0.05027121 0.7148855 0.6974321 -0.04892283 0.7149227 0.6974899 -0.07733064 0.8702386 0.4865231 -0.06738746 0.8703646 0.487775 -0.06390553 0.8393007 0.5398985 -0.06502336 0.8392761 0.5398034 -0.06110972 0.8027551 0.5931692 0.01411306 0.2190861 0.9756036 -0.002100586 0.2159973 0.9763917 -0.01420521 0.3804392 0.9246968 -0.02207559 0.3793386 0.9249947 -0.04285293 0.5853932 0.8096163 -0.06111532 0.777987 0.625301 -0.07141745 0.8674582 0.4923574 -0.03642946 0.5805184 0.8134318 -0.02667224 0.5816755 0.8129836 -0.0434997 0.7886738 0.6132709 -0.05369776 0.5833957 -0.810411 -0.05392456 0.5833768 -0.8104097 -0.07982337 0.970575 0.2271836 -0.05537438 0.7426287 0.6674101 -0.05018818 0.7430328 0.6673706 -0.08938372 0.9777875 -0.189584 -0.08891677 0.9941983 -0.06052696 -0.06808936 0.7589222 -0.6476117 -0.06808674 0.7589228 -0.6476114 -0.06144601 0.6266594 -0.776867 -0.05421441 0.5684257 -0.8209463 -0.6765527 0.390334 -0.6244326 -0.0498467 0.5127075 -0.857115 -0.05049568 0.5207905 -0.8521898 -0.04937005 0.5208907 -0.8521945 -0.07920837 0.931348 0.3554111 -0.07706743 0.9314478 0.35562 -0.07772034 0.9367973 0.3411309 -0.07686066 0.9368277 0.3412423 -0.07773959 0.9437357 0.3214336 -0.08524912 0.9435065 0.3201997 -0.08872079 0.9934094 0.07257086 -0.1010988 0.9869808 0.125092 -0.07238954 0.8055669 0.5880661 -0.08051371 0.9010527 0.4261707 -0.1117327 0.9005425 0.4201653 -0.04863679 0.6830201 0.7287783 -0.04711776 0.6672939 0.7433026 -0.0844447 0.9733535 0.2131953 -0.08181864 0.9476494 0.3086526 -0.1092038 0.9468026 0.3027201 -0.08864825 0.9711753 -0.2212686 -0.088651 0.971175 -0.2212691 -0.01410555 0.3738853 0.9273677 -0.03577214 0.5866429 0.8090553 -0.03423309 0.586713 0.8090711 -0.05507177 0.773952 0.630845 -0.06698125 0.7738467 0.6298213 -0.0861507 0.9782683 0.1885976 -0.1056443 0.9772382 0.1839698 -0.1013739 0.9924254 0.06939148 -0.08918505 0.9807814 -0.1735338 -0.09588658 0.9320427 -0.3494313 -0.09588927 0.9320421 -0.3494319 -0.08757346 0.9729169 -0.2139243 -0.08756941 0.9729208 -0.2139083 -0.08757448 0.97292 -0.2139095 -0.07092863 0.8674806 0.4923886 -0.06428056 0.8026242 0.5930112 -0.05088812 0.6851314 0.7266399 -0.04707771 0.6451186 0.7626308 -0.02468377 0.4195189 0.9074109 -0.03170067 0.4969039 0.8672264 -0.01130068 0.2861839 0.958108 -0.01880997 0.3733872 0.9274849 -0.00991398 0.2746334 0.9614979 -0.00362426 0.275423 0.9613163 -0.008048534 0.3258091 0.9454014 -0.004385471 0.3261633 0.9453033 -0.005745768 0.3416442 0.9398118 -0.01332694 0.3410573 0.9399481 -4.96742e-4 0.1408681 0.9900282 -0.05564159 0.6516059 0.7565142 -0.09131896 0.6513357 0.7532746 -0.102756 0.9155212 0.3889244 -0.1503593 0.9144549 0.3757184 -0.1333429 0.9843962 0.1148207 -0.1312626 0.9880294 0.08104306 -0.1256118 0.9918667 0.02054548 -0.09588837 0.9320414 -0.3494344 -0.08819723 0.9726437 -0.2149081 -0.09021162 0.9820153 -0.1658551 -0.089383 0.9777836 -0.1896048 -0.08938431 0.9777834 -0.1896049 0.1030236 0.4226216 0.9004316 0.10318 0.4238958 0.8998146 0.1456905 0.8357504 0.5294295 0.09909874 0.8867641 0.4514739 0.02598744 0.1100933 0.9935815 0.02598673 0.1100204 0.9935896 0.005711674 0.9753229 -0.2207096 0.09292536 0.7670385 0.634836 0.03263884 0.2703266 0.9622153 0.04666483 0.6105035 0.7906377 0.04842054 0.762871 0.644735 0.02450448 0.7579937 0.6518014 0.02828091 0.3052748 0.9518443 0.01062083 0.3024227 0.9531147 -0.003849983 0.2453465 0.9694278 0.008657395 0.08432155 0.9964011 0.01950943 0.08657139 0.9960547 0.02073556 0.05784428 0.9981102 0.02601295 0.05885535 0.9979276 0.02601283 0.05931937 0.9979001 0.02392584 0.05895704 0.9979737 0.02353948 0.0490868 0.998517 0.07276767 0.1932968 0.9784381 0.152962 0.8873662 0.4349526 0.05594974 0.05143058 0.9971082 0.05615162 0.05279248 0.9970256 0.05597841 0.05148255 0.9971038 0.02511799 -0.1557801 0.9874724 0.03056895 -0.05723774 0.9978924 0.09418874 0.804808 0.586014 0.03413683 0.05076777 0.9981269 0.03402882 0.04937422 0.9982005 0.02027994 -0.09448981 0.9953193 0.01895886 -0.1562539 0.9875349 0.02439397 -0.09045302 0.995602 0.02443665 -0.09025609 0.9956188 0.02224206 -0.01653558 0.9996159 0.02035903 -0.0167672 0.9996522 0.02040427 -0.07702845 0.9968201 0.02634268 -0.0936523 0.9952564 -0.1325359 0.9096102 -0.3937557 -0.1325147 0.909615 -0.3937515 -0.1742314 0.961747 -0.2113908 -0.1589836 0.9374839 -0.3095935 -0.132538 0.9096155 -0.3937426 -0.1325368 0.9096145 -0.3937456 -0.09588861 0.9320417 -0.3494334 -0.1733825 0.9847216 0.01618534 -0.1682624 0.9855305 -0.02043002 -0.2110871 0.9770497 -0.02856719 -0.2437158 0.9488883 0.2005333 -0.2484677 0.9395384 0.2356508 -0.2484645 0.9395458 0.2356249 -0.04903435 0.6732531 0.7377844 -0.03856849 0.5690557 0.8213939 -0.03508442 0.5694281 0.8212921 0.01823949 -0.060768 0.9979852 -0.00972706 0.3617936 0.9322074 0.007728397 0.3646903 0.9310968 -0.01573419 0.7954225 0.6058511 -0.04068773 0.9759966 -0.2139515 0.01606649 0.1890601 0.981834 0.02497315 -0.05759125 0.9980279 -0.0811612 0.9667252 -0.242601 -0.08115607 0.9667261 -0.242599 -0.05362808 0.5821872 -0.8112843 -0.05523163 0.5820517 -0.811274 -0.05235713 0.561249 -0.8259893 -0.05059486 0.5203452 -0.8524559 -0.05059498 0.5203453 -0.8524559 -0.09102517 0.9956508 -0.01984804 -0.08884227 0.995857 -0.01938921 -0.0892238 0.9821412 -0.1656433 -0.08962428 0.9878988 -0.1265839 -0.07341802 0.758129 -0.6479585 -0.07182532 0.7583837 -0.6478391 -0.08517336 0.9258216 -0.3682388 -0.08094501 0.9272389 -0.3656175 -0.06886786 0.8550802 0.5139019 -0.06095689 0.8555844 0.514062 -0.04830509 0.7128076 0.6996942 -0.03688037 0.7138765 0.6992998 -0.04139876 0.7668327 0.6405105 -0.01884412 0.7725039 0.6347305 0.01652038 0.1583767 0.9872405 0.0261321 -0.1356946 0.990406 0.02582621 -0.09019565 0.9955891 0.02574497 -0.08858209 0.9957362 0.02296763 -0.01127284 0.9996727 0.01585686 -0.01281005 0.9997922 0.004137754 0.150193 0.9886481 -9.82198e-4 0.1492927 0.9887925 -0.008916079 0.2445268 0.9696016 -0.02502375 0.4194802 0.9074196 -0.02522075 0.4217497 0.9063615 -0.04179447 0.585482 0.8096074 -0.04983097 0.6731889 0.7377896 -0.06098705 0.7779945 0.6253042 -0.0736674 0.9068874 0.4148837 -0.0754671 0.9067942 0.4147638 -0.0860207 0.9878855 0.1291615 -0.08564287 0.9845636 0.1526427 -0.08548474 0.984574 0.1526635 -0.08613157 0.9883735 0.1252966 -0.0855152 0.9884142 0.1253983 -0.08498561 0.9854703 0.1470571 -0.09129321 0.9850868 0.1458413 -0.08940374 0.9923051 -0.08566009 -0.1030562 0.9906667 -0.08921182 -0.09324902 0.9844987 -0.1485499 0.01153647 -0.2363085 0.9716096 0.02183794 -0.1319968 0.9910095 0.0100615 -0.4660131 0.8847206 -0.03417301 -0.4465217 0.89412 -0.03359013 -0.4464102 0.8941978 0.002957582 -0.4380932 0.8989247 -0.02792942 -0.413483 0.9100835 -0.02792942 -0.4134829 0.9100834 0.04494905 -0.3343932 0.9413611 -4.86018e-4 -0.312432 0.94994 0.03720623 -0.3042527 0.9518646 0.003692984 -0.2850744 0.9584983 0.003690958 -0.2850749 0.9584982 0.03521049 -0.1810182 0.9828492 0.01922106 -0.2813735 0.9594058 0.01902312 -0.2346566 0.9718922 0.03874343 -0.264015 0.9637402 0.03728669 -0.2590379 0.9651471 0.04912328 -0.256496 0.9652962 0.0508728 -0.2649323 0.962924 0.003700435 -0.27514 0.961397 -0.1043322 0.1417014 0.984396 -0.258895 0.7562991 0.6008204 -0.237618 0.6482069 0.7234401 -0.08878648 0.03235673 0.9955249 -0.113372 0.3016767 0.9466457 -0.177688 0.2921388 0.9397245 -0.117948 0.9615336 -0.2480753 -0.1386709 0.9580706 -0.250741 -0.2588897 0.7564089 0.6006844 -0.2452101 0.4127224 0.8772299 -0.2023131 0.1774154 0.9631164 -0.134756 0.9416456 0.3084548 -0.09508323 0.3857136 0.9177059 -0.2376136 0.6482076 0.723441 -0.03433382 -0.448467 0.8931397 -0.03241634 -0.4479848 0.8934534 -0.04127877 -0.2803064 0.9590226 0.002278447 -0.2715018 0.9624353 -0.005782127 -0.1311833 0.9913413 0.04820656 -0.1212089 0.9914557 0.03608471 -0.183462 0.9823643 0.03608494 -0.183462 0.9823643 0.04809492 -0.1243761 0.9910688 0.01752251 0.08639955 0.9961065 0.6086753 0.1018497 0.7868552 -0.07740789 0.1770824 0.9811472 0.02183818 -0.1319956 0.9910097 0.02285754 -0.1318269 0.9910092 0.02266031 -0.1305531 0.9911824 0.01099455 -0.1325941 0.9911094 0.02039974 -0.1441382 0.9893473 0.02039957 -0.1441382 0.9893473 0.007771015 -0.1488127 0.9888348 -0.1025254 -0.1542353 0.9827004 -0.1279554 0.02467304 0.9914729 -0.1608441 0.189473 0.9686223 -0.1897694 0.4797667 0.856628 -0.2530153 0.4633557 0.8492848 -0.2678771 0.7539866 0.5997884 -0.1732575 -0.008114695 0.9848431 -0.1732609 -0.0080958 0.9848427 -0.1371312 -0.1648641 0.9767369 -0.1425486 0.002569794 0.9897844 -0.09071511 -0.30019 0.9495561 -0.07734853 0.1770891 0.9811506 -0.08768713 0.9455814 0.3133475 -0.0282213 0.01194751 0.9995303 -0.03354448 0.1481142 0.9884012 -0.01785951 -0.06204229 0.9979137 -0.06976646 -0.06973028 0.9951233 -0.05130338 -0.2541173 0.9658118 -0.06323343 -0.2570166 0.9643359 -0.0431779 -0.4183285 0.907269 -0.05108624 -0.4206641 0.9057769 -0.0020653 -0.2688421 0.963182 0.01743239 -0.1694827 0.985379 0.01743239 -0.1694827 0.985379 0.01255917 -0.179431 0.9836905 0.0278629 -0.1819089 0.9829206 0.02440673 -0.1826071 0.9828829 0.02867221 -0.203968 0.9785576 0.02867239 -0.203968 0.9785576 0.009201467 -0.1591337 0.9872141 0.0193898 -0.1677069 0.9856462 -0.006505787 -0.1680907 0.9857501 0.00813663 -0.1771737 0.984146 -0.006415188 -0.1795517 0.9837276 0.006413519 -0.1963065 0.9805216 -0.006262779 -0.1985303 0.9800747 0.01244473 -0.22121 0.9751468 -0.006047129 -0.2247881 0.9743888 0.01142925 -0.2316787 0.9727252 -0.01946896 -0.2631798 0.9645503 -0.0194689 -0.2631797 0.9645503 -0.3123325 0.1374449 -0.9399774 0.1611349 -0.8331555 0.5290439 0.01147168 -0.09901893 0.9950194 -0.08239459 0.07237404 -0.9939684 -0.08239513 0.07237428 -0.9939684 0.9781576 0.1943949 0.07360947 0.1884146 0.9706043 0.1497575 0.1818419 0.8361282 0.5175163 0.1998093 0.9292792 -0.3106713 0.005238115 0.3201733 -0.9473445 0.1234121 0.3724249 0.9198202 0.04543781 -0.1098885 0.9929048 0.04702365 -0.1019132 0.9936813 0.108186 0.1980344 0.9742063 0.1039882 0.1761233 0.9788601 0.07972782 0.05516719 0.995289 0.07118713 0.01348364 0.9973719 0.08036088 0.05530977 0.9952301 0.05720233 -0.05283927 0.9969633 0.05355578 -0.07328575 0.995872 0.0400691 -0.1289651 0.9908393 0.0422492 -0.1184282 0.9920634 -0.07433736 -0.5734711 0.815846 0.2334691 0.7430819 0.6271535 -0.1489644 -0.811742 0.5646985 0.06275278 -0.1315554 0.9893206 0.07230454 -0.09548771 0.9928013 0.07377463 -0.107416 0.9914731 0.108498 -0.00651735 0.9940754 0.07051497 -0.1231662 0.9898777 0.1884418 0.8517971 -0.4888062 0.09525948 -0.03965461 0.9946623 0.1742402 0.8709682 -0.459407 0.08706849 -0.06404829 0.9941412 0.09121572 -0.05403476 0.9943641 0.1138351 0.01922738 0.9933136 0.06457597 -0.09358918 0.9935145 0.08653146 -0.04975712 0.9950058 0.08565104 -0.05265802 0.9949327 0.1256871 0.02608418 0.991727 0.1168342 0.02832132 0.9927475 0.1605259 0.1754593 0.9713113 0.1051313 -0.006586313 0.9944365 0.04609161 0.2110419 -0.9763897 0.2542679 0.2891429 0.9228999 -0.04136842 0.1367081 -0.9897472 -0.02553141 0.1243809 -0.9919061 0.1417378 0.02100926 0.9896813 0.4878057 0.8341985 0.2572126 0.1055625 -0.005421102 0.9943979 -0.04863262 0.1555159 -0.9866355 0.4870697 0.8481495 0.2083399 0.4865917 0.8544108 0.1822382 0.1061409 -0.003919184 0.9943434 0.1045257 -0.008145511 0.9944888 0.1045235 -0.008141219 0.9944891 0.4878057 0.8341985 0.2572126 0.488 0.8299111 0.2703766 0.1325718 0.3744744 -0.9177111 -0.1376197 -0.05245906 -0.989095 0.1151145 0.01595693 0.9932241 0.1054506 -0.00574088 0.994408 0.1054963 -0.005630016 0.9944038 -0.06849098 0.1306961 -0.9890539 0.1164171 0.3010712 -0.9464688 0.2475407 0.1557096 0.9562835 0.1986424 0.1730074 0.9646811 -0.07673442 0.06898021 -0.9946625 -0.08103972 0.07073891 -0.9941975 -0.09511399 0.0360434 -0.9948136 -0.07386803 0.1072337 -0.991486 0.08721286 -0.04997646 0.9949353 0.1428906 0.02241212 0.9894847 0.1266157 0.02775466 0.9915635 0.1987672 0.1732575 0.9646105 0.1627299 0.182955 0.96956 0.1042068 -0.01241314 0.9944782 0.2066959 0.3804423 0.9014102 0.07519024 -0.1034642 0.991787 0.07124429 -0.1190915 0.990324 -0.06940484 0.1246243 -0.9897735 -0.06853729 0.1292762 -0.9892372 -0.06846123 0.1305003 -0.9890819 0.0704627 -0.1242344 0.9897479 0.07049018 -0.1243918 0.9897261 0.07058757 -0.1245788 0.9896956 -0.06858855 0.1308964 -0.9890206 -0.06848043 0.1307804 -0.9890434 -0.2235478 0.08151412 0.9712785 0.07047444 -0.124463 0.9897183 0.0386877 -0.1055932 0.9936566 0.0562458 -0.1127732 0.9920275 0.07970064 -0.09402704 0.9923743 0.1340902 -0.1215309 0.9834887 0.2103549 -0.1093031 0.9714956 0.2587817 -0.1376287 0.9560808 0.4481161 0.6827728 -0.577073 0.5824968 0.4137043 0.6996759 0.01970249 0.1601673 -0.9868932 -0.01155292 -0.1537255 0.9880461 -0.01195704 -0.1539309 0.9880092 -0.02515792 -0.1571548 0.9872535 -0.02484452 -0.1552568 0.9875618 0.8541411 0.1304948 0.5034027 0.02027869 -0.1348651 0.9906564 -0.03791588 0.1302039 -0.9907619 0.1297358 0.1493502 -0.9802362 0.0320484 -0.1321585 0.9907103 0.02159154 -0.1345768 0.9906679 0.03609895 0.1635257 -0.9858784 0.1646456 0.224747 -0.9604064 0.1646415 0.2247589 -0.9604045 0.008433759 0.1366264 -0.9905868 0.0413165 -0.1090127 0.9931813 0.04308205 -0.109578 0.9930441 0.05843627 -0.0861898 0.9945635 0.07945412 -0.09478855 0.9923216 0.1226488 -0.06560933 0.990279 0.2089616 -0.1096173 0.9717608 0.3478131 -0.08763444 0.9334593 0.3399403 -0.08882671 0.9362428 0.4320284 -0.1466598 0.8898553 -0.03845047 0.1242058 -0.9915112 0.3386793 -0.140407 0.9303667 0.1311397 0.1103729 -0.9852006 0.2643347 -0.1409248 0.9540793 -0.3030487 0.1354835 -0.9432951 -0.302573 0.1363428 -0.943324 0.3716857 -0.1454491 0.9168938 0.807595 -0.1689617 0.5650151 0.9952712 0.02480548 -0.09391468 0.7960531 -0.1666882 0.5818201 0.8013048 -0.1681706 0.5741335 0.1310527 0.09547394 -0.9867674 0.3381829 -0.129975 0.9320616 -0.02181249 -0.1074861 0.9939674 0.6163555 -0.1447679 0.7740465 0.2835736 -0.1416848 0.9484257 0.2958671 -0.1421449 0.9445939 0.7941595 -0.1668532 0.584355 0.8222547 -0.171569 0.542643 0.7913705 -0.1667851 0.5881456 0.2994976 -0.1422784 0.9434288 0.2871096 -0.1418167 0.9473416 0.2997587 -0.1423073 0.9433416 0.8402023 -0.1714317 0.5144621 -0.2367056 0.1248822 -0.9635221 -0.2984421 0.1342521 -0.9449384 -0.03532922 0.1264248 -0.9913468 -0.03532922 0.1264254 -0.9913468 0.3075143 0.1590285 -0.9381604 0.2656369 0.1257615 -0.9558352 0.05921077 0.1269934 -0.9901347 0.9345143 0.1571009 0.319378 0.02070659 -0.1347686 0.9906607 0.8670592 0.1337 0.4799298 0.8543012 0.1305151 0.5031254 0.8545008 0.1305548 0.5027762 0.01812863 -0.1353301 0.9906347 0.02519482 -0.1337883 0.9906896 0.02065604 -0.1347813 0.99066 0.8411502 0.128841 0.5252298 0.8406324 0.1384282 0.523617 0.487917 0.3206143 -0.8118765 0.06311678 -0.130779 0.9894003 0.7124651 -0.01131761 0.7016164 0.01660865 -0.1274467 0.9917064 0.09615391 -0.2652435 0.9593749 0.09614849 -0.2652413 0.9593761 0.09612989 -0.2652014 0.9593891 0.01338064 -0.07592171 0.9970241 0.04132509 -0.09404587 0.9947098 0.07086181 -0.2068291 0.9758075 0.04203408 -0.1598184 0.9862511 0.0370146 -0.1325007 0.9904916 0.02279525 -0.123817 0.9920433 0.03342723 -0.1239679 0.9917231 0.04325586 -0.1279819 0.9908328 0.05306071 -0.1090561 0.9926184 0.09352314 -0.1295157 0.9871571 0.1380317 -0.1187432 0.9832839 0.1586378 -0.1306215 0.9786583 0.2711086 -0.1380898 0.9525919 0.2411004 -0.1182231 0.9632725 -0.3123311 0.1374523 -0.9399767 -0.2983652 0.1343846 -0.9449439 -0.2926734 0.1327125 -0.9469581 0.1787924 -0.9804997 0.08157008 -0.02692067 -0.02508723 0.9993228 -0.01725268 -0.0678271 0.9975479 -0.001574277 -0.144057 0.9895682 0.1385206 -0.8358179 0.5312442 0.1392162 -0.8388151 0.5263155 0.05764985 -0.4037526 0.9130499 0.104179 -0.6049132 0.7894471 0.1041159 -0.6046476 0.7896588 -0.007832169 -0.09759908 0.995195 0.05697643 -0.2879725 0.9559422 0.1773617 -0.7589827 0.6264888 0.1305416 -0.7484865 0.6501746 0.0165522 -0.213658 0.9767683 0.01655817 -0.2136867 0.9767619 0.05764418 -0.4037275 0.9130615 0.0576449 -0.4037308 0.91306 0.01299256 -0.2142557 0.9766911 0.01299202 -0.2142529 0.9766918 0.03419518 -0.06670463 0.9971867 0.09946 -0.1089503 0.9890589 0.06863582 -0.1300057 0.9891348 0.04831188 -0.1182587 0.9918069 0.06468766 -0.2019757 0.977252 0.07245635 -0.1927719 0.9785648 0.1307021 -0.3353747 0.9329742 0.05240994 -0.2931411 0.9546316 0.03593873 -0.2170353 0.975502 0.0129553 -0.2140833 0.9767295 0.01298701 -0.2142612 0.97669 0.01519173 -0.1795994 0.9836225 0.01519137 -0.179596 0.9836232 0.01968365 -0.2131638 0.9768182 0.009950876 -0.1692143 0.985529 0.02230304 -0.1708406 0.9850462 0.02004659 -0.1675782 0.9856549 0.02654093 -0.1485264 0.9885522 0.04162114 -0.1546571 0.9870911 0.03618478 -0.1218126 0.9918934 0.06705003 -0.1374353 0.9882388 0.08626937 -0.1182267 0.989232 0.1037035 -0.128276 0.9863017 0.1756801 -0.128103 0.9760769 0.1027791 -0.08084124 0.9914137 0.03717464 -0.1294481 0.9908891 0.03717476 -0.1294477 0.9908891 0.03710585 -0.143941 0.9888903 0.0265311 -0.1562845 0.9873557 0.02606695 -0.1654219 0.9858783 0.02666157 -0.1687041 0.9853061 0.02934372 -0.1748058 0.9841656 0.03137779 -0.1441774 0.9890543 0.04627221 -0.1294507 0.9905056 0.04855239 -0.1181637 0.9918065 0.0546959 -0.1049739 0.9929698 0.06223726 -0.07292824 0.9953934 0.065674 -0.06127649 0.9959579 0.08357959 0.01393097 0.9964038 0.08583384 0.02298164 0.9960444 0.1210445 0.1763994 0.9768477 0.1221232 0.1811673 0.9758404 8.32891e-4 0.3212624 -0.9469898 0.1661813 0.8578996 -0.4862018 -0.1554085 -0.8297523 0.5360591 0.1730049 0.8712949 -0.4592542 0.2176265 0.9510793 -0.2192878 0.03399389 -0.164304 0.9858239 0.04143905 -0.1301288 0.9906308 -0.01893573 -0.3716067 0.9281972 0.1518121 0.8094155 -0.5672739 0.1838454 0.8937705 -0.409115 0.1967298 0.9228815 -0.3310396 -0.09858477 -0.6556661 0.7485873 -0.1069515 -0.6830816 0.7224686 -0.1190434 -0.7217232 0.6818683 0.204388 0.9383055 -0.2789415 0.2445622 0.9338778 0.260886 0.04402196 0.47106 -0.881002 0.002834439 0.3177521 -0.9481696 0.004528403 0.3173375 -0.9483019 -0.01332503 0.250945 -0.9679096 -0.01332503 0.250945 -0.9679096 0.02675014 0.4332601 -0.9008718 0.109678 0.781036 -0.6147793 0.08257073 0.09576058 0.9919738 0.1129426 0.2904624 0.9501976 0.1214289 0.3554987 0.9267555 0.1868489 0.8861361 0.4240875 0.1840103 0.8556511 0.4837368 0.1825415 0.8421536 0.5074012 0.1241943 0.3796443 0.9167584 0.1244798 0.3824227 0.9155642 0.1284361 0.4244932 0.8962754 0.1731078 0.7690255 0.615332 0.9853249 0.168411 0.02779304 -0.02496927 0.1299538 -0.9912056 0.02418678 -0.1456589 0.9890392 0.04331308 -0.1481391 0.9880176 0.04647666 -0.1152994 0.9922429 0.05161547 -0.1165633 0.9918411 0.06346666 -0.0894078 0.993971 0.05853182 -0.08782786 0.9944145 0.08740162 -0.04962891 0.9949361 0.1238158 -0.06460762 0.9901998 0.2096927 -0.007644057 0.9777376 0.2041554 -0.01113915 0.9788752 0.1673963 0.2441061 -0.9551914 0.1118125 0.2105547 -0.9711666 0.2210709 4.34465e-4 0.9752576 -0.002356469 -0.1345317 0.9909065 -0.02287191 -0.1525577 0.9880299 0.03265541 0.157568 -0.9869681 0.03550237 0.1613474 -0.9862589 0.03607338 0.1629022 -0.9859825 -0.02523118 -0.1563854 0.9873738 -0.02523839 -0.1568394 0.9873015 -0.02518928 -0.1570673 0.9872666 0.03604 0.1638336 -0.9858294 0.0360012 0.1639496 -0.9858115 0.03592824 0.1641252 -0.985785 -0.02509754 -0.1572924 0.9872331 -0.2645627 0.3774467 0.8874348 0.34233 0.006883263 0.9395545 0.0222631 0.1614354 -0.9866322 -0.01466488 -0.1552649 0.9877641 -0.01266634 -0.1542851 0.9879452 -0.01232403 -0.1541148 0.9879761 0.01930505 0.1599675 -0.9869335 0.01830333 0.1594584 -0.9870349 0.6988935 0.4535101 -0.5530611 0.6037394 0.4225909 0.6759554 0.5910226 0.4155902 0.6913589 -0.0113818 -0.1536365 0.9880619 -0.01030254 -0.1530767 0.9881606 0.03659868 -0.127354 0.9911819 0.2024771 0.3911985 -0.8977565 0.1953328 0.3985402 -0.8961087 -0.04741859 0.101209 -0.9937345 -0.04983484 0.102782 -0.9934548 -0.0220592 0.1339848 -0.9907379 -0.02205973 0.1339852 -0.9907377 -0.02351182 0.1264877 -0.9916895 -0.02962875 0.100162 -0.99453 0.04232358 -0.003831028 -0.9990966 -0.08894646 0.4539973 -0.8865523 -0.01256304 0.2063325 -0.9784013 0.0334472 1.29006e-4 -0.9994405 -0.10802 0.7049705 -0.7009625 -0.04362231 0.3928315 -0.9185752 0.02247583 0.04611462 -0.9986833 -0.04979526 0.3907642 -0.919143 -0.01065921 0.2065142 -0.9783855 0.09012657 -0.282072 -0.9551506 0.03159403 3.14644e-4 -0.9995008 0.02007639 0.05624747 -0.998215 -0.01255768 0.2063083 -0.9784064 -0.01256537 0.2063432 -0.978399 -0.0125609 0.2063227 -0.9784034 -0.01255607 0.2062997 -0.9784083 -0.06160366 0.4397106 -0.8960242 0.01414459 0.07369923 -0.9971802 -0.01896804 0.177327 -0.9839691 0.001433849 0.1055803 -0.9944097 -0.009925901 0.1400194 -0.990099 -0.007341742 0.1298891 -0.9915013 -0.00221157 0.08109277 -0.9967041 0.07131785 -0.06373083 -0.9954156 -0.3837189 0.7981801 -0.4644011 -0.3836926 0.7981529 -0.4644696 -0.02154058 0.1150494 -0.9931262 0.0504381 -0.1736111 0.9835219 -0.01291573 0.08203858 -0.9965454 -0.01264494 0.08100455 -0.9966335 -0.04716771 0.0829274 -0.9954388 -0.01768457 0.09526795 -0.9952946 -0.0314477 0.09616976 -0.994868 -0.03144812 0.09617 -0.994868 -0.009128451 0.1062939 -0.9942928 -0.01116818 0.1002451 -0.9949001 -0.01649498 0.1024407 -0.9946023 -0.01737505 0.09340876 -0.9954763 -0.02100193 0.08675622 -0.9960081 -0.02153426 0.08945602 -0.995758 -0.03367531 0.0929656 -0.9950997 -0.0115574 0.1249054 -0.9921013 -0.03524708 0.1151716 -0.9927201 -0.01256263 0.1094657 -0.9939112 -0.03711932 0.1007208 -0.9942221 -0.0371201 0.1007208 -0.994222 -0.04716616 0.08292645 -0.9954388 0.04072421 9.08482e-4 -0.9991701 -0.005282878 0.1774032 -0.984124 -0.005274713 0.1773636 -0.9841312 0.001781463 0.1384527 -0.9903675 -0.003583312 0.1629603 -0.986626 0.002889096 0.1285157 -0.9917032 -0.008574426 0.1621497 -0.986729 -0.006399214 0.1438307 -0.9895816 -0.02675861 0.1591595 -0.9868903 -0.02187037 0.1545057 -0.9877498 0.01668715 0.1662107 -0.985949 0.0187363 0.2583976 -0.965857 0.09337991 0.2863208 -0.9535725 0.1616911 0.3776733 -0.9117121 0.1953809 0.3714609 -0.9076581 0.09956282 0.3171025 -0.9431507 0.1467108 0.3247684 -0.9343455 0.09894526 0.2843587 -0.9535983 0.09894543 0.2843588 -0.9535984 0.1702795 0.2456861 -0.9542763 0.1709277 0.2457867 -0.9541345 0.1181442 0.1380608 -0.9833521 0.1763225 0.2998092 -0.9375632 0.1628963 0.29705 -0.9408646 0.1420365 0.2639962 -0.9540082 -0.2238429 -0.2765831 -0.9345566 -0.2104006 -0.1749431 -0.961835 -0.1674266 -0.1663151 -0.9717549 -0.1414761 -0.06628787 -0.9877198 -0.06191939 -0.0513426 -0.9967597 -0.02758842 0.02692013 -0.9992568 0.04878282 0.03866416 -0.9980608 0.07674449 0.08866155 -0.9931009 0.1034379 0.09256893 -0.990319 0.1433827 0.1809504 -0.9729843 0.1586695 0.1833848 -0.9701514 -0.2168588 -0.4524809 -0.8650048 -0.2141168 -0.6374813 -0.740116 -0.2240805 -0.6085838 -0.7611923 -0.2148587 -0.6097835 -0.7628891 -0.2275943 -0.2772962 -0.9334385 -0.187096 -0.5014644 -0.8447061 -0.2273598 -0.124288 -0.9658468 -0.2003217 -0.5434979 -0.8151572 -0.1983779 -0.5438615 -0.81539 -0.1694572 -0.3956548 -0.9026304 -0.2164908 -0.5372096 -0.8151917 -0.2164893 -0.5372099 -0.8151919 -0.02811068 -0.2493889 -0.9679952 -0.02811068 -0.249389 -0.9679954 0.007807672 -0.1444598 -0.9894798 -0.2091343 -0.5692967 -0.7950875 -0.2091348 -0.5692967 -0.7950874 0.118142 0.1380603 -0.9833523 0.1265385 0.1250523 -0.9840477 0.09921222 0.03683841 -0.9943842 0.07628774 0.03342092 -0.9965257 0.02121555 -0.1263044 -0.9917646 -0.02494531 -0.130175 -0.9911772 -0.05262684 -0.2094761 -0.9763966 -0.1158658 -0.2127858 -0.9702047 -0.1401022 -0.3166095 -0.9381523 -0.1914674 -0.319237 -0.9281314 -0.1962589 -0.4299311 -0.8812728 -0.2271577 -0.4311711 -0.8732072 -0.2173727 -0.530429 -0.8193864 0.004853844 0.1643214 -0.986395 0.06644201 0.2305533 -0.9707886 0.03336614 0.220394 -0.9748401 0.03665173 0.2147717 -0.9759763 0.03665179 0.2147717 -0.9759762 0.02526527 0.1836152 -0.9826735 0.03826528 0.1856865 -0.9818637 0.01751738 0.1788914 -0.9837129 0.01514047 0.1808068 -0.9834021 0.007445931 0.1795704 -0.983717 0.01668715 0.1662106 -0.9859491 0.02491128 0.1925118 -0.9809784 0.008332431 0.1646104 -0.9863235 0.01802468 0.1662184 -0.9859241 0.008306741 0.1570137 -0.9875614 0.005249202 0.1589227 -0.987277 -0.2168583 -0.4524812 -0.8650048 -0.1425577 -0.7922366 -0.5933283 -0.1991284 -0.5299186 -0.8243386 -0.1345511 -0.7928053 -0.5944373 -0.1345695 -0.7927505 -0.5945062 -0.1977612 -0.1146191 -0.973526 -0.2107533 0.1854553 -0.9597861 0.1616915 0.3776733 -0.9117119 0.2248542 0.4302706 -0.874247 0.1659379 0.4225164 -0.8910357 0.2326008 0.4814152 -0.8450658 0.1703459 0.4731483 -0.8643569 0.2204567 0.502775 -0.8358327 0.02629673 0.4642106 -0.8853344 0.1192754 0.5327261 -0.8378403 0.02781111 0.5112058 -0.8590083 -0.04427355 0.4473577 -0.8932586 0.02645081 0.4689453 -0.882831 -0.151836 0.3748108 -0.9145832 -0.1322782 0.3716946 -0.9188828 -0.1948938 0.3464035 -0.917617 -0.119842 0.2236245 -0.9672797 0.06662398 0.254343 -0.9648166 0.06662428 0.254343 -0.9648164 0.06463301 0.2556268 -0.9646126 0.1077038 0.289649 -0.9510537 0.1028897 0.2887085 -0.9518724 0.1095438 0.3058859 -0.9457452 0.1095445 0.305886 -0.9457451 0.04453867 0.2265928 -0.9729707 0.04458498 0.2207588 -0.9743089 0.03341835 0.2186987 -0.9752201 0.01923292 0.1958379 -0.9804477 0.008413553 0.1896116 -0.9818232 -0.2273594 -0.1242952 -0.9658459 -0.227652 0.04802459 -0.9725576 -0.2000924 0.05778563 -0.9780715 -0.1673414 0.1428399 -0.9754966 -0.1077851 0.1621319 -0.9808648 -0.07441782 0.2270737 -0.9710302 0.03961366 0.2570312 -0.9655908 0.0605728 0.2869153 -0.956039 0.1585761 0.3055186 -0.9388887 0.1630468 0.3107315 -0.9364089 0.187834 0.3145979 -0.930455 0.1926054 0.3223901 -0.9268051 0.2015343 0.3237132 -0.9244424 0.201275 0.3233077 -0.9246408 0.1893706 0.3215903 -0.9277492 0.1854771 0.3155637 -0.9306008 0.1494672 0.3101057 -0.9388792 0.1442312 0.3014655 -0.9425051 0.1033743 0.2945405 -0.9500315 0.09278953 0.2757784 -0.9567322 0.05637788 0.2686867 -0.9615763 0.05632114 0.2661244 -0.962292 0.01894623 0.2332722 -0.9722269 0.2574703 -0.5381841 0.8025378 0.3126335 -0.7686318 0.5580908 0.2842684 -0.9575055 0.04873162 0.2662503 -0.961183 -0.07237511 0.3287169 -0.7738836 0.5413404 0.3164608 -0.8852064 0.3409724 0.3005532 -0.9366278 0.1799892 0.300593 -0.9365513 0.1803205 0.3071141 -0.567161 0.764205 0.2752611 -0.4389376 0.8553158 0.01003628 -0.4291978 0.9031547 0.1958678 -0.2696137 0.9428384 0.1557722 -0.3976671 0.9042102 -0.2208914 0.04713439 0.9741588 -0.1589437 -0.1559264 0.9748969 -0.09044361 -0.19606 0.976412 -0.02001547 -0.22597 0.9739286 -0.01423549 -0.2273022 0.9737202 -0.01113247 -0.2215467 0.9750862 -0.01946163 -0.308784 0.9509331 -0.2208888 0.04712378 0.9741599 -0.206614 -0.01757031 0.9782647 -0.2346646 0.016308 0.9719397 -0.3378556 0.299071 0.8924182 -0.3412435 0.323662 0.8824941 -0.3412431 0.3236605 0.8824949 -0.3920764 0.5897489 0.7060258 -0.3957006 0.6685198 0.6296843 -0.3956996 0.6684918 0.6297146 -0.401552 0.798887 0.447812 -0.4015741 0.7988784 0.4478074 -0.3570659 0.9245609 0.1330084 -0.3782657 0.8904742 0.2529247 -0.3974079 0.800527 0.4485795 -0.3969417 0.8039097 0.4429069 -0.3969498 0.8038488 0.4430103 0.1755928 -0.1343724 0.9752493 0.175705 -0.1342931 0.97524 0.1372502 -0.1635456 0.9769418 0.135914 -0.3541015 0.9252781 0.1293014 -0.4074302 0.9040364 0.1544974 -0.5496834 0.8209621 0.1745641 -0.5416015 0.8223109 0.2752595 -0.4389405 0.8553149 -0.19937 -0.0172137 0.9797731 -0.1993642 -0.01723486 0.9797739 -0.2835134 0.3188883 0.9043951 -0.2926089 0.3967661 0.8700326 -0.322611 0.6148938 0.7196025 -0.1993675 -0.01722425 0.9797734 -0.1995448 -0.01510846 0.9797722 -0.0925315 -0.3008068 0.9491856 -0.09253144 -0.3008067 0.9491855 -0.08222389 -0.2514901 0.9643609 -0.002225697 -0.3925696 0.9197197 0.2281293 -0.9629572 -0.1437727 0.2286297 -0.9628489 -0.1437025 0.2281963 -0.9629415 -0.1437713 0.09341746 -0.9616863 -0.2577455 0.09341806 -0.9616873 -0.2577412 0.1010487 -0.9754776 -0.1955318 0.1420729 -0.9787178 0.1480774 0.231956 -0.9585525 0.1654493 0.08160924 -0.962463 -0.2588531 0.1462142 -0.968787 0.200183 0.1462147 -0.9687854 0.2001904 0.2996598 -0.9197688 0.2534357 0.2319468 -0.9416416 0.2439506 0.2336807 -0.8305466 0.5055547 0.1538823 -0.8574938 0.4909425 0.164133 -0.7413572 0.6507303 0.164133 -0.7413746 0.6507104 0.1641327 -0.7413681 0.6507179 0.1641327 -0.7413684 0.6507176 0.2775357 -0.7692297 0.5755517 0.220453 -0.7918865 0.5694878 0.1973958 -0.5959839 0.7783559 0.1220288 -0.6264959 0.7698129 0.1186629 -0.5303429 0.8394376 -0.3283761 0.7361729 0.5917925 -0.3216668 0.8150468 0.4819017 -0.3252272 0.7371337 0.5923356 -0.3252257 0.7372499 0.5921916 0.1186633 -0.5303484 0.8394342 0.1186636 -0.5303492 0.8394336 0.01744025 -0.4265465 0.9042975 0.01628023 -0.4610868 0.8872057 0.009685277 -0.4247153 0.9052751 -0.8172898 -0.5761823 -0.007167339 -0.2588194 -0.9659243 -0.001660704 -0.3649742 -0.9280465 0.07432025 -0.1512024 -0.9884748 0.00743401 -0.1512055 -0.9884743 0.007434666 -0.03323262 -0.9994477 3.10063e-4 -0.8172783 -0.5761986 -0.007167339 -0.6207719 -0.7800779 0.07823485 -0.7070953 -0.7070967 0.005529046 -0.6256949 -0.7800658 0.001846075 -0.3841889 -0.9232529 -0.001675784 -0.9467083 -0.3219162 0.0106517 -0.9654388 -0.2586889 0.03174829 -0.9488125 -0.31214 0.04820293 -0.8387388 0.5444423 -0.009988009 -0.9317067 0.3630827 0.00966686 -0.9654469 0.2586911 0.03148508 -0.9875204 0.1574912 0 -0.9956533 -0.09313684 0 -0.7393747 0.6703392 -0.06301021 -0.7289715 0.6820803 -0.05802601 -0.6545752 0.7556069 -0.02428424 -0.6544867 0.7556845 -0.02425295 -0.6291106 0.7771534 -0.01588654 -0.6255896 0.7781818 0.05541235 -0.5963087 0.8027457 0.003904283 -0.6277973 0.7783174 0.009621918 -0.7068826 0.706884 0.02513909 -0.5838646 0.8088839 0.06934499 -0.5841841 0.8086624 0.06923961 -0.6555863 0.7537658 0.04520982 -0.6557686 0.7536108 0.04514694 -0.6869626 0.7258519 0.03494751 -0.7195712 0.6939679 0.02501565 -0.8387487 0.5444272 -0.009988188 -0.8387373 0.5444447 -0.009988188 -0.9705951 0.234476 -0.05446314 -0.8762812 0.4815922 0.01414978 -0.7070407 0.7070421 0.01359963 -0.8412566 0.5073014 -0.1869027 -0.7289598 0.6820937 -0.05801641 -0.9705976 0.2344644 -0.05446654 -0.9651271 0.2586054 -0.04065525 -0.9715395 0.2346553 -0.03237396 -0.8948757 -0.4460563 0.01520681 -0.8948702 -0.4460674 0.01520919 -0.9646885 -0.2584879 -0.05059784 -0.9880995 -0.1538165 0 -0.9987182 0.05061715 0 -0.8948784 -0.4460511 0.01520681 -0.7068162 -0.7068176 -0.02863115 -0.6947149 -0.7190377 -0.01887524 0.2588197 -0.9659256 1.44673e-6 -5.52954e-6 -1 1.49776e-6 -0.001680433 -0.9999985 -1.23588e-7 -0.003060936 -0.9999953 -3.94054e-6 -0.008112967 -0.9999672 -2.29057e-5 -0.0303536 -0.9995391 -3.07045e-4 -0.03027671 -0.9995415 -3.04902e-4 -0.066854 -0.9977605 -0.002150714 -0.1156949 -0.9932628 -0.006610929 -0.115707 -0.9932614 -0.006612479 -0.1923896 -0.9811376 -0.01884716 -0.2561455 -0.9659571 -0.03627991 -0.4094182 -0.9082417 -0.08645135 -0.258812 -0.9658969 -0.007716298 -0.4314798 -0.9020593 0.01069432 -0.4314682 -0.9020648 0.01069432 -0.03313803 -0.9994508 3.08123e-4 -0.005503475 -0.9999849 0 0.2588197 -0.9659257 0 0.1702117 -0.9842752 0.04722553 0.2590646 -0.96586 0 0.3105098 -0.95017 0.02757835 0.1713009 -0.9841239 -0.04643309 0.1823366 0.9831567 0.01249647 0.05727672 0.9983572 0.001503348 0.05728822 0.9983565 0.001504004 0.02424424 0.999706 2.32769e-4 0.02419996 0.9997071 2.3193e-4 0.6658843 0.7459653 0.01156991 0.7065794 0.7065808 0.03859019 0.7911295 0.6115406 0.01149439 0.4228736 0.9061605 -0.007148981 0.4228585 0.9061675 -0.007149517 0.258812 0.9659021 -0.007040977 0.4001229 0.9115966 0.09430366 0.1823423 0.9831556 0.01249772 0.9858825 0.167439 0 0.9858858 0.1674191 -5.98116e-6 0.965217 0.2586266 0.03832048 0.883498 0.4682513 -0.0131191 0.883494 0.4682587 -0.0131191 0.9898542 -0.1420868 0 0.9654003 -0.2586757 0.03300213 0.899208 -0.4373776 -0.01122641 0.767332 -0.6341966 -0.09484779 0.7147948 -0.6972496 -0.05395883 0.6768995 -0.7353016 -0.03374177 0.6769469 -0.735257 -0.03376299 0.6494154 -0.7600996 -0.02254319 0.6494216 -0.7600944 -0.02254533 0.6288958 -0.7774275 0.009820282 0.6285647 -0.7775983 -0.01572328 0.6048991 -0.7962542 -0.00873202 0.5739842 -0.8188664 0 0.6068562 -0.7947905 0.005800724 0.6298012 -0.7766921 0.009991586 0.641865 -0.7667189 0.01230317 0.6626231 -0.7487691 0.01660364 0.6626357 -0.7487577 0.0166065 0.7418358 -0.6695123 0.0378521 0.7418415 -0.6695059 0.03785431 0.7069771 -0.7069786 0.01909053 0.8992203 -0.437352 -0.01122522 0.8992161 -0.4373606 -0.01122522 0.9838443 -0.1519523 -0.09466183 0.9653679 -0.258667 -0.03400254 0.8969255 -0.4419645 0.01386505 0.8969227 -0.4419701 0.0138669 0.707045 -0.7070465 0.01314222 0.8571189 -0.4644868 -0.2227088 0.7673555 -0.6341652 -0.09486836 0.9313397 0.3641501 0.001075625 0.9313358 0.36416 0.001077711 0.9747065 0.2101171 -0.07614487 0.9647781 0.258509 -0.04874849 0.9962038 0.0870524 0 0.9875969 -0.1570105 0 0.7065957 0.7065971 -0.037988 0.7660707 0.6427552 -0.001203775 0.9312962 0.364261 0.001075625 0.004881978 0.9999881 -4.7258e-6 0.004503726 0.9999899 -3.54208e-6 0.01646357 0.9998645 -1.03636e-4 0.05904608 0.9982545 -0.001191914 0.0613383 0.9981163 -0.001251101 0.2441613 0.9695196 -0.0204215 0.2441774 0.9695155 -0.02042365 0.4900336 0.8605196 -0.1391877 0.2587857 0.9658042 -0.01587551 0.5283477 0.8489333 0.01268666 0.5283589 0.8489264 0.01268666 0.00706011 0.999975 9.95518e-6 4.98008e-4 1 0 -0.2588184 0.965926 0 -0.2588184 0.965926 0 -0.5740515 0.8188192 0 -0.6090489 0.7930703 -0.009945392 -0.364997 0.929235 0.05744147 -0.1900724 0.9810874 -0.03660827 -0.2588184 0.9659261 0 0 1 0 0 1 0 0.08798277 -0.9729786 -0.2134754 0.1811354 -0.9601619 -0.2127892 0.0568397 -0.8260782 -0.5606818 0.08354485 -0.9253259 -0.369854 0.02726459 -0.4972829 0.86716 0.1020355 -0.805559 0.583664 0.07140529 -0.4099131 0.9093253 0.01053667 0.42526 0.9050099 0.0251761 -0.5123824 0.8583883 0.02870309 -0.5122432 0.8583607 -0.0090608 -0.1651316 0.9862299 -0.06933486 -0.2783308 0.9579795 -0.1187632 -0.8187794 0.56169 -0.1037864 -0.6377207 0.7632435 -0.123093 -0.9018723 0.4140947 -0.02613216 0.1356946 0.9904061 -0.02913051 0.1630803 0.9861826 -0.01001948 -0.1965156 0.9804494 -0.01723039 -0.06454372 0.9977661 -0.01343154 -0.06391429 0.997865 -0.006832003 -0.1648057 0.9863024 0.2372242 -0.6388928 0.7318065 0.2372248 -0.6388927 0.7318064 0.1530377 -0.8146002 0.5594693 0.01019221 0.4278765 0.9037798 0.001335084 0.4277383 0.9039016 7.14721e-4 0.4271516 0.9041797 0.07825314 -0.4127093 0.9074952 0.07823473 -0.4127185 0.9074926 0.09712421 -0.4115618 0.906192 0.02513515 -0.4301674 0.9023991 -0.02837055 0.06820261 0.997268 -0.03053617 0.06795781 0.9972208 -0.02451181 0.01227366 0.9996241 -0.02451175 0.01227366 0.9996243 0.1779988 -0.9816474 0.06844526 0.1941947 -0.9585102 0.208678 0.2484611 -0.9395543 0.2355943 0.09782272 -0.8233666 0.5590154 0.1578294 -0.8234376 0.545014 0.1465352 -0.9249859 0.3506119 0.2028579 -0.9192598 0.3373574 0.1289877 0.0751087 0.9887976 0.1442085 0.07823532 0.9864497 0.05837792 -0.6829808 0.7280997 -0.01514124 -0.1521188 0.9882462 -0.01032376 -0.247605 0.968806 0.04220271 -0.6673645 0.7435346 0.02119857 -0.4700001 0.8824118 0.02288937 -0.4698884 0.882429 0.003631293 -0.2755036 0.9612932 0.02468377 -0.4195189 0.9074109 0.03170162 -0.4969149 0.8672201 0.01130259 -0.2862042 0.9581019 0.02207547 -0.3793386 0.9249946 0.03856831 -0.5690559 0.8213939 0.04905217 -0.6734303 0.7376215 0.04892033 -0.7149088 0.6975042 0.05026882 -0.7148713 0.6974469 0.04331874 -0.6453375 0.7626683 0.04707771 -0.6451186 0.7626308 0.05087637 -0.6850086 0.7267563 0.04282993 -0.5851258 0.8098108 0.06113457 -0.7781594 0.6250845 9.82366e-4 -0.1492924 0.9887926 0.008916437 -0.2445268 0.9696016 0.02502429 -0.4194802 0.9074195 0.02521651 -0.4216943 0.9063874 0.04176872 -0.5852154 0.8098014 0.04984563 -0.6733665 0.7376266 0.06100142 -0.7781669 0.6250882 0.08331668 -0.9931793 0.08156871 0.08408874 -0.9964244 -0.008216083 -0.01381564 -0.1535731 0.9880407 0.0465458 -0.9988982 -0.006012141 0.02811026 -0.8574411 0.5138139 0.06840151 -0.8554509 0.5133468 0.0791825 -0.9651125 0.2495754 0.08922576 -0.9821684 -0.1654813 0.08884328 -0.9958575 -0.0193578 0.08551025 -0.9883868 0.1256161 0.08612406 -0.9883463 0.1255161 0.08548212 -0.9845743 0.1526639 0.08962219 -0.987868 -0.1268249 0.08909058 -0.9958065 0.02079164 0.0888397 -0.9634634 -0.2526775 0.08354705 -0.9253258 -0.3698542 0.0770803 -0.9315526 0.3553425 0.07922255 -0.9314531 0.3551323 0.08564549 -0.9845635 0.152642 0.08602333 -0.9878855 0.1291598 0.0875706 -0.9959367 0.02101373 0.0836417 -0.9648448 0.2491555 0.08359444 -0.9116079 -0.4024711 0.1065858 -0.991176 0.07880145 0.0769416 -0.8536059 -0.5152058 0.07569336 -0.8537337 -0.5151789 0.09020364 -0.9954648 0.03022128 0.09021556 -0.9954636 0.03022056 0.08872181 -0.9934191 0.07243484 0.1010994 -0.9869778 0.1251147 0.07239353 -0.8056007 0.5880195 0.08051961 -0.9011086 0.4260517 0.11173 -0.9005978 0.4200477 0.0486359 -0.68302 0.7287787 0.04711693 -0.6672939 0.7433027 0.08444833 -0.9733818 0.2130639 0.08181154 -0.9475718 0.3088923 0.1092091 -0.9467288 0.302949 0.08797675 -0.9729793 -0.2134746 0.1085347 -0.9899537 -0.09061962 0.08940464 -0.9923059 -0.08564889 0.08524894 -0.9434962 0.3202304 0.0777384 -0.9437263 0.3214616 0.08986073 -0.982801 -0.1613298 0.08986216 -0.9827993 -0.1613388 0.1177201 -0.9624127 -0.2447527 0.008046686 -0.3257879 0.9454087 0.00438404 -0.3261421 0.9453107 0.005747973 -0.3416645 0.9398045 0.01332789 -0.3410785 0.9399403 4.95975e-4 -0.1408589 0.9900295 0.05563873 -0.6515735 0.7565424 0.09131747 -0.6513034 0.7533028 0.1027567 -0.9155161 0.3889362 0.1503602 -0.9144478 0.3757352 0.1333447 -0.9843936 0.1148408 0.1312631 -0.9880294 0.08104306 0.09621691 -0.9664074 -0.2383259 0.05684238 -0.8260766 -0.5606839 0.08753901 -0.968276 -0.2340481 0.08754128 -0.9682758 -0.2340482 0.09061568 -0.9819904 -0.1657819 0.08818739 -0.972548 -0.2153448 0.09102588 -0.9956514 -0.01981425 0.09129399 -0.9850966 0.1457734 0.08498746 -0.9854795 0.1469941 0.07686215 -0.9368395 0.3412094 0.07772201 -0.9368093 0.3410977 -0.04730492 -0.09477502 0.9943741 -0.04730087 -0.09474259 0.9943774 -0.04729592 -0.09470039 0.9943817 -0.07752424 -0.3618474 0.9290083 -0.07751661 -0.3617759 0.9290367 -0.1187964 -0.8192706 0.5609662 -0.1188138 -0.8195405 0.5605681 -0.1045933 -0.6377124 0.7631403 -0.1045837 -0.6375869 0.7632464 -0.06933689 -0.2783523 0.9579731 -0.06933563 -0.278352 0.9579733 -0.02109134 0.04735708 0.9986553 0.01116561 -0.6357708 0.7717971 -0.02714675 -0.1408068 0.9896649 -0.02750331 0.08369481 0.9961118 -0.03119742 0.0494678 0.9982884 -0.03369092 0.01178729 0.9993628 -0.02784478 0.05001348 0.9983603 -0.02784436 0.05001646 0.9983602 -0.02109169 0.04734897 0.9986557 -0.03454339 -0.3134013 0.9489923 -0.07379084 -0.3217669 0.943939 -0.03359216 0.09264498 0.9951324 -0.03581273 0.01144331 0.999293 -0.02439415 0.09045302 0.995602 -0.02458012 0.08959406 0.995675 -0.02239489 0.01137775 0.9996845 -0.02035194 0.01174104 0.999724 -0.02040427 0.07702726 0.9968201 -0.02634292 0.09365141 0.9952565 0.08340799 -0.8961634 -0.4358145 0.08344787 -0.8961562 -0.4358219 0.08340352 -0.8961551 -0.4358323 0.2195914 -0.9747564 -0.04036945 0.2003912 -0.9724599 -0.1190183 0.1856071 -0.9591054 -0.213698 0.1856172 -0.959118 -0.2136325 0.05683994 -0.8260782 -0.5606819 0.06313884 -0.8263306 -0.5596349 0.1682632 -0.9855306 -0.0204215 0.2110888 -0.9770496 -0.02855658 0.2437158 -0.9488883 0.2005333 0.2484519 -0.9395728 0.2355303 0.2484838 -0.9395009 0.2357836 0.006324231 -0.5520254 0.8338033 0.006308674 -0.5517811 0.8339652 -0.004381358 -0.382943 0.9237616 0.01024228 -0.6201493 0.784417 0.006740748 -0.5721954 0.8200896 0.01907265 -0.7450325 0.6667553 0.05537635 -0.7426287 0.66741 0.07979327 -0.970332 0.2282298 0.07363957 -0.9066403 0.4154284 0.07544124 -0.9065476 0.4153073 0.07141745 -0.8674581 0.4923575 0.07092827 -0.8674805 0.4923889 0.0642659 -0.8024821 0.5932052 0.06109356 -0.8026139 0.5933619 0.06502038 -0.8392608 0.5398275 0.06390386 -0.8392856 0.5399221 0.06739646 -0.870444 0.487632 0.07733786 -0.8703179 0.4863802 0.08874183 -0.9809491 -0.172812 0.08976036 -0.982331 -0.1642215 0.1013675 -0.9924355 0.06925719 0.1056404 -0.9772585 0.1838645 0.08615303 -0.9782899 0.188485 0.06697332 -0.7737596 0.6299291 0.05506134 -0.7738645 0.6309533 0.0342341 -0.5867235 0.8090634 0.03577256 -0.5866535 0.8090476 0.01410466 -0.3738807 0.9273697 0.01880967 -0.3733811 0.9274873 0.009921491 -0.2747154 0.9614744 -0.03026884 0.170319 0.984924 0.06009358 -0.9814506 -0.1820541 0.01678448 -0.6341013 0.7730678 -0.02807956 0.1353705 0.990397 -0.02439367 0.09045308 0.9956019 0.04628825 -0.1150022 -0.9922862 0.07777559 -0.1234881 -0.9892936 0.01929044 -0.1318579 -0.9910809 0.04219293 -0.1602414 -0.9861757 0.07960826 0.06342571 -0.9948064 -0.007212042 -0.3487818 -0.9371762 0.07964307 0.06360322 -0.9947923 0.02837783 -0.1715064 -0.9847741 0.01996719 -0.1760637 -0.9841762 0.04122006 -0.1280883 -0.9909057 0.03373599 -0.1286498 -0.9911161 0.05840581 -0.134622 -0.9891743 0.09669649 -0.04320341 -0.9943758 0.07826322 -0.06570649 -0.994765 0.131801 -0.002282381 -0.9912736 0.2546752 0.1506813 -0.955215 0.08930695 -0.05175888 -0.9946584 0.05869579 -0.118506 -0.991217 0.03693807 -0.111555 -0.9930715 0.04302597 -0.1221225 -0.991582 0.1766154 -0.07891803 -0.9811111 0.1500267 -0.07709026 -0.9856719 0.05020779 -0.1095851 -0.9927086 0.05527848 -0.1018359 -0.9932642 0.04889863 -0.09995347 -0.9937899 0.0516684 -0.09645169 -0.9939957 0.06714993 -0.1014056 -0.9925764 0.08240854 -0.06703907 -0.9943413 0.1802281 0.1686305 -0.9690622 0.1797383 0.1674088 -0.969365 0.2039168 -0.1272002 -0.9706894 0.203885 -0.1271962 -0.9706966 0.05080437 -0.06490248 -0.9965975 0.05080902 -0.06490588 -0.9965971 0.03682929 0.04092144 0.9984833 0.05388605 -0.06586259 -0.9963726 6.53927e-4 -0.3175628 -0.9482371 0.05755031 -0.06515109 -0.9962145 0.03769016 -0.1428068 -0.9890326 0.08378207 0.05990093 -0.9946821 0.09612441 0.06128579 -0.9934808 0.09613144 0.06131619 -0.9934783 0.08560788 0.07389211 -0.9935851 0.09941071 0.07554417 -0.9921747 0.1358042 0.2487959 -0.958988 0.1504211 0.2473617 -0.9571759 0.08467119 -0.0625931 -0.994441 0.03210079 -0.1708869 -0.9847676 0.03210079 -0.1708859 -0.9847677 0.03239792 -0.1647812 -0.985798 0.03239697 -0.1647857 -0.9857972 0.02662324 -0.1634742 -0.9861883 0.05328363 -0.1679145 -0.9843605 0.06073993 -0.1350758 -0.9889718 0.04656505 -0.1332647 -0.989986 0.04392927 -0.1473895 -0.9881026 0.03630685 -0.1477103 -0.988364 0.03492367 -0.1559986 -0.9871397 -0.0754286 -0.02730792 -0.9967772 0.04316794 -0.09100484 -0.9949144 0.07760924 -0.1134405 -0.9905089 0.02973842 -0.1018003 -0.9943603 0.06495338 -0.1228401 -0.9902986 0.01658058 -0.1123405 -0.9935315 0.0322678 -0.1197053 -0.992285 0.02020543 -0.1190063 -0.992688 0.02716034 -0.1218602 -0.9921756 0.01899605 -0.1218829 -0.9923627 0.03408652 -0.1258185 -0.9914675 0.02016746 -0.1753262 -0.9843039 0.02518898 -0.1647336 -0.9860164 0.02062481 -0.1649124 -0.9860925 0.03928756 -0.1482415 -0.9881705 0.03155446 -0.1462714 -0.9887411 0.03155428 -0.1462714 -0.9887412 0.02837777 -0.1715063 -0.9847742 0.03083956 -0.1575944 -0.9870223 0.03742951 -0.1573207 -0.9868381 0.04429507 -0.1427344 -0.9887694 0.05583542 -0.1442075 -0.987971 0.06411516 -0.133473 -0.9889763 0.04130673 -0.1278914 -0.9909276 0.04640769 -0.1247839 -0.9910981 0.02892422 -0.1191918 -0.9924498 0.03233772 -0.1175662 -0.9925383 0.03407317 -0.118277 -0.9923959 0.03897351 -0.1170398 -0.9923622 0.05498284 -0.1251624 -0.9906115 0.06564849 -0.1254324 -0.9899278 0.03737074 -0.1131102 -0.9928793 0.03442519 -0.1126725 -0.9930356 -0.1599019 -0.009097754 -0.987091 0.08188587 -0.4360072 -0.8962101 -0.1438233 0.8446503 -0.5156362 0.1550416 -0.8571169 -0.491236 0.3093252 -0.9472528 -0.08384615 0.3371309 -0.940981 0.02995878 0.2665418 -0.9483692 -0.1719051 0.2686641 -0.9206911 -0.2831032 0.2985897 -0.9367615 -0.1825438 0.3850581 -0.8826762 0.2694678 0.283705 -0.9432899 -0.1723819 0.3093404 -0.9472528 -0.0837897 0.06354784 -0.7287598 -0.6818143 0.1199312 -0.7854902 -0.6071422 0.1972355 -0.861005 -0.4687948 0.1972115 -0.8609821 -0.4688468 0.07564669 -0.6925267 -0.717415 0.02831834 -0.6273001 -0.7782626 -0.0485391 -0.421703 -0.9054338 -0.1836119 -0.3765649 -0.9080117 0.02951711 -0.4221125 -0.9060628 0.03578877 -0.2819179 -0.9587708 -0.001639902 -0.4787885 -0.8779288 -0.001639842 -0.4787886 -0.8779287 0.04451209 -0.5743277 -0.8174146 -0.05593824 -0.5638319 -0.823993 -0.001715481 -0.6015359 -0.7988439 0.07186156 -0.01618862 -0.9972832 0.05643594 -0.1100458 -0.992323 0.01691395 -0.2157736 -0.9762969 -0.01680004 -0.1988438 -0.9798872 0.03578889 -0.2819184 -0.9587707 -0.00359869 0.5052205 -0.8629829 0.05465424 0.1895697 -0.980345 0.03957796 -0.008393883 -0.9991813 0.05689829 0.1548148 -0.9863036 0.004455327 0.499861 -0.8660942 -0.1361872 0.8172557 -0.5599519 -0.1361916 0.8172628 -0.5599404 -0.1525809 0.8428297 -0.516098 -0.2017995 0.9380826 -0.2815634 0.007617413 0.4755563 -0.8796523 -0.02070438 0.4693053 -0.8827933 -0.08415114 0.6724465 -0.7353464 -0.1489433 0.8544173 -0.497782 -0.1428911 0.8448465 -0.515574 -0.09901297 0.7288792 -0.6774449 -0.09798002 0.7290515 -0.6774097 0.003305554 0.5027136 -0.8644466 0.07040637 0.1809921 -0.9809612 0.06151229 0.132287 -0.989301 -0.01134085 0.3977018 -0.9174447 0.03836226 0.4086189 -0.9118985 0.1192462 0.08868664 -0.9888958 0.1136079 -0.02627623 -0.9931781 0.07222604 -0.04215049 -0.9964973 0.04223519 0.06731146 -0.9968376 0.09497547 0.0848149 -0.9918599 0.09618419 0.08100652 -0.9920618 0.07319521 -0.4014895 -0.912934 0.07051795 -0.3667107 -0.9276586 0.08272069 -0.1907218 -0.9781526 0.111473 -0.2270047 -0.967493 0.1114729 -0.2270045 -0.967493 0.3580211 -0.9217669 0.1488846 0.3602476 -0.920964 0.148482 0.3495338 -0.9318913 0.09697884 0.2979511 -0.926841 0.228453 0.2979283 -0.9268941 0.2282676 0.3601438 -0.9209958 0.148537 0.2865433 -0.9476934 0.1406065 0.2228108 -0.9610037 -0.1637905 0.3106409 -0.9232209 0.2261978 0.2096431 -0.9531116 -0.2182382 0.2096492 -0.9531159 -0.2182141 0.08736574 -0.7632051 -0.6402228 0.1383461 -0.8619426 -0.4877656 0.07394015 -0.7670822 -0.6372737 0.073942 -0.7670856 -0.6372693 0.1642296 -0.8109295 -0.5616245 0.1383317 -0.8186967 -0.5573151 0.03611105 -0.6558197 -0.7540535 0.04363816 -0.6534734 -0.7556905 0.1132354 -0.7552783 -0.6455482 -0.02897328 0.7923333 -0.6094001 0.119244 0.08869785 -0.9888952 0.03679317 0.4801468 -0.8764162 -0.002480089 0.6827246 -0.7306716 -0.03264468 0.7920185 -0.6096236 -0.03267467 0.7921204 -0.6094896 -0.05933994 0.8769492 -0.4769055 -0.1490261 0.8543947 -0.4977961 -0.1477001 0.8545928 -0.4978513 0.02314424 -0.5628239 -0.8262528 0.0231437 -0.5628225 -0.8262538 0.007808685 -0.4299398 -0.9028239 0.1278893 -0.5245122 -0.841743 0.1278871 -0.524509 -0.8417453 0.1105483 -0.3866655 -0.9155703 -0.007802426 -0.1805642 -0.9835323 -0.1542566 -0.4385638 -0.8853625 -0.07749158 -0.3781099 -0.9225118 -0.1223635 -0.3618184 -0.9241833 -0.07755142 -0.3782013 -0.9224693 -0.05771827 -0.345371 -0.9366896 -0.07882118 -0.3492002 -0.9337272 -0.05771231 -0.3141514 -0.9476172 -0.1498803 -0.3643771 -0.9191111 -0.07418555 -0.5748736 -0.8148723 0.1266644 -0.5432809 -0.829941 0.01130652 -0.5355635 -0.8444193 0.008541405 -0.4861847 -0.8738144 0.008538603 -0.4861854 -0.873814 -0.06949627 -0.490513 -0.8686582 -0.111662 -0.5366004 -0.8364159 -0.07247376 -0.5431705 -0.8364887 -0.112038 -0.5517545 -0.8264468 -0.1828265 -0.5243848 -0.831622 -0.1409603 -0.5144613 -0.8458486 -0.1824958 -0.5209668 -0.8338399 -0.1396148 -0.4569329 -0.878476 -0.1553655 -0.4601874 -0.8741219 -0.1394518 -0.4512722 -0.881423 -0.1394522 -0.4512722 -0.8814229 -0.1542565 -0.4385637 -0.8853625 -0.1223595 -0.3618175 -0.9241841 -0.1223616 -0.361818 -0.9241836 0.003039598 -0.1781195 -0.9840042 -0.004913687 -0.201278 -0.9795218 0.001472532 -0.2116422 -0.9773461 -0.007954061 -0.2135971 -0.9768894 0.001470625 -0.2116426 -0.977346 0.001473128 -0.2116422 -0.9773462 0.1030808 -0.4738558 -0.8745486 0.1217926 -0.437612 -0.8908773 0.09995013 -0.4458113 -0.8895291 0.120394 -0.4119992 -0.9031955 0.09321576 -0.3868999 -0.9173981 0.147988 -0.3968888 -0.9058581 0.091443 -0.3584712 -0.9290515 -0.0139299 -0.3164293 -0.9485138 -0.01393514 -0.3164303 -0.9485133 -0.05772024 -0.3228058 -0.9447036 -0.01484692 -0.2645472 -0.9642584 -0.01507723 -0.2645419 -0.9642563 -0.004109144 -0.246065 -0.9692446 -0.01549267 -0.2299502 -0.973079 -0.006514191 -0.2179802 -0.9759315 -0.007973551 -0.2179983 -0.9759167 -0.006513774 -0.2177402 -0.9759851 -0.006511986 -0.21774 -0.9759851 -0.01720356 -0.1662926 -0.9859264 -0.1179594 -0.527245 -0.8414858 -0.07099205 -0.5166148 -0.8532697 0.04713159 -0.4282509 -0.9024299 0.1204779 -0.4134756 -0.9025092 -0.06959885 -0.4922823 -0.8676486 -0.06959915 -0.4922823 -0.8676485 -0.2166939 -0.4897952 -0.8444787 -0.1776599 -0.4733183 -0.8627901 -0.2324332 -0.4807143 -0.8455109 -0.1726206 -0.4272952 -0.8874801 -0.1533042 -0.4211046 -0.8939624 -0.1494674 -0.3101061 -0.938879 -0.1442309 -0.3014651 -0.9425053 -0.1033743 -0.2945402 -0.9500316 -0.0927897 -0.2757784 -0.9567321 -0.05637782 -0.2686866 -0.9615764 -0.1957701 -0.373717 -0.9066476 -0.185477 -0.3155641 -0.9306007 -0.1893706 -0.3215908 -0.927749 -0.1702791 -0.2456849 -0.9542767 -0.1709273 -0.2457855 -0.9541348 -0.121644 -0.1424218 -0.9823028 -0.174742 -0.2852468 -0.9423903 -0.1634693 -0.2831378 -0.9450454 -0.1408963 -0.2570479 -0.9560725 0.1077858 -0.1621311 -0.9808647 0.07441776 -0.2270742 -0.97103 -0.03961354 -0.257031 -0.965591 -0.06057292 -0.2869154 -0.956039 -0.1585757 -0.3055185 -0.9388887 -0.1630464 -0.3107315 -0.9364089 -0.1878343 -0.314598 -0.930455 -0.1926052 -0.3223894 -0.9268054 0.1674271 0.1663153 -0.9717548 0.1414771 0.06629043 -0.9877195 0.06191956 0.05134373 -0.9967596 0.02758872 -0.02691924 -0.9992569 -0.0487836 -0.03866583 -0.9980608 -0.07674431 -0.08866155 -0.993101 -0.103438 -0.09256893 -0.9903189 -0.1433831 -0.1809511 -0.9729841 -0.1586696 -0.1833856 -0.9701514 -0.2015338 -0.3237124 -0.9244427 -0.2012754 -0.3233083 -0.9246404 -0.2250477 -0.4311851 -0.8737465 -0.1500645 -0.3672291 -0.9179452 0.2147983 0.6084077 -0.7640038 0.2214885 0.6075397 -0.7627834 0.2111246 0.6644446 -0.7168958 0.2110986 0.4920153 -0.8446054 0.2110993 0.4920153 -0.8446052 0.1345511 0.7928054 -0.5944373 0.1345695 0.7927505 -0.5945062 0.2275943 0.2772962 -0.9334385 0.187096 0.5014644 -0.8447061 0.1975752 0.5371735 -0.8200053 0.2051586 0.5354678 -0.8192583 0.1876873 0.459769 -0.8679782 0.2181778 0.5406683 -0.8124507 0.2181793 0.5406681 -0.8124504 0.05808526 0.3147546 -0.9473941 0.05808544 0.3147546 -0.9473941 0.0376901 0.2593511 -0.9650474 0.161387 0.4239308 -0.8911997 0.1613866 0.4239309 -0.8911997 -0.1216438 -0.1424217 -0.9823028 -0.1240515 -0.1169206 -0.9853633 -0.09921222 -0.03683841 -0.9943842 -0.0762878 -0.03342092 -0.9965256 -0.02121448 0.1263069 -0.9917643 0.02494621 0.1301776 -0.9911768 0.05262607 0.2094739 -0.976397 0.1158643 0.2127809 -0.970206 0.1401018 0.3166095 -0.9381523 0.1914678 0.319237 -0.9281314 0.1962594 0.4299319 -0.8812723 0.2271572 0.4311705 -0.8732076 -0.004853785 -0.1643218 -0.9863948 -0.03227603 -0.2010648 -0.979046 -0.04679387 -0.1965705 -0.9793725 -0.03343665 -0.2181074 -0.9753518 -0.067335 -0.2325253 -0.9702566 -0.04452407 -0.2283802 -0.9725534 -0.03227591 -0.2010648 -0.9790461 -0.0253266 -0.1820648 -0.9829602 -0.03339517 -0.1833527 -0.9824797 -0.01747769 -0.1798821 -0.9835329 -0.01561403 -0.181565 -0.9832549 -0.007564961 -0.1802706 -0.983588 -0.01720362 -0.1662924 -0.9859265 -0.03405421 -0.1977336 -0.9796641 -0.0078516 -0.1911286 -0.9815336 -0.02484756 -0.1941032 -0.9806663 -0.007730364 -0.1654301 -0.9861912 -0.0179885 -0.1671285 -0.985771 -0.007691383 -0.1573981 -0.9875053 -0.005249202 -0.1589227 -0.987277 0.1425522 0.7922535 -0.593307 0.1991279 0.529921 -0.8243371 0.2173721 0.5304312 -0.8193852 0.2238424 0.2765831 -0.9345568 0.2104001 0.174943 -0.9618351 0.2000918 -0.057787 -0.9780716 0.1673417 -0.1428388 -0.9754968 0.1514438 -0.3791477 -0.9128592 0.1204769 -0.4134761 -0.9025092 0.2273581 0.124318 -0.9658433 0.2273592 0.1242951 -0.9658461 0.2276517 -0.04802596 -0.9725576 0.1977614 0.1146152 -0.9735264 0.2095185 -0.3551648 -0.9110213 0.1111385 -0.2271391 -0.9674999 0.1077121 -0.2214599 -0.9692025 0.1249133 -0.2215654 -0.9671119 -0.06759607 -0.2575072 -0.9639092 -0.06759601 -0.2575072 -0.9639092 -0.05846315 -0.2653959 -0.9623654 -0.1130102 -0.2800011 -0.9533248 -0.101988 -0.2779506 -0.955166 -0.1180796 -0.3184875 -0.940544 -0.1180797 -0.3184875 -0.9405439 -0.1478852 -0.3345208 -0.9307125 -0.1478849 -0.3345208 -0.9307126 -0.1477285 -0.3345296 -0.9307343 -0.05761444 -0.2743296 -0.9599081 -0.09307736 -0.2808939 -0.9552147 -0.05750459 -0.249637 -0.9666305 -0.05594021 -0.2493226 -0.9668035 -0.05751019 -0.250694 -0.9663565 -0.04436647 -0.2466926 -0.9680776 -0.01563018 -0.2180433 -0.9758139 -0.0156303 -0.2180433 -0.9758139 -0.08161443 0.9624691 -0.2588286 -0.2336817 0.8305383 0.5055679 -0.1687133 0.4230167 0.8902768 -0.2588945 0.4663242 0.8458815 -0.2984933 0.940766 0.1608135 -0.2810295 0.9593312 0.02657419 -0.2629637 0.9602318 -0.09383445 -0.3311424 0.7542593 0.5669548 -0.3238072 0.8401889 0.4350073 -0.3127834 0.9016774 0.2985708 -0.3127366 0.9018787 0.2980108 -0.3139758 0.5943776 0.740361 -0.3125156 0.6564157 0.6866239 -0.1748737 0.2998916 0.9378082 -0.04869103 0.4150525 0.9084936 0.02588099 0.2771445 0.9604796 0.02588039 0.2771471 0.9604789 -0.1727207 0.3931409 0.9031101 -0.0477094 0.1210328 0.9915013 0.00897479 0.2253801 0.9742295 0.08090448 0.2088944 0.9745858 0.3555639 -0.409109 0.8403596 0.2516713 -0.04522788 0.9667553 0.2516599 -0.04521375 0.966759 0.2003079 0.01537424 0.9796124 0.1711035 0.1343004 0.9760569 0.1711045 0.1342967 0.9760571 0.3618766 -0.3896257 0.8468986 0.4008809 -0.7713362 0.4943025 0.3899765 -0.5905498 0.7065191 0.3222243 -0.6150081 0.7196781 0.4015384 -0.7989063 0.4477898 0.3995916 -0.7996611 0.4481838 0.4008711 -0.771469 0.4941031 0.3976317 -0.8004333 0.4485484 0.3729894 -0.9018301 0.2181314 -0.1755952 0.134379 0.9752479 -0.175454 0.1344793 0.9752596 -0.1372511 0.1635398 0.9769426 -0.1344439 0.3560997 0.9247258 -0.1307775 0.4155259 0.9001307 -0.154498 0.5496805 0.8209639 -0.186376 0.5367068 0.8229276 -0.2588913 0.4663295 0.8458795 0.334557 -0.3003279 0.8932383 0.2805524 -0.3199353 0.9049486 0.2803392 -0.3179295 0.9057211 0.140997 0.1266881 0.9818707 0.1409966 0.1266899 0.9818705 0.1827604 0.009276092 0.9831137 0.1704373 0.1368629 0.9758175 0.1704344 0.1368738 0.9758164 0.1016855 0.3449448 0.9330987 0.08222419 0.2514886 0.9643613 0.002225816 0.3925694 0.9197197 -0.2281359 0.9629611 -0.1437355 -0.2265933 0.9632927 -0.1439539 -0.2282509 0.9629405 -0.143691 -0.09341287 0.9616774 -0.2577801 -0.0934152 0.9616819 -0.2577625 -0.1010481 0.9754768 -0.1955358 -0.1420691 0.9787238 0.148041 -0.2319574 0.958559 0.1654098 -0.2319486 0.9416373 0.243965 -0.3013776 0.9191421 0.2536717 -0.3133875 0.7474169 0.5857955 -0.1641324 0.7413685 0.6507174 -0.1641323 0.7413682 0.6507179 -0.1462157 0.9687854 0.2001894 -0.1462158 0.9687852 0.2001906 -0.1538832 0.8574867 0.4909546 -0.1641327 0.7413614 0.6507256 -0.1641327 0.7413748 0.6507104 -0.2837181 0.7665678 0.5760886 -0.2204554 0.7918819 0.5694932 -0.1973982 0.595984 0.7783554 -0.122029 0.6264961 0.7698128 -0.1186631 0.5303475 0.8394346 0.32834 -0.7074199 0.6258992 0.3207745 -0.8151873 0.4822584 0.3241735 -0.7087639 0.6265504 0.3241744 -0.7087923 0.6265177 -0.1186631 0.5303473 0.8394348 -0.1186637 0.5303495 0.8394334 -0.01744002 0.4265451 0.9042982 -0.01628005 0.4610866 0.8872057 -0.009685039 0.4247154 0.9052751 -0.01455777 0.1819801 0.9831945 -0.02092832 0.2469134 0.9688115 -0.4221927 0.9059047 0.03301614 0.03155565 0.00586456 0.9994848 -0.03419506 0.06670504 0.9971867 -0.514455 0.1883688 0.8365722 -0.3735264 -0.7255358 0.577993 -0.03137773 0.1441776 0.9890542 -0.3152107 -0.9423044 -0.1127151 -0.206465 -0.8909667 0.4044139 0.001314401 0.3254091 0.9455723 -0.1893469 -0.6367756 0.7474387 -0.1893469 -0.6367756 0.7474387 -0.1892997 -0.6364578 0.7477213 -0.1446285 -0.3679808 0.9185165 -0.1446399 -0.3680437 0.9184896 -0.09361654 -0.1017049 0.9904 -0.05965965 0.04478162 0.9972137 -0.08884012 -0.1010356 0.9909083 -0.05878591 0.04492157 0.9972593 -0.05243217 0.07955378 0.9954508 -0.0265311 0.1562845 0.9873557 -0.03710573 0.1439411 0.9888904 -0.03717464 0.1294482 0.9908891 -0.03717464 0.129448 0.9908891 -0.2137761 -0.9574664 -0.1937981 -0.1175295 -0.01871424 0.992893 -0.08583116 -0.02297097 0.9960449 -0.08358097 -0.01393586 0.9964035 -0.0713666 -0.01349467 0.9973589 -0.0587874 0.04491448 0.9972596 -0.0546962 0.1049731 0.9929698 -0.09946036 0.108952 0.9890587 -0.0400688 0.1289665 0.9908391 -0.04224926 0.118428 0.9920634 -0.04855239 0.1181634 0.9918064 -0.04627215 0.1294509 0.9905056 -0.06275272 0.1315556 0.9893206 -0.04647678 0.1152997 0.9922428 -0.05161607 0.1165637 0.9918411 -0.0413165 0.1090127 0.9931814 -0.04308146 0.1095778 0.9930441 -0.03868734 0.1055932 0.9936566 -0.05624651 0.1127737 0.9920274 -0.04219311 0.1602414 0.9861757 -0.04219359 0.1602398 0.986176 -0.04221022 0.1601706 0.9861864 -0.3981689 -0.8337127 0.3826026 -0.3915284 -0.8007085 0.4534 -0.1818062 -0.1789634 0.9669119 -0.3734482 -0.7255686 0.5780025 -0.3730874 -0.7242205 0.5799229 -0.3731037 -0.7242313 0.579899 -0.1363667 -0.01604104 0.9905286 -0.09891062 0.05374079 0.9936441 -0.08653235 0.04975795 0.9950057 -0.07377445 0.107415 0.9914733 -0.07230448 0.09548765 0.9928012 -0.0645768 0.09358936 0.9935144 -0.0634675 0.08940809 0.9939708 -0.05853146 0.08782774 0.9944146 -0.05843585 0.08618897 0.9945635 -0.07945442 0.09478771 0.9923216 -0.07969999 0.09402906 0.9923741 -0.1511021 0.1300959 0.97992 -0.1782878 -0.00328505 0.9839729 -0.1191787 0.09026843 0.9887608 -0.2926601 -0.05334085 0.9547276 -0.486095 -0.03259599 0.8732978 -0.1719527 0.1264467 0.9769563 -0.05355584 0.07328575 0.995872 -0.06223732 0.07292824 0.9953935 -0.06567412 0.06127649 0.9959579 -0.08706796 0.06404823 0.9941414 -0.1053308 0.01970845 0.9942419 -0.09607213 0.01812839 0.9952093 -0.1192339 -0.03012806 0.9924091 -0.1545978 -0.01850134 0.9878042 -0.2614798 -0.1508604 0.9533464 -0.4011571 -0.3292111 0.8548058 -0.6396611 -0.6981608 0.3215667 -0.243574 -0.131186 0.9609693 -0.2435383 -0.1311419 0.9609844 -0.019616 0.1149042 0.9931828 -0.01961231 0.1148976 0.9931837 -0.04836356 0.1630131 0.9854379 -0.04831254 0.1182599 0.9918068 -0.05480527 0.1513367 0.9869617 -0.05663198 0.1523874 0.986697 -0.02044713 0.09663832 0.9951095 -0.03031355 0.2107496 0.97707 -0.1709289 0.6811335 0.7119274 -0.2543908 0.9265595 0.2770792 -0.1848863 0.9399824 0.2867929 -0.1762781 0.9111418 0.3724875 -0.176297 0.9112072 0.372318 -0.2027322 0.9791328 -0.01409679 -0.1163738 0.6749256 0.7286512 -0.1846814 0.9393451 0.2890046 -0.1159979 0.6754297 0.7282439 -0.1174774 0.6816651 0.7221716 -0.1160399 0.6756317 0.7280498 -0.05937111 0.4280635 0.9017964 -0.4222028 0.9059108 0.03271806 -0.2616985 0.9380297 0.2271876 -0.1054267 0.4592384 0.8820347 -0.06561118 0.4560208 0.8875472 -0.0594474 0.4280851 0.9017812 -0.4830335 0.8412127 -0.2429808 -0.4059255 0.9126405 0.04808115 -0.1234422 0.3226954 0.9384188 -0.05503267 0.2976185 0.9530974 -0.05665791 0.3034637 0.951157 -0.03191572 0.300559 0.9532291 -0.03227066 0.3023676 0.9526449 -0.01451659 0.2098155 0.9776332 -0.01451653 0.2098153 0.9776333 -0.08516377 0.219663 0.9718515 -0.06701678 0.2094575 0.9755185 -0.06826245 0.2129856 0.9746679 -0.02753859 0.1967868 0.9800595 -0.03163331 0.2164922 0.9757717 -0.015464 0.2144125 0.9766207 -0.02092903 0.2469173 0.9688105 -0.06863588 0.1300069 0.9891346 -0.04132401 0.09404516 0.9947099 -0.013381 0.07592195 0.997024 -0.01455783 0.1819806 0.9831943 -0.01178944 0.1694581 0.9854669 -0.02230328 0.1708407 0.9850462 -0.02004671 0.1675782 0.985655 -0.02654111 0.1485264 0.9885522 -0.0416212 0.1546572 0.9870911 -0.03618484 0.1218128 0.9918933 -0.06704902 0.1374351 0.9882389 -0.08626914 0.1182253 0.9892322 -0.1037032 0.1282743 0.9863018 -0.1757 0.1281 0.9760737 -0.1028024 0.08084702 0.9914109 -0.04220992 0.1601725 0.9861862 -0.04221946 0.1601386 0.9861913 -0.2433899 -0.9595813 0.141298 -0.2134417 -0.9651741 0.1512664 -0.08884799 -0.1010743 0.9909036 -0.02606695 0.1654223 0.9858782 -0.02666139 0.1687035 0.9853062 -0.02934366 0.1748056 0.9841656 -0.02418678 0.1456588 0.9890392 -0.04331332 0.148139 0.9880176 -0.01660883 0.1274467 0.9917064 -0.0370146 0.1325007 0.9904916 -0.02279543 0.123817 0.9920432 -0.03342694 0.1239678 0.9917231 -0.0432558 0.127982 0.9908328 -0.05306082 0.1090559 0.9926185 -0.09352374 0.1295155 0.9871571 -0.1746121 0.1096469 0.9785133 -0.206483 0.1234315 0.9706335 -0.3014775 0.128672 0.9447512 -0.3423473 0.1321307 0.9302363 -0.283142 0.1284886 0.9504321 -0.03715974 -0.01145863 -0.9992436 0.0371589 -0.3280524 -0.9439284 0.02815842 -0.1000522 -0.9945837 0.009925663 -0.1400184 -0.9900991 0.06267893 -0.3303565 -0.9417727 0.1223585 -0.7023682 -0.7012184 0.05135136 -0.3923022 -0.9184018 0.05097043 -0.3905724 -0.9191601 0.0109741 -0.2065492 -0.9783747 0.01098477 -0.2065989 -0.9783641 0.01098078 -0.2065802 -0.9783681 0.007341682 -0.1298888 -0.9915013 0.009128332 -0.1062945 -0.9942928 0.01116818 -0.1002453 -0.9949001 -0.03585618 0.01135975 -0.9992924 -0.03772836 0.01633483 -0.9991545 -0.03572338 0.0110045 -0.9993012 -0.03966552 0.02172422 -0.9989768 0.04774957 -0.2788639 -0.9591428 -0.02340513 -0.03315222 -0.9991762 0.01783818 -0.1745825 -0.984481 0.0601772 -0.1915869 -0.9796292 0.007294058 0.05756109 0.9983153 -0.003073334 -0.0659793 -0.9978163 -0.00104165 -0.06886214 -0.9976257 -0.0504437 0.1736216 0.9835197 0.01097917 -0.2065722 -0.9783697 0.00119239 -0.1578801 -0.9874575 0.01390218 -0.1595703 -0.9870886 -0.001433253 -0.1055821 -0.9944096 0.02154022 -0.1150485 -0.9931263 0.01649516 -0.1024411 -0.9946023 0.01737534 -0.09340822 -0.9954763 0.198545 -0.575983 -0.7929838 0.0758509 -0.1050688 0.9915681 0.08065277 -0.09976834 0.9917365 0.01119571 -0.2066793 -0.9783447 0.04490381 -0.3633165 -0.9305831 0.04240202 -0.3519893 -0.935043 0.0701406 -0.3551185 -0.9321863 -0.01362675 -0.06793069 -0.997597 -0.01919704 -0.06941127 -0.9974034 0.04104721 -0.02758109 0.9987764 0.06138086 -0.08469152 0.9945149 0.02100157 -0.08675694 -0.996008 0.0129165 -0.08203977 -0.9965454 -0.04232227 0.003829002 -0.9990967 0.01095652 -0.2065692 -0.9783706 0.008825361 -0.1965628 -0.9804515 0.02500087 -0.198667 -0.9797481 0.00451219 -0.1285309 -0.9916953 0.03352987 -0.1404097 -0.9895256 0.01979017 -0.1151984 -0.9931453 -0.003158271 -0.06596648 -0.9978169 0.005567193 0.06135356 0.9981005 0.006118476 0.06014078 0.9981712 0.006388187 0.0595532 0.9982047 -0.003030657 -0.06600159 -0.9978148 -0.002820491 -0.06619876 -0.9978026 -0.002284228 -0.06689929 -0.9977571 0.008997499 0.05379647 0.9985113 0.01241612 0.04616749 0.9988565 0.0191552 0.03081911 0.9993414 -4.77098e-4 -0.06985998 -0.9975567 0.0657131 -0.1959826 -0.9784032 0.01978671 -0.1151921 -0.9931462 0.02361404 -0.1233801 -0.9920785 0.1739193 -0.04314053 -0.9838145 0.005215167 0.06212455 0.9980547 0.005214691 0.06212556 0.9980547 0.3384579 -0.879397 0.3348242 0.2111692 -0.6134517 -0.7609761 0.1964076 -0.5730721 -0.7956209 -0.03592276 0.01153749 -0.999288 -0.03466475 0.008186399 -0.9993655 -0.03590023 0.01147812 -0.9992895 0.199674 -0.5781408 -0.791128 0.2018955 -0.5827636 -0.7871626 0.2362459 -0.4762707 0.8469676 0.07092148 -0.08219689 0.9940895 0.06757169 -0.0854144 0.9940516 0.008552372 -0.09270417 -0.9956569 0.01776975 -0.09577727 -0.9952442 0.02959668 -0.09661602 -0.9948816 0.02213174 -0.09248918 -0.9954677 0.03776746 -0.0953499 -0.9947271 0.01269984 -0.0812124 -0.9966159 0.05309152 -0.08300358 -0.995134 0.053092 -0.08300387 -0.995134 0.005274891 -0.1773653 -0.9841309 0.00527507 -0.1773659 -0.9841308 -0.001781702 -0.1384515 -0.9903676 0.003583312 -0.1629603 -0.9866261 -0.002889156 -0.1285155 -0.9917032 0.008574426 -0.1621494 -0.986729 0.00647664 -0.1444832 -0.9894861 0.02612012 -0.159266 -0.9868901 0.02122867 -0.1546116 -0.9877473 0.02277487 -0.1279802 -0.9915152 0.0338087 -0.1280628 -0.9911897 0.01158702 -0.1251339 -0.9920722 0.03538268 -0.1152657 -0.9927044 0.01257014 -0.1095154 -0.9939056 0.03716087 -0.1007264 -0.9942199 0.03716218 -0.1007264 -0.9942199 -0.01153641 0.2363088 0.9716095 -0.02183759 0.1319983 0.9910093 -0.01006144 0.4660134 0.8847204 0.03417295 0.4465218 0.8941199 0.03359013 0.4464102 0.8941978 -0.002957344 0.4380933 0.8989247 0.02792942 0.4134832 0.9100833 0.02792942 0.4134832 0.9100833 -0.04494929 0.334393 0.9413612 4.85992e-4 0.3124319 0.94994 -0.03720605 0.3042526 0.9518646 -0.003692984 0.2850744 0.9584983 -0.003690838 0.2850749 0.9584981 -0.03521043 0.1810179 0.9828493 -0.01922124 0.2813735 0.9594057 -0.01902329 0.2346569 0.9718921 -0.03874325 0.2640147 0.9637402 -0.03728675 0.2590382 0.965147 -0.0491234 0.2564963 0.9652962 -0.05087274 0.2649317 0.9629244 -0.003700256 0.2751396 0.9613972 0.1043323 -0.141704 0.9843956 0.261007 -0.7273599 0.6346834 0.2376185 -0.6482262 0.7234226 0.08878654 -0.03235697 0.995525 0.1133716 -0.3016652 0.9466494 0.1776867 -0.2921249 0.9397289 0.1179455 -0.9615308 -0.2480876 0.1386685 -0.958068 -0.2507526 0.1347566 -0.9416408 0.3084692 0.09508389 -0.3857188 0.9177036 0.2376191 -0.6482261 0.7234224 0.034334 0.4484673 0.8931395 0.0324161 0.4479849 0.8934533 0.04127871 0.2803062 0.9590227 -0.002278447 0.2715018 0.9624353 0.005782127 0.131184 0.9913411 -0.04820656 0.1212102 0.9914556 -0.03608483 0.183462 0.9823643 -0.03608483 0.183462 0.9823643 -0.04809498 0.1243754 0.9910689 -0.01752263 -0.08639776 0.9961066 -0.6085888 -0.1018381 0.7869236 0.07739096 -0.1770777 0.9811494 -0.02285754 0.1318274 0.9910091 -0.02285754 0.1318272 0.9910092 -0.0220707 0.1306566 0.991182 -0.01099455 0.1325939 0.9911095 -0.02039986 0.1441381 0.9893473 -0.02039992 0.1441382 0.9893473 -0.007771015 0.1488128 0.9888348 0.1025252 0.1542359 0.9827003 0.1279555 -0.02467322 0.9914729 0.1608428 -0.1894659 0.9686239 0.1897699 -0.4797841 0.8566181 0.2537902 -0.4631645 0.8491579 0.2689872 -0.7252222 0.6337971 0.1379354 0.1256252 0.9824419 0.2610057 -0.7274014 0.6346363 0.2347297 -0.3335578 0.9130396 0.2019419 -0.1775171 0.9631755 0.1451303 0.1281304 0.981081 0.136343 0.1646248 0.9768875 0.1379356 0.125623 0.9824423 0.1379349 0.125627 0.9824417 0.07734793 -0.1770826 0.9811519 0.08768653 -0.9455767 0.313362 0.0282213 -0.01194751 0.9995303 0.03354448 -0.148117 0.9884007 0.01785963 0.06204187 0.9979138 0.06976652 0.0697298 0.9951233 0.05130338 0.2541169 0.9658119 0.06323349 0.2570163 0.964336 0.0431779 0.4183287 0.9072688 0.0288552 0.4140263 0.9098075 -3.64997e-4 0.3094573 0.9509133 -0.01743239 0.1694827 0.9853789 -0.01743227 0.1694827 0.9853789 -0.01255917 0.1794309 0.9836905 -0.02786326 0.1819087 0.9829207 -0.02440673 0.1826071 0.9828831 -0.02867221 0.203968 0.9785576 -0.02867227 0.203968 0.9785576 -0.009201467 0.1591337 0.9872142 -0.01938992 0.1677069 0.9856461 0.006505787 0.1680907 0.9857501 -0.00813663 0.1771737 0.9841459 0.006415188 0.1795516 0.9837276 -0.006413578 0.1963067 0.9805216 0.006262779 0.1985304 0.9800747 -0.01244467 0.22121 0.9751468 0.006047129 0.2247881 0.9743888 -0.01142919 0.2316786 0.9727252 0.01946896 0.2631797 0.9645504 0.01946896 0.2631797 0.9645504 -0.006301105 -0.1938007 0.9810208 0.01303488 -0.5122163 0.8587576 -0.003990054 -0.1737043 0.9847898 -0.003989875 -0.1737048 0.9847897 -0.004558026 -0.1704169 0.9853615 0.008521616 -0.2101808 0.9776254 0.005277872 -0.3898841 0.9208489 0.04428231 -0.4997816 0.8650187 0.03143036 -0.5042481 0.8629866 0.04212647 -0.4129018 0.9098008 -0.005829751 -0.2505711 0.9680807 -0.01656991 -0.2397586 0.9706911 -0.005938947 -0.2377017 0.9713201 -0.01729929 -0.2076125 0.9780582 -0.00620526 -0.2056036 0.9786157 -0.01807171 -0.1723719 0.9848661 -0.003574013 -0.1933429 0.9811248 -0.03639042 -0.4733345 0.8801308 -0.01078075 -0.538498 0.8425578 -0.04246526 -0.5466252 0.8363 -0.01793414 -0.6005534 0.7993835 -0.05504316 -0.5680257 0.8211682 -0.0888552 -0.5341323 0.8407185 -0.04761588 -0.5265432 0.848814 -0.07186079 -0.461608 0.8841686 -0.03505098 -0.4548765 0.8898646 -0.05568069 -0.3915343 0.9184773 -0.003298223 -0.3306953 0.9437318 -0.02539527 -0.333052 0.9425664 -0.003013193 -0.3288487 0.9443778 -0.01976007 -0.29877 0.9541205 0.002320826 -0.2940729 0.9557802 -0.01953881 -0.2974209 0.9545466 -0.02014523 -0.2978494 0.9544003 -0.0379852 -0.286004 0.9574753 -0.01984441 -0.282306 0.9591192 -0.0372743 -0.2567781 0.9657514 -0.03727447 -0.2567781 0.9657513 0.1055946 -0.7610535 0.640037 0.0730676 -0.6128494 -0.7868144 -0.005809307 -0.3804624 0.9247782 0.001727759 -0.2160756 0.9763752 -0.003800392 -0.1826744 0.9831662 -0.06837606 -0.04502141 0.9966433 -0.06837511 -0.04501521 0.9966436 -0.311907 -0.8714544 0.3785251 -0.3119064 -0.8714454 0.3785464 -0.1906218 -0.9309006 0.3115882 -0.1341009 -0.8272898 0.545535 -0.09801995 -0.2136504 0.9719802 -0.09802621 -0.2137293 0.9719623 -0.1906197 -0.9308891 0.3116243 -0.19062 -0.9308948 0.3116072 -0.01963526 0.1538019 0.9879066 -0.1450924 -0.7581483 -0.6357352 -0.2087404 -0.7233973 -0.6581214 -0.3282942 -0.9445555 -0.006140232 -0.3180304 -0.9480798 -0.001168727 -0.3485288 -0.8676238 0.354622 -0.3552206 -0.8856277 0.2991354 -0.3552216 -0.8856274 0.2991348 -0.3429189 -0.8915727 0.295812 -0.3429065 -0.8915754 0.2958182 -0.3503886 -0.8925473 0.2838786 -0.3459234 -0.8387144 0.4205893 -0.3365806 -0.8403049 0.4249722 -0.3219816 -0.7811096 0.5349726 -0.2934954 -0.783926 0.5471019 -0.2746317 -0.7064557 0.652302 -0.2072524 -0.7071121 0.6760467 -0.2136426 -0.9652298 -0.1506261 -0.1725276 -0.976592 -0.1284614 -0.07513111 -0.8536971 0.5153219 0.1308478 -0.7529357 0.6449549 0.0889551 -0.8612779 0.5002872 0.02482587 -0.84551 0.5333822 0.02309453 -0.8730725 0.4870431 0.04960972 -0.9470929 0.3171026 -0.05591988 -0.8516091 0.5211861 -0.06805127 -0.8771783 0.4753181 -0.06805562 -0.8771788 0.4753166 -0.2687124 -0.9176209 0.2928576 0.08593803 -0.8319178 0.5482037 0.1167871 -0.7575314 0.6422671 0.1167855 -0.7575376 0.64226 -0.08712697 -0.4129638 0.9065705 -0.1073569 -0.4162799 0.9028763 -0.05158817 -0.3394423 0.9392112 0.04653525 -0.6110657 0.7902109 0.08038508 -0.6008725 0.7952926 -0.02786642 -0.6823424 0.7305015 -0.01589888 -0.6855764 0.727827 -0.02865362 -0.6885935 0.7245814 -0.1394276 -0.6610736 0.7372527 -0.1184137 -0.6572513 0.744311 -0.216224 -0.6244873 0.7505084 -0.18405 -0.6206205 0.7622045 -0.194378 -0.5838511 0.7882482 -0.1882638 -0.5831817 0.7902253 -0.03212201 -0.3736065 0.927031 -0.0321176 -0.3736057 0.9270315 -0.07868444 -0.385559 0.9193221 -0.0745334 -0.4730887 0.8778564 -0.07453334 -0.4730887 0.8778564 0.003668069 -0.2157605 0.9764394 0.003668069 -0.2157606 0.9764394 -0.03605169 -0.2227206 0.9742155 -0.01638126 -0.2479017 0.9686467 -0.052087 -0.2544124 0.9656921 -0.00626266 -0.1830636 0.9830811 -0.00559014 -0.1850634 0.9827107 -0.01691085 -0.1868512 0.9822427 -0.003526449 -0.1955721 0.980683 -0.02407115 -0.1989021 0.9797237 -0.002846837 -0.2273238 0.973815 -0.01703286 -0.2194797 0.9754683 0.07764178 -0.9366627 -0.3415182 0.09245359 -0.843218 0.5295619 0.05344629 -0.6129031 0.7883485 0.07306689 -0.6128497 -0.7868142 0.08109313 -0.9364677 -0.341251 0.07382631 -0.6112278 -0.7880039 -0.002930641 -0.2168328 0.9762043 0.05348426 -0.6131528 0.7881517 0.02328169 -0.4093146 0.9120963 0.0185585 -0.3767373 0.9261342 0.02262008 -0.4093465 0.9120987 0.02262264 -0.4093665 0.9120896 0.06446546 -0.4628219 -0.8841041 0.06446629 -0.4628393 -0.884095 0.07754755 -0.9390395 -0.3349496 -0.002935945 -0.216794 0.9762129 0.006004154 -0.276054 0.9611234 -0.01447445 -0.2792578 0.9601072 -0.01257145 -0.290819 0.9566954 -0.0224018 -0.2923542 0.9560477 0.09268462 -0.8444768 0.5275117 0.04409992 -0.5499798 0.8340128 0.01013344 -0.5548914 0.8318611 -0.004765987 -0.3957679 0.9183383 -0.01585781 -0.3974242 0.917498 -0.02151685 -0.3227054 0.9462548 -0.03754311 -0.3252824 0.9448714 0.07406425 -0.9392589 -0.3351225 0.07211613 -0.6113263 -0.7880859 -0.06052768 0.3200682 0.9454591 0.003208696 -0.6267032 0.7792515 -0.02036261 -0.6295348 0.7767055 -0.03033852 -0.4893255 0.8715733 -0.07418322 -0.4954091 0.8654864 -0.0519824 -0.5046958 0.8617309 0.06497961 -0.5317155 -0.8444267 0.06498044 -0.5317155 -0.8444265 0.06411135 -0.4628336 -0.8841238 0.06430017 -0.5099074 -0.8578227 0.05941104 -0.5100395 -0.8580968 -0.06642931 0.03752398 0.9970853 0.05761975 -0.1557109 -0.9861207 -0.08266121 -0.5452303 0.8342009 -0.1156642 -0.5501816 0.8269958 -0.06837475 -0.04501193 0.9966437 0.02006733 -0.8291206 0.5587096 0.06577008 -0.4614996 -0.8846991 0.06405782 -0.4615551 -0.8847959 -0.01612758 -0.6837926 0.7294981 -0.07073318 -0.6888483 0.7214463 -0.07446187 -0.567245 0.8201759 -0.08333879 -0.5687469 0.8182798 0.1294949 -0.9883372 0.08012849 0.09517192 -0.8456635 0.5251626 -3.07966e-4 -0.2475813 0.9688671 0.1309166 -0.9061571 -0.4021695 0.08216571 -0.9100174 -0.406346 0.01191657 -0.5740529 0.8187315 -0.0013327 -0.5758193 0.8175759 -0.01308864 -0.4379647 0.8988969 -0.03280854 -0.440882 0.8969652 -0.03720331 -0.3650199 0.9302561 -0.07545214 -0.3711943 0.9254847 -0.05280214 -0.5735507 0.8174666 -0.0833913 -0.5790086 0.8110456 -0.08528202 -0.5568466 0.8262257 -0.1143143 -0.5616024 0.8194724 -0.113507 -0.480601 0.8695625 -0.1605914 -0.4866217 0.8587256 -0.1719197 -0.5793995 0.7967057 -0.2322766 -0.5837919 0.7779682 -0.2511745 -0.6814484 0.687415 -0.2831515 -0.6815207 0.6747997 0.04311549 -0.4514321 0.8912632 0.07781559 -0.6009435 0.7954946 0.1105166 -0.5335367 0.8385252 0.1105167 -0.5335358 0.8385258 0.1105165 -0.5335305 0.8385292 0.1198858 -0.7188065 0.6847953 0.04708629 -0.7404916 0.6704141 0.05786138 -0.7567312 0.6511604 -0.04472041 -0.7795611 0.6247277 -0.04481464 -0.779431 0.6248831 -0.1880804 -0.7963509 0.5748486 -0.2024723 -0.7766566 0.5964977 -0.2707443 -0.7783426 0.5664629 -0.2951632 -0.7434319 0.6001563 -0.2478203 -0.7431552 0.6215348 -0.2593424 -0.6642143 0.701114 -0.2157685 -0.6619721 0.7178 -0.01575326 -0.2745441 0.9614455 -0.03775501 -0.2764153 0.9602963 -0.06985485 -0.2823672 0.9567597 -0.0383194 -0.3001959 0.9531076 -0.07820808 -0.3078454 0.9482166 -0.03906339 -0.3328612 0.9421664 -0.02565652 -0.3346117 0.9420067 -0.3234696 -0.845848 0.4241564 -0.3420663 -0.8432092 0.4147154 -0.3294201 -0.8299865 0.4501167 -0.330662 -0.8298341 0.4494864 -0.2951332 -0.7657162 0.5714673 -0.2990194 -0.7655006 0.5697335 -0.1865532 -0.4560515 0.870181 -0.1851073 -0.4803779 0.8573052 -0.1205835 -0.4720433 0.8732897 -0.1308739 -0.4008377 0.9067531 -0.0881769 -0.3940573 0.9148463 -0.09895658 -0.3518659 0.930805 -0.07160085 -0.3469317 0.9351533 -0.08000802 -0.3242002 0.942599 -0.05126225 -0.3191135 0.9463291 -0.05926746 -0.2998391 0.9521469 -0.03294283 -0.295228 0.9548587 -0.04064929 -0.2627475 0.9640081 -0.02057451 -0.259397 0.9655516 -0.02625346 -0.2362579 0.9713357 -0.01388871 -0.2342914 0.9720672 -0.01777309 -0.2251928 0.9741521 0.00282222 -0.2219342 0.9750576 0.001726806 -0.2160685 0.9763767 0.04070949 0.05372333 -0.9977257 -0.02984356 0.789478 -0.6130529 0.02678328 -0.9842007 0.1750187 -0.3435068 -0.9143429 -0.2144303 -0.1191831 -0.2058371 0.9713015 -0.2968336 -0.8762083 -0.3796695 -0.02397447 -0.387042 -0.9217504 -0.006581902 -0.2372466 -0.9714272 -0.2225802 -0.7183437 -0.6591209 -0.1167784 -0.4523368 -0.8841686 0.07753992 0.02846139 -0.9965829 0.03171694 -0.1166272 -0.9926692 0.06787866 -0.009864211 -0.9976448 0.07330936 0.0278126 -0.9969214 0.06832301 0.001040339 -0.9976627 0.1491598 0.3114288 -0.93849 0.1329262 0.3131429 -0.9403575 -0.3013883 -0.8404595 -0.4503252 -0.2125748 -0.6518216 -0.7279701 -0.2526502 -0.6411147 -0.7246654 -0.1921381 -0.9791254 0.0663048 -0.1921404 -0.9791251 0.06630444 -0.242147 -0.6272165 -0.740246 -0.1882374 -0.5198048 -0.8332884 -0.1882379 -0.5198048 -0.8332884 -0.3705687 -0.8941389 -0.2513853 -0.3347558 -0.8182178 -0.4673951 -0.3014377 -0.8325246 -0.4647991 -0.1926524 -0.5949258 -0.7803515 -0.1821326 -0.5966354 -0.7815714 -0.1102767 -0.4368041 -0.8927716 -0.1076959 -0.4368816 -0.8930487 -0.1288878 -0.4516765 -0.8828229 -0.2606546 -0.751869 -0.6056008 -0.2962831 -0.7390819 -0.604958 -0.3305722 -0.8079859 -0.4877303 -0.2822521 -0.8278564 -0.4847549 -0.07147979 -0.9601864 -0.2700606 0.1480392 -0.7049356 0.69365 0.09891414 0.09669965 -0.9903864 0.09302771 0.09575372 -0.9910485 0.0950644 0.1052867 -0.9898877 0.126473 0.3313692 -0.9349861 0.006879448 -0.2764796 -0.9609952 -0.09783214 -0.4221787 -0.9012181 -0.1999401 -0.6779953 -0.7073516 -0.04998904 -0.3032194 -0.9516088 -0.1502997 -0.5634779 -0.812344 -0.2430415 -0.7398247 -0.6273677 -0.1660405 -0.5618837 -0.810381 -0.2804585 -0.8149296 -0.5071813 -0.2169795 -0.6747304 -0.7054493 -0.2653534 -0.7804411 -0.5661265 -0.2488489 -0.7851678 -0.5670853 -0.1565247 -0.5646355 -0.8103621 0.03940773 -0.1382198 -0.9896172 0.01906746 -0.1406644 -0.9898738 -0.05247497 -0.3918823 -0.9185176 0.07942748 0.3487296 -0.9338517 0.09492325 0.2179368 -0.9713357 0.09453904 0.1932993 -0.9765744 0.09454047 0.1933419 -0.9765659 0.1074828 0.322078 -0.9405919 0.0196411 0.687951 0.7254913 0.09454005 0.1933196 -0.9765704 0.09453797 0.1932877 -0.9765768 -0.1490279 -0.3123193 0.9382149 -0.1451662 -0.3134213 0.9384529 -0.1142016 -0.2019709 0.9727106 -0.2109901 -0.8307719 -0.515074 -0.2421613 -0.5493032 0.7997648 -0.2693862 -0.8227455 -0.5005205 -0.3221819 -0.9220116 -0.2146936 -0.3387943 -0.9154365 -0.2172424 -0.119182 -0.2058374 0.9713016 -0.146855 -0.3196916 0.9360721 -0.1547735 -0.3174161 0.9355705 -0.2719761 -0.9589368 0.08043134 -0.1771007 -0.7521477 0.6347512 0.05621796 -0.04613912 -0.9973518 -0.09961992 -0.6625954 -0.7423229 -0.1463146 -0.6572341 -0.7393479 -0.05801296 -0.3880694 -0.9198025 -0.1460154 -0.6626687 -0.7345404 -0.1069365 -0.5453125 -0.8313837 -0.2912345 -0.8704533 -0.3968545 -0.309331 -0.8638954 -0.397491 -0.3254703 -0.8945752 -0.3062747 -0.3290053 -0.8931436 -0.3066758 -0.2870754 -0.8126868 -0.5070779 -0.3052155 -0.8502507 -0.4288558 -0.2489923 -0.7382255 -0.6269178 -0.1929632 -0.9751278 -0.1090449 -0.1117947 -0.9893565 -0.09314298 -0.1443075 -0.9571154 -0.2512082 -0.3720246 -0.8961494 -0.2418963 -0.3123826 -0.9225205 -0.2266561 -0.28649 -0.9294961 0.2322938 -0.1508874 -0.9536921 0.2602005 -0.2261098 -0.9127417 -0.3402601 -0.2312839 -0.9114502 -0.3402447 -0.3438511 -0.8725641 -0.3469845 -0.3845976 -0.920252 -0.0722571 -0.3624313 -0.9297856 -0.06436204 -0.3599534 -0.9301651 -0.07229447 0.06832307 0.001040339 -0.9976627 0.03411561 -0.092444 -0.9951333 0.006436347 -0.1641391 -0.9864162 0.02328771 -0.1176757 -0.992779 -0.0232442 -0.2373613 -0.9711433 -0.01917457 -0.2370212 -0.9713153 0.006305158 -0.1682943 -0.9857167 0.01049548 -0.1678293 -0.9857602 -0.03496021 -0.3023245 -0.9525637 0.02865666 -0.1089513 -0.993634 -0.08558177 -0.4221991 -0.9024543 -0.07953953 -0.4056548 -0.9105589 -0.1411836 -0.5660485 -0.8121922 -0.1450876 -0.5762585 -0.8042859 -0.2044065 -0.7221946 -0.6607972 -0.201897 -0.7160319 -0.6682335 -0.2502748 -0.8284744 -0.5009917 -0.2396605 -0.8043004 -0.5437497 -0.2764286 -0.8832582 -0.3787373 -0.3047563 -0.9344369 -0.1842585 -0.3257032 -0.9266592 -0.1876705 -0.3393657 -0.9398884 -0.03795814 -0.3561186 -0.933479 -0.04238522 -0.3621547 -0.9289658 0.07659238 -0.3606027 -0.9325882 -0.01564961 -0.3633625 -0.9315007 -0.01655781 -0.3475364 -0.9126298 -0.2152334 -0.3441089 -0.9064256 -0.2449116 -0.3108344 -0.8480697 -0.4291384 -0.2572981 -0.7354344 -0.6268445 -0.2488276 -0.73787 -0.6274014 -0.1875868 -0.6090828 -0.7706033 -0.1847153 -0.6095296 -0.7709435 -0.0942794 -0.404293 -0.9097574 -0.0869261 -0.4042753 -0.9104973 -0.2151108 -0.9081501 -0.3591529 -0.2138028 -0.933791 -0.2869194 -0.2073006 -0.9356186 -0.2857348 0.1480388 -0.7049356 0.69365 -0.2017573 -0.7862465 -0.5840466 -0.1499605 -0.9457431 -0.2882392 -0.2115772 -0.9331772 -0.2905434 -0.1973161 -0.9669015 -0.1617648 -0.3144344 -0.9305422 -0.1876755 -0.275136 -0.9089808 0.3131359 -0.3438478 -0.8725658 -0.3469838 0.006875276 -0.2764975 -0.96099 0.001518368 -0.2786934 -0.960379 0.06975001 0.0144267 -0.9974601 0.03777587 -0.08740723 -0.9954562 0.03481733 -0.08779674 -0.9955297 -0.01365965 -0.2378582 -0.9712039 -0.07169896 -0.4055718 -0.9112468 -0.06711912 -0.3921819 -0.9174358 -0.1338157 -0.5773 -0.8054925 -0.1219826 -0.5443245 -0.8299585 -0.187297 -0.718909 -0.669395 -0.1650059 -0.6600047 -0.7329167 -0.2236363 -0.8085454 -0.5442802 -0.2307171 -0.8256012 -0.5149294 -0.2415434 -0.6095721 0.7550356 -0.1197801 -0.2003136 0.9723821 -0.1027421 -0.1457613 0.9839705 -0.2350111 -0.5566865 0.7967873 -0.2352927 -0.5566889 0.7967025 -0.228398 -0.5580438 0.7977603 -0.3610311 -0.9321193 0.02846002 -0.3629519 -0.9261026 0.1029557 -0.3629531 -0.9261022 0.1029555 0.02081137 0.212627 -0.9769117 0.005200982 0.210166 -0.9776519 0.005333244 0.2092304 -0.9778518 0.00533533 0.2092151 -0.977855 0.04487329 -0.08064633 -0.9957321 0.005154788 0.2090772 -0.9778856 -0.02188235 0.3951528 -0.9183548 -0.02205699 0.3963248 -0.9178454 -0.07156568 0.7108967 -0.6996459 0.05582886 -0.08067309 -0.9951758 -0.00383383 0.7925404 -0.6098073 0.06374043 -0.404195 -0.9124492 -0.004508912 0.8510403 -0.5250809 -0.007650911 0.8505316 -0.5258682 0.0378192 0.1004377 -0.9942242 0.002622067 0.4651196 -0.8852439 0.0034101 0.4652593 -0.8851677 -0.003396451 0.5365228 -0.8438789 -0.03989464 0.5296793 -0.8472593 0.006548881 0.2093861 -0.9778111 0.07942676 0.3487299 -0.9338516 0.07234483 0.2507795 -0.9653372 0.07661241 0.2516003 -0.9647942 0.06955063 0.1133175 -0.9911216 0.02869993 0.4731485 -0.8805151 0.009580135 0.1797889 -0.9836585 0.005323767 0.2091814 -0.9778624 0.005320549 0.2092049 -0.9778574 0.03195267 0.4738356 -0.8800334 0.04480534 0.2379729 -0.9702378 0.04503285 0.05433839 -0.9975066 0.01515811 0.1806381 -0.9834329 0.01852017 0.119944 -0.992608 0.02149671 0.1203715 -0.9924961 0.02171158 0.201426 -0.9792631 0.03892058 0.1736528 -0.9840376 0.03892099 0.1736529 -0.9840375 0.01497435 -0.9849146 0.1723916 -0.07730889 -0.9597987 -0.2698327 -0.08780318 -0.9582092 -0.2722606 -0.2151115 -0.9081498 -0.3591529 -0.02700626 -0.9583514 0.2843117 -0.1017252 -0.994236 -0.03386175 -0.01316505 -0.9997637 -0.0172916 -0.06509417 -0.967489 -0.2443925 -0.0714733 -0.9601939 -0.2700353 -0.07149207 -0.960171 -0.270112 0.07335692 -0.01367777 -0.9972119 0.07335853 -0.01367777 -0.9972118 0.09778279 0.0740149 -0.9924517 0.09945255 0.0739212 -0.9922927 0.1530438 0.3755965 -0.9140595 0.09041786 0.1453192 -0.9852446 0.08744078 0.1451043 -0.9855449 0.09720051 0.2003505 -0.9748907 0.03963071 0.193062 -0.9803858 0.1009684 0.2317681 -0.9675169 0.07855004 0.3500333 -0.933438 0.0666061 0.2516958 -0.9655117 0.07003676 0.2523621 -0.9650949 0.0662648 0.2108663 -0.9752663 0.06626349 0.210866 -0.9752664 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -1 0 0 -1 0 0 -0.5000003 -0.8660252 0 -0.5000003 -0.8660252 0 0.5000003 -0.8660252 0 0.5000003 -0.8660252 0 1 0 0 1 0 0 0.5000003 0.8660252 0 0.5000003 0.8660252 0 -0.5000003 0.8660252 0 -0.5000003 0.8660252 0 0.9659276 0.2588127 0 0.9659276 -0.2588127 0 0.9659276 -0.2588127 0 0.7071092 -0.7071043 0 0.7071092 -0.7071043 0 0.258816 -0.9659267 0 0.258816 -0.9659267 0 -0.258816 -0.9659267 0 -0.258816 -0.9659267 0 -0.7071092 -0.7071043 0 -0.7071092 -0.7071043 0 -0.9659276 -0.2588127 0 -0.9659276 -0.2588127 0 -0.9659276 0.2588127 0 -0.9659276 0.2588127 0 -0.7071092 0.7071043 0 -0.7071092 0.7071043 0 -0.258816 0.9659267 0 -0.258816 0.9659267 0 0.258816 0.9659267 0 0.258816 0.9659267 0 0.7071092 0.7071043 0 0.7071092 0.7071043 0 0.9659276 0.2588127 0 -0.9807404 -0.001458048 -0.1953107 -0.8310227 0.004415452 -0.5562209 -0.9807735 0 -0.1951498 -0.8969338 -4.96507e-4 -0.4421645 -0.70701 -4.91155e-4 -0.7072035 -0.8313139 9.78775e-4 -0.5558024 -0.7074483 9.97704e-4 -0.7067644 -0.5555462 -4.97877e-4 -0.8314855 -0.2583617 -4.71184e-4 -0.9660482 -0.5553057 7.01901e-4 -0.831646 -0.2592327 7.38623e-4 -0.9658146 -0.1951038 0 -0.9807826 -0.4903966 -0.8493912 -0.1950537 -0.416216 -0.7199037 -0.5554304 -0.448448 -0.7767359 -0.4422397 -0.490387 -0.8493765 -0.1951414 -0.1310851 -0.2211937 -0.9663799 -0.3528591 -0.6131634 -0.7067681 -0.3528546 -0.6131555 -0.7067772 -0.2770363 -0.4812461 -0.8316568 -0.09670197 -0.1689662 -0.9808665 -0.1294206 -0.2241632 -0.9659199 0.4903879 -0.849376 -0.1951416 0.4903956 -0.8493914 -0.195055 0.415758 -0.7201151 -0.5554993 0.4157373 -0.7200776 -0.5555634 0.2777494 -0.4810757 -0.8315177 0.2777843 -0.4811379 -0.8314699 0.09755605 -0.1689725 -0.9807808 0.09754467 -0.1689523 -0.9807855 0.9807735 0 -0.1951498 0.9807735 0 -0.1951498 0.8315983 0 -0.5553776 0.8315982 0 -0.5553776 0.5554269 0 -0.8315654 0.5554269 0 -0.8315654 0.1951038 0 -0.9807826 0.1951038 0 -0.9807826 0.4903966 0.8493912 -0.1950537 0.490387 0.8493766 -0.195141 0.4157363 0.7200776 -0.5555643 0.4157586 0.7201144 -0.5554997 0.2777853 0.4811378 -0.8314696 0.2777484 0.4810759 -0.8315178 0.09754437 0.1689523 -0.9807855 0.09755611 0.1689722 -0.980781 -0.4903879 0.849376 -0.1951416 -0.4903956 0.8493914 -0.195055 -0.4158191 0.7202209 -0.5553164 -0.4157373 0.7200769 -0.5555643 -0.4157283 0.7200618 -0.5555906 -0.2777274 0.4810375 -0.831547 -0.2777844 0.4811384 -0.8314697 -0.2777929 0.4811529 -0.8314584 -0.09755605 0.1689725 -0.9807808 -0.09754467 0.1689523 -0.9807855 -0.02678352 0.9842006 0.1750199 0.3435139 0.9143522 -0.2143791 0.1191805 0.2058292 0.9713035 0.296738 0.8760151 -0.3801895 0.02393811 0.3869064 -0.9218083 0.006581902 0.2372466 -0.9714272 0.2225794 0.7183438 -0.659121 0.2065147 0.9172614 -0.3405629 -0.09302765 -0.09575372 -0.9910485 -0.008627355 0.1585039 -0.9873207 0.252639 0.6410873 -0.7246935 0.2125629 0.6517939 -0.7279985 0.2065122 0.917262 -0.3405629 0.2376044 0.6179627 -0.7494439 0.2337517 0.6029865 -0.7627369 0.2300781 0.5988427 -0.7671059 0.1061604 0.2812594 -0.9537416 0.1055302 0.2812811 -0.9538052 0.2307081 0.6921485 -0.683889 -0.1046186 -0.1052886 -0.9889233 -0.1046183 -0.1052885 -0.9889233 0.3705719 0.8941448 -0.2513592 0.3347359 0.8181739 -0.4674863 0.3014166 0.8324798 -0.4648928 0.19263 0.5948721 -0.7803978 0.1821101 0.596584 -0.7816159 0.1102533 0.4367488 -0.8928017 0.1076725 0.4368261 -0.8930788 0.0232445 0.2373608 -0.9711434 0.01917421 0.2370212 -0.9713153 -0.09891432 -0.09669971 -0.9903863 -0.06787854 0.009864509 -0.9976449 -0.031717 0.1166274 -0.9926691 -0.02328753 0.1176757 -0.992779 -0.006431341 0.1641526 -0.986414 0.1167942 0.4523749 -0.8841471 0.1289038 0.4517158 -0.8828004 0.2606792 0.7519237 -0.6055223 0.2963077 0.7391342 -0.6048821 0.3305669 0.8079776 -0.4877477 0.2870603 0.8259852 -0.4851234 0.0714879 0.9601761 -0.2700951 -0.04094195 0.9721863 0.2306031 -0.006879031 0.2764816 -0.9609946 0.09778058 0.4220489 -0.9012843 0.1998307 0.6777388 -0.7076284 0.05001044 0.3032755 -0.9515897 0.1502817 0.5634308 -0.81238 0.2430641 0.7398767 -0.6272976 0.1660182 0.5618321 -0.8104213 0.2803992 0.8148093 -0.5074072 0.2168651 0.6744716 -0.7057319 0.2653845 0.7805052 -0.5660235 0.2488754 0.785229 -0.5669891 0.1565449 0.5646871 -0.8103222 -0.03941208 0.1382021 -0.9896197 -0.01907318 0.1406462 -0.9898762 0.0524078 0.3916605 -0.918616 -0.07942306 -0.3485727 -0.9339107 -0.09452575 -0.1932329 -0.9765889 -0.09490966 -0.2178481 -0.971357 -0.06837236 -0.04500025 -0.9966446 -0.09452581 -0.1932345 -0.9765886 -0.09452539 -0.1932257 -0.9765904 -0.09452569 -0.1932303 -0.9765894 0.1490736 0.3124998 0.9381477 0.1452144 0.3136012 0.9383853 0.1142011 0.201971 0.9727106 0.2110601 0.8309566 -0.5147473 0.2421013 0.5491189 0.7999097 0.2693853 0.8227459 -0.5005206 0.3222538 0.9221211 -0.2141155 0.3388671 0.9155458 -0.2166678 0.11918 0.2058293 0.9713034 0.146855 0.3196916 0.9360721 0.1547735 0.3174161 0.9355705 0.2719761 0.9589368 0.08043134 0.1771007 0.7521477 0.6347512 -0.05621844 0.04613649 -0.9973521 0.09976208 0.6630842 -0.7418673 0.1464795 0.6577121 -0.7388901 0.05797028 0.3879336 -0.9198625 0.145884 0.6622838 -0.7349135 0.1070429 0.5456393 -0.8311556 0.2912335 0.8704537 -0.3968544 0.309331 0.8638954 -0.397491 0.3254703 0.8945752 -0.3062747 0.3290053 0.8931436 -0.3066758 0.2870167 0.8125667 -0.5073035 0.3052138 0.8502514 -0.4288557 0.2490155 0.7382771 -0.6268478 0.1929623 0.9751292 -0.1090348 0.111794 0.9893571 -0.09313708 0.1443082 0.9571152 -0.2512083 0.3720298 0.896158 -0.2418567 0.312384 0.9225285 -0.2266219 0.3117534 0.9149762 -0.2561803 0.1993135 0.9496599 -0.2417025 0.1804301 0.9792919 -0.09182745 0.1776739 0.9798216 -0.09154963 0.3438471 0.8725585 -0.3470028 0.3845993 0.9202527 -0.07223713 0.3624429 0.9297822 -0.06434506 0.3599515 0.9301638 -0.07232034 0.2151108 0.9081477 -0.3591587 0.2138026 0.9337932 -0.2869123 0.2072977 0.9356215 -0.2857274 -0.04094308 0.9721862 0.2306029 0.2107537 0.7668501 -0.6062375 0.1054791 0.9942271 -0.01966536 0.1793599 0.9833557 -0.02901452 0.1973169 0.9668996 -0.1617753 0.3144329 0.9305396 -0.1876917 0.2751312 0.9089748 0.3131577 0.3438475 0.8725582 -0.3470028 -0.006880342 0.2764761 -0.9609962 -0.001523673 0.2786718 -0.9603853 -0.06975007 -0.01442712 -0.9974601 -0.03777348 0.08741545 -0.9954556 -0.03481495 0.08780503 -0.9955292 0.01365906 0.2378582 -0.9712039 0.07173162 0.405667 -0.9112019 0.06704342 0.3919603 -0.917536 0.133742 0.5770938 -0.8056524 0.1220992 0.544649 -0.8297283 0.1875538 0.7195695 -0.668613 0.1648665 0.659624 -0.7332905 0.2235133 0.8082385 -0.5447866 0.2307962 0.8257818 -0.5146044 0.2415641 0.6096458 0.7549694 0.1197801 0.2003136 0.9723823 0.1027397 0.1457538 0.9839718 0.2350121 0.5566877 0.7967861 0.2350595 0.5566872 0.7967725 0.2283812 0.557999 0.7977964 0.361031 0.9321199 0.02844238 0.3629525 0.9261024 0.1029556 0.3629525 0.9261023 0.1029557 -0.005321502 -0.2091969 -0.9778591 -0.005320429 -0.2092049 -0.9778574 -0.005199909 -0.2101733 -0.9776503 -0.005333781 -0.2092266 -0.9778527 -0.00534141 -0.2091708 -0.9778645 0.03989243 -0.5296665 -0.8472674 -0.006549 -0.2093861 -0.9778111 -0.04487174 0.08063453 -0.9957333 -0.005119323 -0.2093275 -0.9778322 0.02188241 -0.3951528 -0.9183548 0.02217018 -0.397084 -0.9175145 0.07156628 -0.7108966 -0.6996459 -0.03781944 -0.1004341 -0.9942247 -0.002623438 -0.4651036 -0.8852524 0.02987611 -0.7897558 -0.6126934 -0.07942271 -0.3485728 -0.9339107 -0.0705198 -0.2266445 -0.9714213 -0.07580846 -0.2275883 -0.9708021 -0.06975263 -0.1112375 -0.9913429 -0.0286991 -0.4731464 -0.8805162 -0.03195297 -0.4738335 -0.8800345 0.004511654 -0.8510627 -0.5250446 0.00765264 -0.8505539 -0.5258322 -0.05582976 0.08070224 -0.9951735 0.003861308 -0.7928012 -0.6094682 -0.06373983 0.4041829 -0.9124547 -0.00958532 -0.179753 -0.9836651 -0.01919031 -0.1154201 -0.9931314 -0.01570177 -0.1807265 -0.983408 0.003396689 -0.5365213 -0.8438799 -0.003411293 -0.4652434 -0.8851763 -0.02081108 -0.2126323 -0.9769106 -0.02208292 -0.1967895 -0.980197 -0.0223912 -0.1158751 -0.9930114 -0.04454827 -0.2485804 -0.9675862 -0.04405903 -0.2537274 -0.9662719 -0.03441607 -0.166991 -0.9853575 -0.03354179 -0.1668472 -0.9854121 -0.03289288 -0.1913295 -0.9809745 -0.03289288 -0.1913296 -0.9809746 -0.01497429 0.9849147 0.1723916 0.07730883 0.9597987 -0.2698327 0.08780318 0.9582092 -0.2722606 0.2151131 0.9081472 -0.3591589 0.02700626 0.9583514 0.2843117 0.1017265 0.9942358 -0.03386735 0.01316523 0.9997638 -0.01729232 0.06509405 0.9674891 -0.2443925 0.07147854 0.9601876 -0.2700567 0.07148808 0.9601759 -0.2700957 -0.07682371 0.002208948 -0.9970422 -0.076824 0.002208948 -0.9970422 -0.1050722 -0.09558796 -0.9898599 -0.1073207 -0.09556311 -0.9896211 -0.1481103 -0.3513567 -0.9244522 -0.09063899 -0.1200339 -0.9886234 -0.08438283 -0.119799 -0.9892057 -0.1105927 -0.2619833 -0.9587147 -0.1105935 -0.2619835 -0.9587146 0.03497928 0.302381 -0.9525452 -0.02865797 0.1089466 -0.9936344 0.08553171 0.4220649 -0.9025218 0.07957369 0.4057503 -0.9105135 0.1412047 0.5661085 -0.8121468 0.1450051 0.5760471 -0.8044522 0.2044075 0.7221942 -0.6607974 0.202174 0.7167104 -0.6674217 0.2502707 0.8284738 -0.5009948 0.2395263 0.8039983 -0.5442553 0.2763304 0.8830667 -0.3792555 0.304796 0.9345003 -0.1838704 0.3257483 0.9267184 -0.1872996 0.33933 0.9398782 -0.03852641 0.3560772 0.9334686 -0.04295796 0.3621557 0.9289626 0.07662791 0.3606043 0.9325879 -0.01563495 0.3633632 0.9315007 -0.01654332 0.3475426 0.9126396 -0.2151817 0.3441126 0.9064313 -0.2448855 0.3108344 0.8480697 -0.4291384 0.2572981 0.7354344 -0.6268445 0.2488268 0.7378703 -0.6274015 0.1876032 0.6091201 -0.7705698 0.1847305 0.6095676 -0.7709099 0.0942974 0.4043384 -0.9097355 0.08694404 0.4043195 -0.9104759 -0.006310284 0.1682808 -0.985719 -0.01049983 0.1678162 -0.9857624 -0.07753992 -0.02846127 -0.9965829 -0.0733093 -0.0278126 -0.9969213 -0.09506452 -0.1052877 -0.9898874 -0.126473 -0.3313692 -0.9349861 -0.1074828 -0.3220781 -0.940592 -0.01977747 -0.6886972 0.7247794 -0.04442995 -0.2902378 -0.9559226 -0.07512873 -0.2977294 -0.9516895 -0.06726843 -0.2267318 -0.9716314 -0.07028013 -0.2272708 -0.9712923 -0.06683093 -0.1926862 -0.978982 -0.06683081 -0.1926862 -0.978982 -0.1055951 0.7610533 0.6400371 0.04816412 0.9897948 -0.1341135 0.02240169 0.2923539 0.9560478 5.79794e-4 0.2122493 0.9772154 0.002893507 0.184805 0.9827709 0.09683418 0.2067124 0.973598 0.09683215 0.2066974 0.9736015 0.09683573 0.2067253 0.9735952 0.09683537 0.2067223 0.9735959 -0.04150503 0.2009921 -0.9787131 0.09244215 0.1811159 0.9791075 -0.05381512 0.2166155 -0.9747726 0.3119119 0.8714711 0.3784825 0.311912 0.871472 0.3784804 0.1906219 0.9309257 0.3115132 0.1906184 0.9309069 0.3115716 0.1906192 0.9309195 0.3115335 0.01963627 -0.1537984 0.9879071 0.145085 0.7581253 -0.6357645 0.2087305 0.723372 -0.6581524 0.3282935 0.9445556 -0.006170868 0.3180237 0.948082 -0.001195251 0.3485267 0.8676162 0.3546426 0.3552212 0.8856275 0.2991351 0.3552211 0.8856276 0.2991351 -0.05381584 0.2166092 -0.9747739 -0.0538156 0.2166092 -0.974774 -0.05454289 0.2018479 -0.9778969 0.07070595 0.5880726 0.8057116 0.1472908 0.596177 0.7892265 0.1305685 0.9857792 -0.105789 0.2136393 0.9652261 -0.1506547 0.2072483 0.7070892 0.6760717 0.2746257 0.7064335 0.6523284 0.2934969 0.7839347 0.5470888 0.3219841 0.7811177 0.5349593 0.3365811 0.8403047 0.4249719 0.3459228 0.8387145 0.4205894 0.350388 0.8925452 0.2838861 0.3429191 0.8915751 0.2958046 0.3429179 0.8915754 0.2958052 0.07513099 0.8536967 0.5153225 -0.1308465 0.7529394 0.6449507 -0.0889551 0.8612779 0.5002872 -0.02482604 0.845507 0.5333869 -0.02309453 0.8730725 0.4870431 -0.04960972 0.9470929 0.3171026 0.05592006 0.8516089 0.5211864 0.06805104 0.8771782 0.4753181 0.06805491 0.8771786 0.4753169 0.2687119 0.9176214 0.2928565 -0.08593958 0.8319145 0.5482085 -0.1167871 0.7575314 0.6422671 -0.1167855 0.7575376 0.64226 0.07849353 0.3102712 0.947402 0.03888392 0.3354438 0.9412573 0.02313911 0.3328693 0.942689 0.05066132 0.3381424 0.9397304 0.1073563 0.4162799 0.9028764 0.08712708 0.4129638 0.9065705 0.1882638 0.5831813 0.7902256 0.1943783 0.5838507 0.7882484 -0.04343867 0.61578 0.7867199 -0.07646083 0.6191545 0.781538 0.06887799 0.6780595 0.7317726 0.01788502 0.6924641 0.7212307 0.07294046 0.7044751 0.7059706 0.1469856 0.6828957 0.7155758 0.06754171 0.6692942 0.7399213 0.2241443 0.6468884 0.7288997 0.1093268 0.6160627 0.7800733 0.1822015 0.6269218 0.7574772 0.03145492 0.3729733 0.9273087 0.03145498 0.3729734 0.9273087 0.09437131 0.436375 0.8948022 0.0804004 0.4938821 0.8658038 0.08040034 0.4938821 0.8658038 0.003551423 0.184911 0.9827488 0.003372192 0.1854437 0.9826491 0.01686519 0.1875764 0.9821052 0.001437008 0.2335973 0.9723324 -0.07763427 0.9368181 -0.3410936 -0.06517666 0.6836361 0.726907 -0.1288225 0.991538 -0.01603353 -0.1071951 0.9226682 0.3703952 -0.1071404 0.9224136 0.3710447 -0.07307136 0.612957 -0.7867302 -0.08108884 0.9366237 -0.3408235 -0.07381802 0.611041 -0.7881496 -0.06446528 0.4628058 -0.8841127 -0.06446546 0.4628089 -0.884111 -0.07754325 0.939141 -0.3346657 -0.02686661 0.4333228 0.9008383 -0.01863014 0.3767247 0.926138 0.005809009 0.3804627 0.924778 0.01447409 0.27926 0.9601064 0.01257145 0.2908188 0.9566955 -0.02572029 0.4334551 0.900808 -0.008875191 0.3061242 0.9519503 -0.004006564 0.276374 0.9610418 -0.001838386 0.2499822 0.9682487 -0.001838922 0.2499861 0.9682476 -0.06521522 0.6838728 0.7266807 -0.04388093 0.5499607 0.834037 -0.0101282 0.5548308 0.8319016 0.004766583 0.3957556 0.9183435 0.01585865 0.3974118 0.9175033 0.02151674 0.3227061 0.9462547 0.03754323 0.3252835 0.9448711 -0.02004212 0.828911 0.5590215 -0.06576395 0.4612815 -0.8848132 -0.06405609 0.4613389 -0.8849086 -0.06411123 0.4628174 -0.8841322 -0.06430053 0.5101197 -0.8576964 -0.05940455 0.5102513 -0.8579713 0.01612824 0.6837903 0.7295002 0.07073378 0.6888365 0.7214576 0.06642949 -0.03752273 0.9970853 -0.05762022 0.1557041 -0.9861217 0.05198365 0.5046693 0.8617463 -0.06498056 0.5316746 -0.8444523 -0.0649802 0.5316747 -0.8444523 -4.28922e-4 0.9930897 -0.1173567 0.07571899 0.495614 0.865236 0.03033792 0.4893372 0.8715668 0.02036708 0.6294793 0.7767502 -0.003203332 0.6266441 0.779299 0.06053167 -0.320154 0.9454297 -0.07211041 0.6111382 -0.7882323 -0.07405877 0.9393607 -0.3348386 -0.07307112 0.6129572 -0.7867301 -0.06423974 0.6838996 0.7267425 -0.1310965 0.905836 -0.4028337 -0.08216816 0.90974 -0.4069661 -0.01192289 0.5741164 0.8186869 0.001327395 0.5758802 0.8175331 0.0130878 0.4379767 0.898891 0.03280806 0.4408929 0.89696 0.03720343 0.3650199 0.9302561 0.06027197 0.3688092 0.9275489 0.05779743 0.3908753 0.9186272 0.08438694 0.3951967 0.9147122 0.08276605 0.4196125 0.903922 0.1124017 0.4243773 0.8984819 0.113507 0.480601 0.8695625 0.1605917 0.4866218 0.8587256 0.1719208 0.579406 0.7967006 0.2322779 0.5837984 0.7779629 0.2511739 0.6814454 0.6874184 0.2831509 0.6815177 0.6748031 -0.04311275 0.4514325 0.8912631 -0.07564306 0.6052228 0.7924542 -0.1105167 0.533537 0.8385252 -0.1105169 0.5335347 0.8385266 -0.1105169 0.5335348 0.8385264 -0.119886 0.7188072 0.6847946 -0.047086 0.7404928 0.6704128 -0.05786037 0.7567313 0.6511604 0.04472029 0.7795611 0.6247276 0.04481464 0.779431 0.6248831 0.1880804 0.7963509 0.5748486 0.202472 0.776657 0.5964972 0.2707443 0.7783433 0.5664622 0.2951639 0.7434318 0.6001563 0.2478207 0.7431548 0.621535 0.2593427 0.6642151 0.7011132 0.2157688 0.6619728 0.7177993 0.002642333 0.1968374 0.9804326 0.002642273 0.1968374 0.9804325 0.0232774 0.2128447 0.9768087 0.01800912 0.2170442 0.9759956 0.03615802 0.2201309 0.9748001 0.01743274 0.2440793 0.9695986 0.05212992 0.250385 0.9667418 0.01686668 0.2698695 0.9627491 0.06978154 0.279856 0.9575026 0.0159527 0.3100423 0.9505888 0.03726381 0.3024411 0.9524395 0.323471 0.8458457 0.4241598 0.3420653 0.8432072 0.4147202 0.3294209 0.8299863 0.4501162 0.330662 0.8298341 0.4494864 0.2951332 0.7657162 0.5714673 0.2990194 0.7655006 0.5697335 0.1865534 0.4560522 0.8701805 0.1851077 0.480378 0.8573052 0.1205829 0.4720432 0.8732897 0.1308735 0.400837 0.9067535 0.08817684 0.3940566 0.9148465 0.09895652 0.3518653 0.9308053 0.07160127 0.3469312 0.9351535 0.08000797 0.3242011 0.9425988 0.05126202 0.3191142 0.9463289 0.05926746 0.2998394 0.9521469 0.03294283 0.2952281 0.9548587 0.04064947 0.2627468 0.9640081 0.02057456 0.2593966 0.9655518 0.02625334 0.236258 0.9713357 0.01388871 0.2342915 0.9720672 0.01777309 0.2251929 0.9741521 0.002012252 0.2227078 0.9748831 0.003866672 0.2127729 0.977094 -0.04281896 0.412644 0.9098854 0.006322801 0.1911042 0.9815494 0.04415738 0.5069954 0.8608168 0.06786942 0.4399126 0.8954723 0.03122645 0.4327148 0.9009899 0.05133926 0.3678594 0.9284631 0.00683099 0.3534715 0.9354203 0.0228666 0.3315687 0.9431539 0.002806305 0.3275083 0.9448441 0.01668709 0.3014997 0.9533203 -0.001761138 0.2977414 0.9546449 0.01646476 0.3003963 0.9536724 0.02020853 0.3011459 0.953364 0.003127038 0.1735655 0.9848174 0.003126919 0.1735659 0.9848173 0.003693759 0.1702786 0.9853891 -0.008557021 0.2075771 0.9781812 -0.005277872 0.3898842 0.9208488 -0.03084802 0.5017706 0.8644504 -0.01273542 0.5076034 0.8614968 -0.04347145 0.5310802 0.8462057 0.04193466 0.5402323 0.8404705 0.04724311 0.5326215 0.845034 0.04117977 0.5311384 0.8462838 0.04556542 0.5210465 0.8523113 0.04650539 0.5202637 0.8527384 0.04557526 0.5211087 0.8522727 0.08539319 0.5152248 0.8527904 0.03618687 0.2808034 0.959083 0.03618693 0.2808034 0.9590829 0.01942127 0.2607684 0.965206 0.01704949 0.2616485 0.9650126 0.005734384 0.2616841 0.9651365 0.01735639 0.2476036 0.968706 0.005874037 0.2453699 0.9694117 0.01809817 0.2127826 0.9769319 0.006164252 0.2106162 0.9775494 0.01887267 0.1749094 0.9844036 0.002774477 0.1905074 0.9816818 -0.001971185 0.6759874 -0.7369106 -0.003866374 0.8909416 -0.4541015 -0.05989968 0.6809946 -0.7298344 -0.02581262 -0.07054591 -0.9971745 -0.02537947 -0.09610897 -0.9950472 -0.06959336 0.1594087 -0.9847567 -0.04582738 0.4035791 -0.9137964 -0.1301133 0.9057736 -0.4032925 -0.1355269 0.7479711 -0.6497474 -0.09512138 0.5372802 -0.8380227 -0.1322501 0.7490543 -0.6491746 -0.1321363 0.7427473 -0.6564043 -0.135527 0.7479541 -0.6497669 -0.1355266 0.7479508 -0.6497709 -0.09216636 0.3981643 -0.9126722 -0.1161937 0.4184762 -0.9007645 -0.1178553 0.4216935 -0.8990466 -0.137244 0.5207375 -0.842613 -0.07430613 0.5018596 -0.8617515 -0.09216737 0.3981657 -0.9126716 -0.09216803 0.3981642 -0.9126721 0.06011193 0.5990887 -0.7984231 6.66697e-4 0.3836479 -0.9234793 6.65503e-4 0.3836445 -0.9234806 6.65641e-4 0.3836445 -0.9234806 0.1400111 0.458046 -0.877833 0.1400135 0.4580503 -0.8778303 0.1054068 0.421301 -0.9007747 0.1054075 0.421301 -0.9007745 0.139234 0.4345339 -0.8898282 0.1234842 0.3938734 -0.9108322 0.07441502 0.4880572 -0.8696337 0.07449191 0.4880571 -0.8696272 0.1010186 0.487623 -0.8671903 0.07850211 0.4154711 -0.9062125 0.07850956 0.4154723 -0.9062114 0.01382309 0.4239253 -0.9055916 0.05380439 0.5337912 -0.8439029 0.01112794 0.537312 -0.8433102 0.01112729 0.537312 -0.8433102 -0.005069673 0.5014319 -0.8651823 0.001621127 0.4811755 -0.8766229 0.001318275 0.480282 -0.8771131 0.008473336 0.4615554 -0.887071 0.007907748 0.4054454 -0.914085 0.007903337 0.4054461 -0.9140848 -0.002316772 0.4082314 -0.9128756 0.008473217 0.4615552 -0.8870711 0.008474707 0.4615552 -0.887071 -0.07594931 0.1386196 -0.9874291 0.002208173 0.287936 -0.9576471 0.002208113 0.287936 -0.9576472 -0.03412467 0.1654448 -0.9856284 -0.03922337 0.1704204 -0.9845904 -0.03922337 0.1704204 -0.9845905 0.1162641 0.108895 -0.9872307 0.1160953 0.1088573 -0.9872548 0.1169962 0.108978 -0.9871351 -0.03758758 0.07978123 -0.9961035 -0.02771538 0.1334485 -0.9906681 -0.02773076 0.1333706 -0.9906781 -0.06959068 0.1594069 -0.9847571 -0.027731 0.1333699 -0.9906783 -0.02595347 0.1384299 -0.990032 -0.02836436 0.1383783 -0.9899732 -0.1262443 0.1121339 -0.9856411 -0.04464197 -0.1607887 -0.9859788 -0.04464215 -0.1607887 -0.9859787 -0.05166691 -0.1270766 -0.9905464 -0.03802549 -0.08954805 -0.9952564 -0.07140612 -0.1455153 -0.9867757 -0.02140021 -0.09610348 -0.9951413 -0.0268644 -0.1304644 -0.991089 -0.04464149 -0.1607881 -0.9859789 -0.02082991 -0.07055133 -0.9972907 -0.02593398 -0.09695303 -0.9949511 -0.02538007 -0.09610956 -0.9950471 -0.006950259 -0.03212851 -0.9994596 0.04532015 0.1054707 -0.9933892 -0.02032989 0.1329502 -0.9909142 -0.006948053 -0.03212618 -0.9994598 -0.02110975 -0.04454094 -0.9987845 -0.01686263 -0.04456788 -0.9988641 -0.02033919 -0.06417036 -0.9977316 -0.02581244 -0.07054579 -0.9971745 -0.03957551 0.3766486 -0.9255106 -0.03957653 0.3766484 -0.9255105 0.04714775 0.3263791 -0.9440624 -0.02033019 0.1329498 -0.9909143 -0.02032983 0.1329501 -0.9909141 -0.03957694 0.3766471 -0.925511 0.02184545 0.5111265 -0.8592278 -0.05023592 0.5797057 -0.813276 -0.01053631 0.867565 -0.497212 -0.03782933 0.7722242 -0.6342231 -0.05905127 0.7512637 -0.6573552 -0.05908513 0.8749041 -0.4806783 -0.05990082 0.6809807 -0.7298473 -0.06273072 0.8538675 -0.5166963 -0.05701744 0.8658476 -0.4970481 -0.05701315 0.8658491 -0.4970462 -0.1062807 0.8640924 -0.4919847 -0.0815795 0.9013897 -0.4252547 -0.1319163 0.8818048 -0.4527893 -0.1189435 0.9696922 -0.2134232 -0.1424997 0.5185871 -0.8430665 -0.1182497 0.6475525 -0.7527901 -0.07190412 0.6513835 -0.755334 -0.1372438 0.5207345 -0.8426148 -0.1417231 0.5068147 -0.8503255 -0.07449823 0.5118796 -0.8558208 -0.06968289 0.5288212 -0.8458678 0.06174367 0.5325818 -0.8441234 -0.06959336 0.1594085 -0.9847567 -0.0583083 0.1833408 -0.9813187 -0.1279445 0.1807591 -0.9751699 -0.07802879 0.2332868 -0.9692723 -0.06929337 0.2336259 -0.9698544 -0.04436814 0.2837637 -0.9578673 -0.01339626 0.2847335 -0.9585132 -0.001301765 0.3313944 -0.9434914 -0.008711755 0.331196 -0.9435217 0.002331018 0.3713954 -0.9284719 -0.01315498 0.3709486 -0.9285602 -0.004944622 0.3993077 -0.9168037 0.06769496 0.4003669 -0.9138511 0.05994224 0.3861798 -0.9204738 0.09998124 0.3860034 -0.9170632 0.1069828 0.3995324 -0.9104551 0.09635233 0.3996893 -0.9115726 0.03262323 0.7552933 -0.6545744 -0.07625067 0.7514201 -0.6554034 -0.07488715 0.8613022 -0.5025439 -0.1555479 0.8522436 -0.4994855 -0.1487766 0.9332253 -0.3270412 -0.1301124 0.9057737 -0.4032925 -0.1166217 0.9025816 -0.4144224 -0.1199839 0.7734644 -0.62238 -0.0706461 0.7779642 -0.6243243 -0.06998234 0.6571393 -0.7505135 0.03645026 0.6607826 -0.7496917 0.07169473 0.5656979 -0.82149 0.1290094 0.5639287 -0.8156844 0.1356714 0.4346235 -0.8903346 0.139234 0.4345339 -0.8898283 -0.05990064 0.6809946 -0.7298344 -0.05990421 0.6810215 -0.7298091 -0.06872469 0.7507401 -0.6570131 0.008118212 0.5805978 -0.81415 0.002548754 0.676039 -0.7368615 -0.1487551 0.9332284 -0.327042 -0.08308029 0.937052 -0.3391624 -0.08901715 0.8096318 -0.5801486 -9.55014e-4 0.8142564 -0.5805046 0.02520048 0.7082275 -0.7055344 0.08186662 0.7070933 -0.7023652 0.09487766 0.5057364 -0.8574549 0.1202866 0.5050143 -0.8546881 0.1264299 0.419032 -0.8991262 0.1232576 0.4190931 -0.8995379 -0.1189416 0.9696928 -0.2134211 -0.04520791 0.9758009 -0.2139366 -0.04934865 0.8004547 -0.5973583 0.03885 0.8018885 -0.5962095 0.05237275 0.6011458 -0.7974214 0.03091108 0.6013051 -0.7984215 0.08850973 0.5118389 -0.8545097 0.02961891 0.3828657 -0.9233291 0.1002353 0.3820745 -0.9186795 0.05021619 0.2659232 -0.9626855 0.07250714 0.265864 -0.9612799 0.04285174 0.1987625 -0.9791104 -0.01332968 0.1981412 -0.9800828 -0.01923042 0.1727772 -0.9847732 -0.008322596 0.1729772 -0.9848906 -0.02272337 0.1120078 -0.9934475 -0.01221799 0.1121864 -0.993612 -0.024024 0.06181359 -0.9977985 -0.06626719 0.06109154 -0.9959299 -0.0579583 0.07880908 -0.9952035 -0.0797578 0.07835394 -0.99373 -0.07140719 -0.1455153 -0.9867756 + + + + + + + + + + + + + + + 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 +

0 0 1 0 2 0 3 1 4 1 5 1 6 2 7 2 8 2 9 3 10 3 11 3 12 4 13 4 14 4 15 5 16 5 17 5 17 6 18 6 15 6 15 7 18 7 19 7 15 8 19 8 20 8 21 9 22 9 23 9 21 10 23 10 15 10 15 11 23 11 24 11 15 12 24 12 16 12 25 13 26 13 27 13 27 14 26 14 28 14 27 15 28 15 21 15 21 16 28 16 29 16 21 17 29 17 22 17 14 18 13 18 27 18 27 19 13 19 30 19 27 20 30 20 25 20 12 21 14 21 31 21 31 22 14 22 32 22 31 23 32 23 33 23 34 24 35 24 36 24 36 25 35 25 37 25 36 26 37 26 32 26 32 27 37 27 38 27 32 28 38 28 33 28 39 29 40 29 36 29 36 30 40 30 41 30 36 31 41 31 34 31 42 32 43 32 44 32 44 33 43 33 45 33 45 34 46 34 44 34 44 35 46 35 47 35 44 36 47 36 39 36 39 37 47 37 48 37 39 38 48 38 40 38 49 39 50 39 51 39 52 40 53 40 54 40 11 41 55 41 56 41 57 42 58 42 10 42 10 43 58 43 59 43 10 44 59 44 60 44 60 45 61 45 10 45 10 46 61 46 62 46 10 47 62 47 63 47 63 48 64 48 10 48 10 49 64 49 65 49 10 50 65 50 11 50 11 51 65 51 66 51 11 52 66 52 55 52 67 53 68 53 69 53 69 54 68 54 70 54 69 55 70 55 71 55 72 56 73 56 74 56 72 57 74 57 75 57 75 58 74 58 76 58 75 59 76 59 77 59 78 60 79 60 76 60 76 61 79 61 80 61 76 62 80 62 77 62 81 63 82 63 83 63 83 64 82 64 84 64 83 65 84 65 85 65 85 66 84 66 86 66 87 67 88 67 89 67 89 68 88 68 90 68 89 69 90 69 91 69 92 70 93 70 94 70 94 71 93 71 95 71 94 72 95 72 96 72 97 73 98 73 99 73 99 74 98 74 100 74 99 75 100 75 95 75 95 76 100 76 101 76 95 77 101 77 96 77 102 78 103 78 104 78 104 79 103 79 105 79 3 80 5 80 106 80 71 81 107 81 69 81 69 82 107 82 108 82 69 83 108 83 109 83 1 84 0 84 103 84 103 85 0 85 110 85 103 86 110 86 105 86 105 87 110 87 8 87 105 88 8 88 111 88 111 89 8 89 7 89 111 90 7 90 112 90 92 91 87 91 93 91 93 92 87 92 89 92 93 93 89 93 113 93 113 94 89 94 91 94 113 95 91 95 114 95 102 96 115 96 103 96 103 97 115 97 97 97 103 98 97 98 1 98 1 99 97 99 99 99 1 100 99 100 2 100 2 101 99 101 95 101 2 102 95 102 116 102 116 103 95 103 93 103 116 104 93 104 85 104 85 105 93 105 113 105 85 106 113 106 83 106 83 107 113 107 114 107 83 108 114 108 81 108 117 109 106 109 118 109 118 110 106 110 5 110 118 111 5 111 119 111 119 112 5 112 120 112 119 113 120 113 121 113 20 114 117 114 15 114 15 115 117 115 118 115 15 116 118 116 21 116 21 117 118 117 119 117 21 118 119 118 27 118 27 119 119 119 121 119 27 120 121 120 14 120 14 121 121 121 122 121 14 122 122 122 32 122 32 123 122 123 123 123 32 124 123 124 36 124 36 125 123 125 124 125 36 126 124 126 39 126 107 127 125 127 108 127 108 128 125 128 9 128 108 129 9 129 109 129 109 130 9 130 11 130 109 131 11 131 126 131 126 132 11 132 56 132 126 133 56 133 127 133 127 134 52 134 126 134 126 135 52 135 54 135 126 136 54 136 109 136 109 137 54 137 128 137 109 138 128 138 69 138 69 139 128 139 74 139 69 140 74 140 67 140 67 141 74 141 73 141 53 142 50 142 54 142 54 143 50 143 49 143 54 144 49 144 128 144 128 145 49 145 129 145 128 146 129 146 74 146 74 147 129 147 130 147 74 148 130 148 76 148 76 149 130 149 85 149 76 150 85 150 78 150 78 151 85 151 86 151 51 152 42 152 49 152 49 153 42 153 44 153 49 154 44 154 129 154 129 155 44 155 39 155 129 156 39 156 130 156 130 157 39 157 124 157 130 158 124 158 85 158 85 159 124 159 123 159 85 160 123 160 116 160 116 161 123 161 122 161 116 162 122 162 2 162 2 163 122 163 121 163 2 164 121 164 0 164 0 165 121 165 120 165 0 166 120 166 110 166 110 167 120 167 5 167 110 168 5 168 8 168 8 169 5 169 4 169 8 170 4 170 6 170 131 171 132 171 133 171 134 172 135 172 136 172 137 173 138 173 139 173 140 174 141 174 133 174 142 175 143 175 144 175 144 176 143 176 145 176 138 177 137 177 144 177 146 178 147 178 137 178 137 179 147 179 148 179 137 180 148 180 144 180 144 181 148 181 149 181 144 182 149 182 142 182 150 183 151 183 137 183 137 184 151 184 152 184 137 185 152 185 146 185 150 186 153 186 154 186 154 187 153 187 155 187 154 188 155 188 156 188 156 189 155 189 157 189 141 190 158 190 133 190 133 191 158 191 159 191 133 192 159 192 155 192 155 193 159 193 160 193 155 194 160 194 157 194 161 195 162 195 163 195 163 196 162 196 164 196 163 197 164 197 165 197 165 198 164 198 166 198 165 199 166 199 133 199 133 200 166 200 167 200 133 201 167 201 140 201 134 202 168 202 169 202 170 203 171 203 172 203 172 204 171 204 173 204 172 205 173 205 134 205 134 206 173 206 174 206 134 207 174 207 168 207 170 208 172 208 175 208 175 209 172 209 176 209 175 210 176 210 177 210 177 211 176 211 178 211 178 212 176 212 179 212 178 213 179 213 180 213 181 214 182 214 183 214 134 215 136 215 172 215 172 216 136 216 181 216 172 217 181 217 176 217 176 218 181 218 183 218 176 219 183 219 179 219 184 220 136 220 185 220 185 221 136 221 135 221 185 222 135 222 186 222 169 223 161 223 134 223 134 224 161 224 163 224 134 225 163 225 135 225 135 226 163 226 165 226 135 227 165 227 186 227 132 228 187 228 133 228 133 229 187 229 188 229 133 230 188 230 165 230 165 231 188 231 189 231 165 232 189 232 186 232 190 233 191 233 192 233 192 234 191 234 193 234 194 235 144 235 195 235 195 236 144 236 145 236 195 237 145 237 196 237 194 238 191 238 144 238 144 239 191 239 190 239 144 240 190 240 138 240 138 241 190 241 197 241 138 242 197 242 198 242 198 243 199 243 138 243 138 244 199 244 200 244 138 245 200 245 139 245 139 246 200 246 201 246 139 247 201 247 202 247 150 248 137 248 153 248 153 249 137 249 139 249 153 250 139 250 155 250 155 251 139 251 202 251 155 252 202 252 203 252 204 253 205 253 206 253 184 254 207 254 136 254 136 255 207 255 208 255 136 256 208 256 181 256 181 257 208 257 209 257 181 258 209 258 204 258 204 259 206 259 181 259 181 260 206 260 210 260 181 261 210 261 182 261 203 262 211 262 155 262 155 263 211 263 212 263 155 264 212 264 133 264 133 265 212 265 213 265 133 266 213 266 131 266 214 267 215 267 216 267 217 268 218 268 219 268 219 269 218 269 220 269 219 270 220 270 221 270 221 271 220 271 222 271 223 272 224 272 222 272 222 273 224 273 225 273 222 274 225 274 221 274 226 275 227 275 228 275 228 276 227 276 229 276 228 277 229 277 230 277 230 278 229 278 231 278 230 279 231 279 232 279 232 280 231 280 233 280 232 281 233 281 234 281 234 282 233 282 235 282 234 283 235 283 236 283 217 284 237 284 218 284 218 285 237 285 238 285 218 286 238 286 239 286 239 287 238 287 226 287 239 288 226 288 240 288 240 289 226 289 228 289 241 290 214 290 242 290 242 291 214 291 216 291 242 292 216 292 243 292 244 293 245 293 216 293 216 294 245 294 246 294 216 295 246 295 243 295 247 296 188 296 187 296 132 297 248 297 187 297 187 298 248 298 249 298 187 299 249 299 247 299 247 300 249 300 250 300 247 301 250 301 251 301 251 302 250 302 252 302 251 303 252 303 253 303 253 304 252 304 254 304 253 305 254 305 223 305 223 306 254 306 255 306 223 307 255 307 224 307 236 308 256 308 234 308 234 309 256 309 257 309 234 310 257 310 258 310 258 311 257 311 259 311 258 312 259 312 260 312 260 313 259 313 261 313 260 314 261 314 244 314 244 315 261 315 262 315 244 316 262 316 245 316 263 317 264 317 265 317 266 318 267 318 268 318 269 319 270 319 267 319 271 320 272 320 273 320 274 321 275 321 276 321 277 322 278 322 279 322 280 323 281 323 282 323 283 324 284 324 277 324 277 325 284 325 285 325 277 326 285 326 278 326 286 327 215 327 214 327 241 328 287 328 288 328 288 329 287 329 289 329 288 330 289 330 290 330 291 331 292 331 293 331 293 332 292 332 294 332 293 333 294 333 295 333 295 334 294 334 296 334 295 335 296 335 297 335 274 336 276 336 298 336 299 337 300 337 301 337 301 338 300 338 302 338 301 339 302 339 303 339 304 340 299 340 305 340 303 341 306 341 301 341 301 342 306 342 307 342 301 343 307 343 308 343 263 344 265 344 309 344 305 345 299 345 310 345 310 346 299 346 301 346 310 347 301 347 265 347 265 348 301 348 308 348 265 349 308 349 309 349 266 350 311 350 267 350 267 351 311 351 291 351 267 352 291 352 269 352 312 353 313 353 283 353 283 354 313 354 314 354 283 355 314 355 284 355 283 356 282 356 276 356 276 357 282 357 281 357 276 358 281 358 298 358 312 359 283 359 315 359 315 360 283 360 276 360 315 361 276 361 316 361 316 362 276 362 275 362 316 363 275 363 304 363 304 364 275 364 271 364 304 365 271 365 299 365 299 366 271 366 273 366 299 367 273 367 300 367 317 368 318 368 319 368 319 369 318 369 320 369 305 370 321 370 304 370 304 371 321 371 322 371 304 372 322 372 316 372 316 373 322 373 319 373 316 374 319 374 315 374 315 375 319 375 320 375 315 376 320 376 312 376 266 377 323 377 311 377 311 378 323 378 324 378 311 379 324 379 291 379 291 380 324 380 325 380 291 381 325 381 292 381 296 382 326 382 297 382 297 383 326 383 327 383 297 384 327 384 328 384 328 385 327 385 329 385 328 386 329 386 330 386 330 387 329 387 331 387 330 388 331 388 288 388 288 389 331 389 286 389 288 390 286 390 241 390 241 391 286 391 214 391 290 392 317 392 288 392 288 393 317 393 319 393 288 394 319 394 330 394 330 395 319 395 322 395 330 396 322 396 328 396 328 397 322 397 321 397 328 398 321 398 297 398 297 399 321 399 305 399 297 400 305 400 295 400 295 401 305 401 310 401 295 402 310 402 293 402 293 403 310 403 265 403 293 404 265 404 291 404 291 405 265 405 264 405 291 406 264 406 269 406 332 407 333 407 334 407 335 408 198 408 197 408 336 409 337 409 338 409 339 410 340 410 341 410 342 411 343 411 344 411 345 412 346 412 347 412 348 413 349 413 350 413 351 414 352 414 353 414 354 415 355 415 356 415 354 416 356 416 357 416 357 417 356 417 358 417 358 418 356 418 359 418 358 419 359 419 279 419 352 420 348 420 353 420 353 421 348 421 350 421 353 422 350 422 360 422 360 423 350 423 361 423 362 424 363 424 364 424 364 425 363 425 365 425 366 426 367 426 368 426 369 427 370 427 371 427 371 428 370 428 372 428 371 429 372 429 366 429 366 430 372 430 373 430 366 431 373 431 367 431 367 432 373 432 362 432 367 433 362 433 368 433 368 434 362 434 364 434 368 435 364 435 366 435 374 436 375 436 376 436 376 437 375 437 377 437 377 438 192 438 193 438 364 439 378 439 366 439 366 440 378 440 376 440 366 441 376 441 371 441 371 442 376 442 377 442 371 443 377 443 369 443 369 444 377 444 193 444 345 445 379 445 380 445 363 446 351 446 365 446 365 447 351 447 353 447 365 448 353 448 381 448 381 449 353 449 360 449 381 450 360 450 382 450 382 451 360 451 361 451 382 452 361 452 383 452 384 453 342 453 385 453 385 454 342 454 344 454 385 455 344 455 386 455 386 456 344 456 379 456 387 457 340 457 388 457 388 458 340 458 339 458 388 459 339 459 389 459 390 460 389 460 391 460 391 461 389 461 339 461 391 462 339 462 392 462 392 463 339 463 341 463 392 464 341 464 393 464 394 465 395 465 396 465 396 466 395 466 397 466 396 467 397 467 398 467 398 468 397 468 399 468 400 469 401 469 402 469 402 470 401 470 403 470 402 471 403 471 404 471 405 472 406 472 407 472 407 473 406 473 408 473 407 474 408 474 409 474 410 475 411 475 412 475 412 476 411 476 413 476 414 477 415 477 405 477 405 478 415 478 416 478 405 479 416 479 406 479 417 480 418 480 419 480 419 481 418 481 420 481 419 482 420 482 421 482 421 483 420 483 422 483 422 484 420 484 337 484 422 485 337 485 423 485 423 486 337 486 336 486 423 487 336 487 413 487 413 488 336 488 338 488 413 489 338 489 412 489 404 490 424 490 393 490 393 491 424 491 425 491 393 492 425 492 392 492 392 493 425 493 426 493 392 494 426 494 391 494 391 495 426 495 427 495 391 496 427 496 390 496 347 497 346 497 428 497 345 498 380 498 346 498 346 499 380 499 429 499 346 500 429 500 428 500 379 501 344 501 380 501 380 502 344 502 343 502 380 503 343 503 429 503 429 504 343 504 430 504 429 505 430 505 428 505 431 506 432 506 433 506 433 507 432 507 434 507 384 508 387 508 342 508 342 509 387 509 388 509 342 510 388 510 343 510 343 511 388 511 389 511 343 512 389 512 430 512 430 513 389 513 390 513 430 514 390 514 428 514 428 515 390 515 427 515 428 516 427 516 435 516 436 517 437 517 374 517 374 518 437 518 438 518 435 519 439 519 428 519 428 520 439 520 440 520 428 521 440 521 441 521 404 522 393 522 402 522 402 523 393 523 341 523 402 524 341 524 400 524 400 525 341 525 340 525 400 526 340 526 442 526 442 527 340 527 387 527 442 528 387 528 383 528 383 529 387 529 384 529 383 530 384 530 382 530 382 531 384 531 385 531 382 532 385 532 381 532 381 533 385 533 386 533 381 534 386 534 365 534 365 535 386 535 379 535 365 536 379 536 364 536 364 537 379 537 345 537 364 538 345 538 378 538 378 539 345 539 347 539 378 540 347 540 376 540 376 541 347 541 428 541 376 542 428 542 374 542 374 543 428 543 441 543 374 544 441 544 436 544 433 545 443 545 431 545 431 546 443 546 418 546 431 547 418 547 444 547 444 548 418 548 417 548 445 549 446 549 356 549 356 550 446 550 447 550 356 551 447 551 359 551 448 552 356 552 332 552 449 553 450 553 451 553 451 554 450 554 452 554 451 555 452 555 453 555 333 556 454 556 334 556 334 557 454 557 455 557 334 558 455 558 456 558 456 559 455 559 451 559 456 560 451 560 394 560 394 561 451 561 453 561 394 562 453 562 395 562 398 563 457 563 396 563 396 564 457 564 458 564 396 565 458 565 394 565 394 566 458 566 459 566 394 567 459 567 456 567 456 568 459 568 460 568 456 569 460 569 334 569 334 570 460 570 461 570 445 571 356 571 462 571 462 572 356 572 448 572 462 573 448 573 463 573 463 574 448 574 464 574 463 575 464 575 465 575 465 576 464 576 466 576 465 577 466 577 467 577 332 578 334 578 448 578 448 579 334 579 461 579 448 580 461 580 464 580 464 581 461 581 468 581 464 582 468 582 466 582 459 583 469 583 470 583 459 584 470 584 460 584 460 585 470 585 471 585 460 586 471 586 461 586 461 587 471 587 472 587 461 588 472 588 468 588 473 589 474 589 335 589 335 590 474 590 475 590 199 591 198 591 476 591 476 592 198 592 335 592 476 593 335 593 477 593 477 594 335 594 475 594 438 595 473 595 374 595 374 596 473 596 335 596 374 597 335 597 375 597 375 598 335 598 197 598 375 599 197 599 377 599 377 600 197 600 190 600 377 601 190 601 192 601 415 602 399 602 416 602 416 603 399 603 397 603 416 604 397 604 406 604 406 605 397 605 395 605 406 606 395 606 408 606 408 607 395 607 453 607 408 608 453 608 409 608 409 609 453 609 452 609 409 610 452 610 478 610 478 611 452 611 479 611 480 612 481 612 410 612 410 613 481 613 482 613 410 614 482 614 411 614 411 615 482 615 483 615 411 616 483 616 413 616 413 617 483 617 484 617 413 618 484 618 423 618 433 619 485 619 443 619 443 620 485 620 486 620 443 621 486 621 418 621 418 622 486 622 487 622 418 623 487 623 420 623 420 624 487 624 414 624 420 625 414 625 337 625 337 626 414 626 405 626 337 627 405 627 338 627 338 628 405 628 407 628 338 629 407 629 412 629 412 630 407 630 409 630 412 631 409 631 410 631 410 632 409 632 478 632 410 633 478 633 480 633 349 634 469 634 350 634 350 635 469 635 459 635 350 636 459 636 361 636 361 637 459 637 458 637 361 638 458 638 383 638 383 639 458 639 457 639 383 640 457 640 442 640 442 641 457 641 398 641 442 642 398 642 400 642 400 643 398 643 399 643 400 644 399 644 401 644 401 645 399 645 415 645 401 646 415 646 403 646 403 647 415 647 414 647 403 648 414 648 404 648 404 649 414 649 487 649 404 650 487 650 424 650 424 651 487 651 486 651 424 652 486 652 425 652 425 653 486 653 485 653 425 654 485 654 426 654 426 655 485 655 433 655 426 656 433 656 427 656 427 657 433 657 434 657 427 658 434 658 435 658 488 659 489 659 490 659 491 660 467 660 466 660 492 661 493 661 494 661 495 662 496 662 497 662 497 663 496 663 498 663 497 664 498 664 499 664 498 665 500 665 499 665 499 666 500 666 501 666 499 667 501 667 502 667 502 668 501 668 503 668 502 669 503 669 504 669 504 670 503 670 505 670 504 671 505 671 506 671 507 672 488 672 348 672 506 673 489 673 504 673 504 674 489 674 488 674 504 675 488 675 502 675 502 676 488 676 507 676 502 677 507 677 499 677 499 678 507 678 508 678 499 679 508 679 497 679 509 680 510 680 511 680 512 681 513 681 514 681 511 682 370 682 369 682 515 683 509 683 516 683 516 684 509 684 511 684 516 685 511 685 517 685 517 686 511 686 369 686 517 687 369 687 193 687 513 688 518 688 514 688 514 689 518 689 519 689 514 690 519 690 520 690 510 691 373 691 511 691 511 692 373 692 372 692 511 693 372 693 370 693 493 694 495 694 494 694 494 695 495 695 497 695 494 696 497 696 521 696 521 697 497 697 508 697 521 698 508 698 522 698 522 699 508 699 507 699 348 700 352 700 507 700 507 701 352 701 351 701 507 702 351 702 522 702 522 703 351 703 363 703 522 704 363 704 523 704 523 705 363 705 362 705 491 706 466 706 524 706 525 707 524 707 526 707 526 708 524 708 466 708 526 709 466 709 527 709 466 710 468 710 527 710 527 711 468 711 472 711 527 712 472 712 528 712 529 713 515 713 520 713 520 714 515 714 516 714 520 715 516 715 514 715 514 716 516 716 517 716 514 717 517 717 512 717 512 718 517 718 193 718 519 719 530 719 520 719 520 720 530 720 531 720 520 721 531 721 529 721 529 722 531 722 532 722 529 723 532 723 533 723 362 724 373 724 523 724 523 725 373 725 510 725 523 726 510 726 522 726 522 727 510 727 509 727 522 728 509 728 521 728 521 729 509 729 515 729 521 730 515 730 494 730 494 731 515 731 529 731 494 732 529 732 492 732 492 733 529 733 533 733 492 734 533 734 534 734 472 735 471 735 528 735 528 736 471 736 470 736 528 737 470 737 490 737 490 738 470 738 469 738 490 739 469 739 488 739 488 740 469 740 349 740 488 741 349 741 348 741 535 742 525 742 536 742 536 743 525 743 526 743 536 744 526 744 537 744 537 745 526 745 527 745 537 746 527 746 538 746 538 747 527 747 528 747 538 748 528 748 539 748 539 749 528 749 490 749 539 750 490 750 540 750 540 751 490 751 489 751 540 752 489 752 541 752 541 753 489 753 506 753 542 754 266 754 268 754 543 755 544 755 545 755 266 756 546 756 547 756 548 757 275 757 274 757 275 758 548 758 271 758 359 759 447 759 446 759 279 760 549 760 550 760 551 761 552 761 279 761 553 762 554 762 555 762 556 763 557 763 558 763 559 764 560 764 445 764 445 765 558 765 561 765 558 766 445 766 556 766 556 767 445 767 462 767 556 768 462 768 562 768 562 769 462 769 463 769 562 770 463 770 563 770 463 771 465 771 563 771 563 772 465 772 467 772 563 773 467 773 564 773 564 774 467 774 491 774 564 775 491 775 565 775 566 776 567 776 557 776 280 777 568 777 569 777 569 778 568 778 557 778 570 779 571 779 572 779 572 780 571 780 573 780 572 781 573 781 574 781 575 782 274 782 298 782 576 783 577 783 575 783 578 784 575 784 579 784 579 785 575 785 298 785 579 786 298 786 281 786 574 787 573 787 580 787 580 788 573 788 581 788 580 789 581 789 582 789 571 790 583 790 573 790 573 791 583 791 584 791 573 792 584 792 581 792 581 793 584 793 585 793 581 794 585 794 582 794 582 795 585 795 578 795 271 796 586 796 587 796 588 797 589 797 590 797 271 798 548 798 590 798 590 799 548 799 591 799 590 800 591 800 588 800 592 801 593 801 594 801 595 802 596 802 272 802 587 803 597 803 271 803 271 804 587 804 272 804 272 805 587 805 586 805 272 806 586 806 595 806 595 807 586 807 271 807 595 808 271 808 596 808 596 809 271 809 598 809 596 810 598 810 272 810 272 811 598 811 599 811 272 812 599 812 590 812 590 813 599 813 600 813 590 814 600 814 271 814 271 815 600 815 599 815 271 816 599 816 598 816 274 817 601 817 602 817 593 818 588 818 594 818 594 819 588 819 591 819 594 820 591 820 603 820 603 821 591 821 548 821 603 822 548 822 604 822 604 823 548 823 274 823 604 824 274 824 605 824 583 825 592 825 584 825 584 826 592 826 594 826 584 827 594 827 585 827 585 828 594 828 603 828 585 829 603 829 578 829 578 830 603 830 604 830 578 831 604 831 575 831 575 832 604 832 605 832 575 833 605 833 576 833 576 834 605 834 274 834 576 835 274 835 577 835 577 836 274 836 602 836 577 837 602 837 575 837 575 838 602 838 601 838 575 839 601 839 606 839 606 840 601 840 274 840 606 841 274 841 607 841 607 842 274 842 575 842 607 843 575 843 606 843 608 844 609 844 610 844 610 845 609 845 611 845 610 846 611 846 612 846 612 847 611 847 613 847 612 848 613 848 614 848 614 849 613 849 615 849 303 850 616 850 306 850 306 851 616 851 617 851 307 852 618 852 619 852 620 853 621 853 622 853 622 854 621 854 623 854 624 855 625 855 622 855 626 856 627 856 622 856 628 857 629 857 309 857 630 858 631 858 632 858 633 859 634 859 635 859 635 860 634 860 636 860 630 861 632 861 637 861 638 862 639 862 630 862 307 863 640 863 641 863 309 864 308 864 634 864 634 865 308 865 307 865 634 866 307 866 642 866 643 867 608 867 644 867 644 868 608 868 610 868 644 869 610 869 645 869 645 870 610 870 612 870 645 871 612 871 646 871 646 872 612 872 614 872 646 873 614 873 636 873 636 874 614 874 635 874 635 875 614 875 647 875 635 876 647 876 633 876 633 877 647 877 648 877 633 878 648 878 269 878 649 879 650 879 614 879 266 880 651 880 615 880 615 881 651 881 652 881 615 882 652 882 614 882 270 883 653 883 654 883 269 884 655 884 270 884 270 885 655 885 656 885 270 886 656 886 657 886 269 887 648 887 655 887 655 888 648 888 647 888 655 889 647 889 656 889 656 890 647 890 614 890 656 891 614 891 657 891 657 892 614 892 650 892 657 893 650 893 270 893 270 894 650 894 649 894 270 895 649 895 653 895 653 896 649 896 614 896 653 897 614 897 654 897 654 898 614 898 652 898 654 899 652 899 270 899 270 900 652 900 651 900 270 901 651 901 267 901 269 902 264 902 633 902 633 903 264 903 263 903 633 904 263 904 637 904 637 905 263 905 309 905 637 906 309 906 630 906 630 907 309 907 658 907 630 908 658 908 638 908 638 909 658 909 309 909 638 910 309 910 639 910 639 911 309 911 629 911 639 912 629 912 630 912 630 913 629 913 628 913 630 914 628 914 631 914 631 915 628 915 309 915 631 916 309 916 632 916 632 917 309 917 634 917 632 918 634 918 637 918 637 919 634 919 633 919 659 920 660 920 643 920 661 921 662 921 663 921 663 922 662 922 664 922 663 923 664 923 546 923 266 924 665 924 666 924 666 925 665 925 667 925 666 926 667 926 546 926 546 927 266 927 666 927 643 928 660 928 608 928 608 929 660 929 668 929 608 930 668 930 609 930 609 931 668 931 669 931 609 932 669 932 611 932 611 933 669 933 670 933 611 934 670 934 613 934 613 935 670 935 671 935 613 936 671 936 615 936 615 937 671 937 266 937 268 938 267 938 542 938 542 939 267 939 651 939 542 940 651 940 266 940 672 941 673 941 674 941 675 942 545 942 676 942 676 943 545 943 544 943 676 944 544 944 674 944 674 945 544 945 677 945 674 946 677 946 672 946 678 947 679 947 545 947 545 948 679 948 680 948 545 949 680 949 543 949 661 950 663 950 681 950 681 951 663 951 682 951 681 952 682 952 545 952 545 953 682 953 683 953 545 954 683 954 684 954 684 955 685 955 545 955 545 956 685 956 686 956 545 957 686 957 678 957 687 958 688 958 689 958 689 959 688 959 690 959 266 960 691 960 665 960 665 961 691 961 692 961 665 962 692 962 667 962 667 963 692 963 693 963 667 964 693 964 546 964 546 965 693 965 694 965 546 966 694 966 663 966 663 967 694 967 689 967 663 968 689 968 682 968 682 969 689 969 690 969 682 970 690 970 683 970 695 971 696 971 659 971 659 972 696 972 697 972 697 973 687 973 659 973 659 974 687 974 689 974 659 975 689 975 660 975 660 976 689 976 694 976 660 977 694 977 668 977 668 978 694 978 693 978 668 979 693 979 669 979 669 980 693 980 692 980 669 981 692 981 670 981 670 982 692 982 691 982 670 983 691 983 671 983 671 984 691 984 266 984 491 985 524 985 565 985 565 986 524 986 525 986 565 987 525 987 698 987 698 988 525 988 535 988 698 989 535 989 699 989 699 990 695 990 698 990 698 991 695 991 570 991 698 992 570 992 565 992 565 993 570 993 572 993 565 994 572 994 564 994 564 995 572 995 574 995 564 996 574 996 563 996 563 997 574 997 580 997 563 998 580 998 562 998 562 999 580 999 582 999 562 1000 582 1000 556 1000 556 1001 582 1001 578 1001 556 1002 578 1002 557 1002 557 1003 578 1003 579 1003 557 1004 579 1004 569 1004 569 1005 579 1005 281 1005 569 1006 281 1006 280 1006 280 1007 282 1007 700 1007 553 1008 557 1008 701 1008 701 1009 557 1009 567 1009 701 1010 567 1010 553 1010 553 1011 567 1011 566 1011 553 1012 566 1012 554 1012 554 1013 566 1013 557 1013 554 1014 557 1014 555 1014 555 1015 557 1015 568 1015 555 1016 568 1016 553 1016 553 1017 568 1017 280 1017 553 1018 280 1018 557 1018 557 1019 280 1019 700 1019 557 1020 700 1020 558 1020 700 1021 277 1021 558 1021 558 1022 277 1022 279 1022 558 1023 279 1023 561 1023 561 1024 279 1024 550 1024 561 1025 550 1025 445 1025 445 1026 550 1026 549 1026 445 1027 549 1027 559 1027 559 1028 549 1028 279 1028 559 1029 279 1029 560 1029 560 1030 279 1030 552 1030 560 1031 552 1031 445 1031 445 1032 552 1032 551 1032 445 1033 551 1033 446 1033 446 1034 551 1034 279 1034 446 1035 279 1035 359 1035 302 1036 300 1036 273 1036 695 1037 659 1037 570 1037 570 1038 659 1038 643 1038 570 1039 643 1039 571 1039 571 1040 643 1040 644 1040 571 1041 644 1041 583 1041 583 1042 644 1042 645 1042 583 1043 645 1043 592 1043 592 1044 645 1044 646 1044 592 1045 646 1045 593 1045 593 1046 646 1046 636 1046 593 1047 636 1047 588 1047 588 1048 636 1048 634 1048 588 1049 634 1049 622 1049 622 1050 634 1050 642 1050 622 1051 642 1051 626 1051 626 1052 642 1052 307 1052 626 1053 307 1053 627 1053 627 1054 307 1054 641 1054 627 1055 641 1055 622 1055 622 1056 641 1056 640 1056 622 1057 640 1057 624 1057 624 1058 640 1058 307 1058 624 1059 307 1059 625 1059 625 1060 307 1060 702 1060 625 1061 702 1061 622 1061 622 1062 702 1062 307 1062 622 1063 307 1063 703 1063 703 1064 307 1064 619 1064 703 1065 619 1065 622 1065 622 1066 619 1066 618 1066 622 1067 618 1067 620 1067 620 1068 618 1068 307 1068 620 1069 307 1069 621 1069 621 1070 307 1070 306 1070 621 1071 306 1071 623 1071 623 1072 306 1072 617 1072 623 1073 617 1073 622 1073 622 1074 617 1074 616 1074 622 1075 616 1075 588 1075 588 1076 616 1076 303 1076 588 1077 303 1077 589 1077 589 1078 303 1078 302 1078 589 1079 302 1079 590 1079 590 1080 302 1080 273 1080 590 1081 273 1081 272 1081 286 1082 331 1082 704 1082 326 1083 296 1083 705 1083 706 1084 266 1084 707 1084 681 1085 545 1085 708 1085 709 1086 710 1086 545 1086 711 1087 545 1087 675 1087 673 1088 712 1088 674 1088 674 1089 712 1089 713 1089 674 1090 713 1090 676 1090 676 1091 713 1091 714 1091 676 1092 714 1092 715 1092 675 1093 676 1093 711 1093 711 1094 676 1094 715 1094 711 1095 715 1095 545 1095 545 1096 715 1096 716 1096 545 1097 716 1097 709 1097 710 1098 717 1098 545 1098 545 1099 717 1099 718 1099 545 1100 718 1100 708 1100 661 1101 681 1101 719 1101 719 1102 681 1102 708 1102 719 1103 708 1103 720 1103 720 1104 708 1104 721 1104 720 1105 721 1105 704 1105 664 1106 662 1106 546 1106 546 1107 662 1107 266 1107 661 1108 719 1108 662 1108 662 1109 719 1109 266 1109 720 1110 707 1110 719 1110 719 1111 707 1111 266 1111 707 1112 722 1112 706 1112 706 1113 722 1113 325 1113 706 1114 325 1114 324 1114 705 1115 296 1115 723 1115 723 1116 296 1116 294 1116 723 1117 294 1117 292 1117 704 1118 724 1118 720 1118 720 1119 724 1119 705 1119 720 1120 705 1120 707 1120 707 1121 705 1121 723 1121 707 1122 723 1122 722 1122 722 1123 723 1123 292 1123 722 1124 292 1124 325 1124 704 1125 331 1125 724 1125 724 1126 331 1126 329 1126 724 1127 329 1127 705 1127 705 1128 329 1128 327 1128 705 1129 327 1129 326 1129 324 1130 323 1130 706 1130 706 1131 323 1131 266 1131 718 1132 725 1132 708 1132 708 1133 725 1133 726 1133 708 1134 726 1134 721 1134 721 1135 726 1135 727 1135 721 1136 727 1136 704 1136 704 1137 727 1137 728 1137 704 1138 728 1138 286 1138 286 1139 728 1139 729 1139 286 1140 729 1140 215 1140 727 1141 726 1141 730 1141 234 1142 731 1142 232 1142 232 1143 731 1143 732 1143 733 1144 239 1144 240 1144 733 1145 240 1145 734 1145 734 1146 240 1146 228 1146 734 1147 228 1147 732 1147 732 1148 228 1148 230 1148 732 1149 230 1149 232 1149 735 1150 736 1150 737 1150 737 1151 736 1151 738 1151 739 1152 736 1152 740 1152 740 1153 736 1153 735 1153 740 1154 735 1154 741 1154 741 1155 735 1155 742 1155 743 1156 744 1156 745 1156 745 1157 744 1157 746 1157 745 1158 746 1158 747 1158 747 1159 746 1159 748 1159 747 1160 748 1160 749 1160 749 1161 748 1161 750 1161 749 1162 750 1162 751 1162 751 1163 750 1163 752 1163 751 1164 752 1164 738 1164 738 1165 752 1165 753 1165 738 1166 753 1166 737 1166 754 1167 755 1167 756 1167 756 1168 755 1168 757 1168 756 1169 757 1169 758 1169 758 1170 757 1170 759 1170 743 1171 208 1171 744 1171 744 1172 208 1172 207 1172 744 1173 207 1173 184 1173 760 1174 761 1174 762 1174 762 1175 761 1175 763 1175 762 1176 763 1176 759 1176 759 1177 763 1177 764 1177 759 1178 764 1178 758 1178 765 1179 766 1179 767 1179 767 1180 766 1180 768 1180 767 1181 768 1181 760 1181 760 1182 768 1182 769 1182 760 1183 769 1183 761 1183 739 1184 765 1184 736 1184 736 1185 765 1185 767 1185 736 1186 767 1186 738 1186 738 1187 767 1187 760 1187 738 1188 760 1188 751 1188 751 1189 760 1189 762 1189 751 1190 762 1190 749 1190 749 1191 762 1191 759 1191 749 1192 759 1192 747 1192 747 1193 759 1193 757 1193 747 1194 757 1194 745 1194 745 1195 757 1195 755 1195 745 1196 755 1196 743 1196 770 1197 729 1197 728 1197 771 1198 772 1198 773 1198 773 1199 772 1199 774 1199 773 1200 774 1200 775 1200 775 1201 774 1201 776 1201 776 1202 774 1202 777 1202 776 1203 777 1203 778 1203 778 1204 777 1204 770 1204 778 1205 770 1205 730 1205 730 1206 770 1206 728 1206 730 1207 728 1207 727 1207 774 1208 244 1208 777 1208 777 1209 244 1209 216 1209 777 1210 216 1210 770 1210 770 1211 216 1211 215 1211 770 1212 215 1212 729 1212 754 1213 205 1213 755 1213 755 1214 205 1214 204 1214 755 1215 204 1215 743 1215 743 1216 204 1216 209 1216 743 1217 209 1217 208 1217 185 1218 186 1218 779 1218 779 1219 186 1219 189 1219 239 1220 733 1220 218 1220 218 1221 733 1221 780 1221 218 1222 780 1222 220 1222 220 1223 780 1223 781 1223 220 1224 781 1224 222 1224 222 1225 781 1225 782 1225 222 1226 782 1226 223 1226 223 1227 782 1227 783 1227 223 1228 783 1228 253 1228 253 1229 783 1229 784 1229 253 1230 784 1230 251 1230 251 1231 784 1231 779 1231 251 1232 779 1232 247 1232 247 1233 779 1233 189 1233 247 1234 189 1234 188 1234 771 1235 785 1235 786 1235 786 1236 785 1236 787 1236 786 1237 787 1237 788 1237 788 1238 787 1238 789 1238 788 1239 789 1239 742 1239 742 1240 789 1240 790 1240 742 1241 790 1241 741 1241 771 1242 786 1242 772 1242 772 1243 786 1243 258 1243 772 1244 258 1244 774 1244 774 1245 258 1245 260 1245 774 1246 260 1246 244 1246 184 1247 185 1247 744 1247 744 1248 185 1248 779 1248 744 1249 779 1249 746 1249 746 1250 779 1250 784 1250 746 1251 784 1251 748 1251 748 1252 784 1252 783 1252 748 1253 783 1253 750 1253 750 1254 783 1254 782 1254 750 1255 782 1255 752 1255 752 1256 782 1256 781 1256 752 1257 781 1257 753 1257 753 1258 781 1258 780 1258 753 1259 780 1259 737 1259 737 1260 780 1260 733 1260 737 1261 733 1261 735 1261 735 1262 733 1262 734 1262 735 1263 734 1263 742 1263 742 1264 734 1264 732 1264 742 1265 732 1265 788 1265 788 1266 732 1266 731 1266 788 1267 731 1267 786 1267 786 1268 731 1268 234 1268 786 1269 234 1269 258 1269 791 1270 792 1270 793 1270 794 1271 795 1271 796 1271 797 1272 798 1272 799 1272 799 1273 798 1273 180 1273 795 1274 800 1274 799 1274 800 1275 801 1275 799 1275 799 1276 801 1276 802 1276 799 1277 802 1277 797 1277 794 1278 796 1278 792 1278 791 1279 793 1279 803 1279 804 1280 805 1280 806 1280 806 1281 805 1281 807 1281 808 1282 809 1282 810 1282 811 1283 812 1283 813 1283 813 1284 812 1284 814 1284 814 1285 815 1285 813 1285 813 1286 815 1286 816 1286 813 1287 816 1287 804 1287 804 1288 816 1288 817 1288 804 1289 817 1289 805 1289 811 1290 813 1290 818 1290 818 1291 813 1291 819 1291 818 1292 819 1292 820 1292 821 1293 822 1293 819 1293 819 1294 822 1294 823 1294 819 1295 823 1295 820 1295 824 1296 825 1296 821 1296 821 1297 825 1297 826 1297 821 1298 826 1298 822 1298 191 1299 194 1299 824 1299 824 1300 194 1300 195 1300 196 1301 827 1301 195 1301 195 1302 827 1302 828 1302 195 1303 828 1303 824 1303 824 1304 828 1304 829 1304 824 1305 829 1305 825 1305 180 1306 179 1306 799 1306 799 1307 179 1307 183 1307 799 1308 183 1308 830 1308 807 1309 808 1309 806 1309 806 1310 808 1310 810 1310 806 1311 810 1311 793 1311 793 1312 810 1312 809 1312 793 1313 809 1313 803 1313 531 1314 530 1314 819 1314 819 1315 530 1315 519 1315 819 1316 519 1316 821 1316 821 1317 519 1317 518 1317 821 1318 518 1318 824 1318 531 1319 819 1319 532 1319 532 1320 819 1320 813 1320 532 1321 813 1321 533 1321 533 1322 813 1322 534 1322 534 1323 813 1323 804 1323 534 1324 804 1324 831 1324 183 1325 182 1325 830 1325 830 1326 182 1326 210 1326 830 1327 210 1327 206 1327 205 1328 832 1328 206 1328 206 1329 832 1329 833 1329 206 1330 833 1330 830 1330 830 1331 833 1331 834 1331 830 1332 834 1332 799 1332 833 1333 835 1333 834 1333 834 1334 835 1334 836 1334 834 1335 836 1335 837 1335 795 1336 799 1336 796 1336 796 1337 799 1337 834 1337 796 1338 834 1338 838 1338 838 1339 834 1339 837 1339 838 1340 837 1340 839 1340 839 1341 840 1341 838 1341 838 1342 840 1342 841 1342 838 1343 841 1343 842 1343 792 1344 796 1344 793 1344 793 1345 796 1345 838 1345 793 1346 838 1346 806 1346 806 1347 838 1347 842 1347 806 1348 842 1348 843 1348 193 1349 191 1349 512 1349 512 1350 191 1350 824 1350 512 1351 824 1351 513 1351 513 1352 824 1352 518 1352 843 1353 844 1353 806 1353 806 1354 844 1354 845 1354 806 1355 845 1355 804 1355 804 1356 845 1356 846 1356 804 1357 846 1357 831 1357 847 1358 848 1358 849 1358 850 1359 851 1359 852 1359 852 1360 851 1360 853 1360 853 1361 854 1361 852 1361 852 1362 854 1362 855 1362 852 1363 855 1363 856 1363 848 1364 857 1364 849 1364 849 1365 857 1365 858 1365 849 1366 858 1366 850 1366 850 1367 858 1367 859 1367 850 1368 859 1368 851 1368 847 1369 849 1369 860 1369 860 1370 849 1370 861 1370 860 1371 861 1371 862 1371 863 1372 864 1372 865 1372 865 1373 864 1373 866 1373 865 1374 866 1374 861 1374 861 1375 866 1375 867 1375 861 1376 867 1376 862 1376 868 1377 869 1377 870 1377 870 1378 869 1378 871 1378 868 1379 872 1379 869 1379 869 1380 872 1380 873 1380 869 1381 873 1381 874 1381 875 1382 876 1382 865 1382 877 1383 878 1383 879 1383 879 1384 878 1384 880 1384 879 1385 880 1385 865 1385 865 1386 880 1386 881 1386 865 1387 881 1387 875 1387 876 1388 882 1388 865 1388 865 1389 882 1389 883 1389 865 1390 883 1390 884 1390 884 1391 885 1391 865 1391 865 1392 885 1392 886 1392 865 1393 886 1393 863 1393 887 1394 888 1394 889 1394 889 1395 888 1395 890 1395 889 1396 890 1396 869 1396 869 1397 890 1397 891 1397 869 1398 891 1398 871 1398 887 1399 889 1399 892 1399 892 1400 889 1400 893 1400 892 1401 893 1401 894 1401 895 1402 896 1402 897 1402 897 1403 896 1403 898 1403 897 1404 898 1404 893 1404 893 1405 898 1405 899 1405 893 1406 899 1406 894 1406 895 1407 897 1407 900 1407 900 1408 897 1408 901 1408 900 1409 901 1409 902 1409 903 1410 904 1410 905 1410 905 1411 904 1411 906 1411 906 1412 907 1412 905 1412 905 1413 907 1413 908 1413 905 1414 908 1414 909 1414 909 1415 910 1415 905 1415 905 1416 910 1416 911 1416 905 1417 911 1417 912 1417 912 1418 913 1418 905 1418 905 1419 913 1419 914 1419 905 1420 914 1420 915 1420 915 1421 916 1421 905 1421 905 1422 916 1422 917 1422 905 1423 917 1423 901 1423 901 1424 917 1424 918 1424 901 1425 918 1425 902 1425 856 1426 919 1426 852 1426 852 1427 919 1427 920 1427 852 1428 920 1428 921 1428 921 1429 920 1429 922 1429 921 1430 922 1430 903 1430 903 1431 922 1431 923 1431 903 1432 923 1432 904 1432 823 1433 822 1433 924 1433 924 1434 822 1434 826 1434 826 1435 825 1435 924 1435 924 1436 825 1436 829 1436 924 1437 829 1437 828 1437 812 1438 925 1438 814 1438 814 1439 925 1439 926 1439 814 1440 926 1440 815 1440 812 1441 811 1441 925 1441 925 1442 811 1442 818 1442 925 1443 818 1443 924 1443 924 1444 818 1444 820 1444 924 1445 820 1445 823 1445 807 1446 805 1446 927 1446 927 1447 805 1447 817 1447 927 1448 817 1448 926 1448 926 1449 817 1449 816 1449 926 1450 816 1450 815 1450 807 1451 927 1451 808 1451 808 1452 927 1452 928 1452 808 1453 928 1453 809 1453 174 1454 173 1454 903 1454 903 1455 173 1455 171 1455 903 1456 171 1456 170 1456 170 1457 175 1457 903 1457 903 1458 175 1458 177 1458 903 1459 177 1459 178 1459 802 1460 801 1460 921 1460 178 1461 180 1461 903 1461 903 1462 180 1462 798 1462 903 1463 798 1463 921 1463 921 1464 798 1464 797 1464 921 1465 797 1465 802 1465 801 1466 800 1466 921 1466 921 1467 800 1467 795 1467 921 1468 795 1468 794 1468 794 1469 792 1469 921 1469 921 1470 792 1470 791 1470 921 1471 791 1471 928 1471 928 1472 791 1472 803 1472 928 1473 803 1473 809 1473 162 1474 929 1474 164 1474 164 1475 929 1475 930 1475 162 1476 161 1476 929 1476 929 1477 161 1477 169 1477 929 1478 169 1478 903 1478 903 1479 169 1479 168 1479 903 1480 168 1480 174 1480 931 1481 158 1481 141 1481 141 1482 140 1482 931 1482 931 1483 140 1483 167 1483 931 1484 167 1484 930 1484 930 1485 167 1485 166 1485 930 1486 166 1486 164 1486 932 1487 160 1487 931 1487 931 1488 160 1488 159 1488 931 1489 159 1489 158 1489 149 1490 148 1490 933 1490 933 1491 148 1491 147 1491 933 1492 147 1492 146 1492 146 1493 152 1493 933 1493 933 1494 152 1494 151 1494 933 1495 151 1495 150 1495 150 1496 154 1496 933 1496 933 1497 154 1497 156 1497 933 1498 156 1498 932 1498 932 1499 156 1499 157 1499 932 1500 157 1500 160 1500 828 1501 827 1501 924 1501 924 1502 827 1502 196 1502 924 1503 196 1503 879 1503 879 1504 196 1504 869 1504 879 1505 869 1505 877 1505 877 1506 869 1506 874 1506 196 1507 145 1507 869 1507 869 1508 145 1508 143 1508 869 1509 143 1509 933 1509 933 1510 143 1510 142 1510 933 1511 142 1511 149 1511 90 1512 88 1512 934 1512 935 1513 936 1513 937 1513 100 1514 98 1514 938 1514 82 1515 81 1515 939 1515 940 1516 941 1516 942 1516 943 1517 944 1517 945 1517 946 1518 947 1518 948 1518 949 1519 950 1519 951 1519 952 1520 953 1520 954 1520 954 1521 953 1521 955 1521 956 1522 957 1522 958 1522 959 1523 107 1523 71 1523 9 1524 960 1524 10 1524 10 1525 960 1525 961 1525 10 1526 961 1526 57 1526 962 1527 963 1527 964 1527 964 1528 963 1528 965 1528 966 1529 965 1529 956 1529 956 1530 965 1530 957 1530 957 1531 965 1531 963 1531 957 1532 963 1532 958 1532 967 1533 968 1533 969 1533 969 1534 968 1534 970 1534 969 1535 970 1535 948 1535 970 1536 950 1536 948 1536 948 1537 950 1537 949 1537 948 1538 949 1538 946 1538 946 1539 949 1539 951 1539 946 1540 951 1540 947 1540 947 1541 951 1541 971 1541 947 1542 971 1542 966 1542 966 1543 971 1543 972 1543 966 1544 972 1544 965 1544 965 1545 972 1545 973 1545 965 1546 973 1546 964 1546 938 1547 974 1547 975 1547 975 1548 974 1548 976 1548 976 1549 977 1549 978 1549 947 1550 979 1550 948 1550 948 1551 979 1551 975 1551 948 1552 975 1552 969 1552 969 1553 975 1553 976 1553 969 1554 976 1554 967 1554 967 1555 976 1555 978 1555 943 1556 955 1556 980 1556 981 1557 75 1557 982 1557 982 1558 75 1558 983 1558 984 1559 953 1559 985 1559 985 1560 953 1560 952 1560 985 1561 952 1561 986 1561 986 1562 952 1562 958 1562 987 1563 942 1563 988 1563 988 1564 942 1564 941 1564 988 1565 941 1565 981 1565 983 1566 989 1566 990 1566 990 1567 989 1567 991 1567 990 1568 991 1568 992 1568 993 1569 940 1569 994 1569 994 1570 940 1570 942 1570 994 1571 942 1571 995 1571 995 1572 942 1572 987 1572 995 1573 987 1573 996 1573 996 1574 987 1574 997 1574 996 1575 997 1575 998 1575 981 1576 982 1576 988 1576 988 1577 982 1577 983 1577 988 1578 983 1578 987 1578 987 1579 983 1579 990 1579 987 1580 990 1580 997 1580 997 1581 990 1581 992 1581 997 1582 992 1582 998 1582 999 1583 1000 1583 1001 1583 1001 1584 1000 1584 1002 1584 78 1585 1002 1585 79 1585 79 1586 1002 1586 1000 1586 79 1587 1000 1587 1003 1587 1003 1588 1000 1588 999 1588 1003 1589 999 1589 1004 1589 1005 1590 1006 1590 1007 1590 1007 1591 1006 1591 1008 1591 1007 1592 1008 1592 1009 1592 1009 1593 1010 1593 1007 1593 1007 1594 1010 1594 1011 1594 1007 1595 1011 1595 1005 1595 1005 1596 1011 1596 939 1596 1005 1597 939 1597 114 1597 114 1598 939 1598 81 1598 1009 1599 1012 1599 1010 1599 1010 1600 1012 1600 1013 1600 1010 1601 1013 1601 1011 1601 1011 1602 1013 1602 1004 1602 1011 1603 1004 1603 939 1603 939 1604 1004 1604 999 1604 939 1605 999 1605 82 1605 82 1606 999 1606 1001 1606 82 1607 1001 1607 84 1607 84 1608 1001 1608 1002 1608 84 1609 1002 1609 86 1609 86 1610 1002 1610 78 1610 1014 1611 1015 1611 1016 1611 945 1612 944 1612 1017 1612 943 1613 980 1613 944 1613 944 1614 980 1614 1018 1614 944 1615 1018 1615 1017 1615 955 1616 953 1616 980 1616 980 1617 953 1617 984 1617 980 1618 984 1618 1018 1618 1018 1619 984 1619 1019 1619 1018 1620 1019 1620 1017 1620 88 1621 87 1621 934 1621 934 1622 87 1622 1014 1622 934 1623 1014 1623 1020 1623 1020 1624 1014 1624 1016 1624 1020 1625 1016 1625 1021 1625 92 1626 94 1626 1017 1626 1017 1627 94 1627 96 1627 1017 1628 96 1628 101 1628 958 1629 952 1629 956 1629 956 1630 952 1630 954 1630 956 1631 954 1631 966 1631 966 1632 954 1632 955 1632 966 1633 955 1633 947 1633 947 1634 955 1634 943 1634 947 1635 943 1635 979 1635 979 1636 943 1636 945 1636 979 1637 945 1637 975 1637 975 1638 945 1638 1017 1638 975 1639 1017 1639 938 1639 938 1640 1017 1640 101 1640 938 1641 101 1641 100 1641 114 1642 91 1642 1005 1642 1005 1643 91 1643 90 1643 1005 1644 90 1644 1006 1644 1006 1645 90 1645 934 1645 1006 1646 934 1646 1008 1646 1008 1647 934 1647 1020 1647 1008 1648 1020 1648 1009 1648 1009 1649 1020 1649 1021 1649 1009 1650 1021 1650 1012 1650 1022 1651 1023 1651 107 1651 1022 1652 107 1652 1024 1652 1023 1653 1025 1653 107 1653 107 1654 1025 1654 1026 1654 107 1655 1026 1655 1027 1655 9 1656 125 1656 960 1656 960 1657 125 1657 107 1657 960 1658 107 1658 1028 1658 1028 1659 107 1659 1027 1659 71 1660 70 1660 959 1660 959 1661 70 1661 68 1661 959 1662 68 1662 67 1662 75 1663 1029 1663 72 1663 72 1664 1029 1664 73 1664 1030 1665 1031 1665 1032 1665 1032 1666 1031 1666 1033 1666 1032 1667 1033 1667 107 1667 107 1668 1033 1668 1034 1668 107 1669 1034 1669 1024 1669 67 1670 73 1670 959 1670 959 1671 73 1671 1035 1671 959 1672 1035 1672 107 1672 107 1673 1035 1673 1036 1673 107 1674 1036 1674 1032 1674 1029 1675 1037 1675 1038 1675 1029 1676 1038 1676 73 1676 73 1677 1038 1677 1039 1677 73 1678 1039 1678 1035 1678 1035 1679 1039 1679 1040 1679 1035 1680 1040 1680 1036 1680 97 1681 115 1681 935 1681 935 1682 115 1682 102 1682 102 1683 104 1683 935 1683 935 1684 104 1684 105 1684 935 1685 105 1685 936 1685 936 1686 105 1686 111 1686 936 1687 111 1687 112 1687 98 1688 97 1688 938 1688 938 1689 97 1689 935 1689 938 1690 935 1690 974 1690 974 1691 935 1691 937 1691 974 1692 937 1692 976 1692 976 1693 937 1693 1041 1693 976 1694 1041 1694 977 1694 75 1695 77 1695 983 1695 983 1696 77 1696 80 1696 983 1697 80 1697 989 1697 989 1698 80 1698 79 1698 989 1699 79 1699 991 1699 991 1700 79 1700 1003 1700 991 1701 1003 1701 992 1701 992 1702 1003 1702 1004 1702 992 1703 1004 1703 998 1703 998 1704 1004 1704 1013 1704 998 1705 1013 1705 996 1705 996 1706 1013 1706 1012 1706 996 1707 1012 1707 995 1707 995 1708 1012 1708 1021 1708 995 1709 1021 1709 994 1709 994 1710 1021 1710 1016 1710 994 1711 1016 1711 993 1711 993 1712 1016 1712 1015 1712 87 1713 92 1713 1014 1713 1014 1714 92 1714 1017 1714 1014 1715 1017 1715 1015 1715 1015 1716 1017 1716 1019 1716 1015 1717 1019 1717 993 1717 993 1718 1019 1718 984 1718 993 1719 984 1719 940 1719 940 1720 984 1720 985 1720 940 1721 985 1721 941 1721 941 1722 985 1722 986 1722 941 1723 986 1723 981 1723 981 1724 986 1724 958 1724 981 1725 958 1725 75 1725 75 1726 958 1726 963 1726 75 1727 963 1727 1029 1727 1029 1728 963 1728 962 1728 1029 1729 962 1729 1037 1729 62 1730 61 1730 1042 1730 1043 1731 1044 1731 1045 1731 1046 1732 1047 1732 1048 1732 1049 1733 1050 1733 1051 1733 1052 1734 58 1734 57 1734 1052 1735 1053 1735 1054 1735 58 1736 1052 1736 59 1736 52 1737 127 1737 1055 1737 1056 1738 1057 1738 1058 1738 1059 1739 1060 1739 1061 1739 1061 1740 1060 1740 1062 1740 1061 1741 1062 1741 1063 1741 1047 1742 1064 1742 1065 1742 1065 1743 1064 1743 1066 1743 1065 1744 1066 1744 1067 1744 1067 1745 1066 1745 1068 1745 1067 1746 1068 1746 1069 1746 1070 1747 1071 1747 1072 1747 1072 1748 1071 1748 1073 1748 1074 1749 1043 1749 1075 1749 1075 1750 1043 1750 1045 1750 1075 1751 1045 1751 1046 1751 1046 1752 1045 1752 1073 1752 1046 1753 1073 1753 1047 1753 1047 1754 1073 1754 1071 1754 1047 1755 1071 1755 1064 1755 1064 1756 1071 1756 1070 1756 1064 1757 1070 1757 1066 1757 1066 1758 1070 1758 1076 1758 1066 1759 1076 1759 1068 1759 1077 1760 1044 1760 1078 1760 1078 1761 1079 1761 1077 1761 1077 1762 1079 1762 1080 1762 1077 1763 1080 1763 1081 1763 1082 1764 1081 1764 1080 1764 59 1765 1052 1765 60 1765 60 1766 1052 1766 1054 1766 60 1767 1054 1767 61 1767 1083 1768 63 1768 62 1768 61 1769 1054 1769 1042 1769 1042 1770 1054 1770 1084 1770 1042 1771 1084 1771 1050 1771 62 1772 1042 1772 1083 1772 1083 1773 1042 1773 1050 1773 1083 1774 1050 1774 1085 1774 1085 1775 1050 1775 1049 1775 1085 1776 1049 1776 1070 1776 56 1777 55 1777 1086 1777 55 1778 66 1778 1086 1778 1086 1779 66 1779 65 1779 1086 1780 65 1780 64 1780 1072 1781 1087 1781 1070 1781 1070 1782 1087 1782 1088 1782 1070 1783 1088 1783 1085 1783 1085 1784 1088 1784 1086 1784 1085 1785 1086 1785 1083 1785 1083 1786 1086 1786 64 1786 1083 1787 64 1787 63 1787 1081 1788 1089 1788 1090 1788 1090 1789 1089 1789 1091 1789 1090 1790 1091 1790 1092 1790 1092 1791 1091 1791 1093 1791 1092 1792 1093 1792 1094 1792 1094 1793 1093 1793 1095 1793 1094 1794 1095 1794 1096 1794 1096 1795 1095 1795 1097 1795 1096 1796 1097 1796 1059 1796 1059 1797 1097 1797 1098 1797 1059 1798 1098 1798 1060 1798 1058 1799 52 1799 1056 1799 1056 1800 52 1800 1055 1800 1056 1801 1055 1801 1099 1801 1099 1802 1055 1802 1063 1802 1099 1803 1063 1803 1100 1803 1100 1804 1063 1804 1062 1804 127 1805 56 1805 1055 1805 1055 1806 56 1806 1086 1806 1055 1807 1086 1807 1063 1807 1063 1808 1086 1808 1088 1808 1063 1809 1088 1809 1061 1809 1061 1810 1088 1810 1087 1810 1061 1811 1087 1811 1059 1811 1059 1812 1087 1812 1072 1812 1059 1813 1072 1813 1096 1813 1096 1814 1072 1814 1073 1814 1096 1815 1073 1815 1094 1815 1094 1816 1073 1816 1045 1816 1094 1817 1045 1817 1092 1817 1092 1818 1045 1818 1044 1818 1092 1819 1044 1819 1090 1819 1090 1820 1044 1820 1077 1820 1090 1821 1077 1821 1081 1821 19 1822 18 1822 1101 1822 1102 1823 1103 1823 1104 1823 1105 1824 1106 1824 1107 1824 904 1825 923 1825 1108 1825 1108 1826 923 1826 922 1826 1106 1827 1105 1827 1108 1827 909 1828 908 1828 1105 1828 1105 1829 908 1829 907 1829 1105 1830 907 1830 1108 1830 1108 1831 907 1831 906 1831 1108 1832 906 1832 904 1832 913 1833 912 1833 1105 1833 912 1834 911 1834 1105 1834 1105 1835 911 1835 910 1835 1105 1836 910 1836 909 1836 913 1837 1109 1837 914 1837 914 1838 1109 1838 915 1838 900 1839 902 1839 1110 1839 900 1840 1110 1840 895 1840 895 1841 1110 1841 1101 1841 895 1842 1101 1842 896 1842 902 1843 918 1843 1110 1843 1110 1844 918 1844 917 1844 1110 1845 917 1845 1109 1845 1109 1846 917 1846 916 1846 1109 1847 916 1847 915 1847 892 1848 894 1848 1111 1848 1111 1849 894 1849 899 1849 1111 1850 899 1850 1101 1850 1101 1851 899 1851 898 1851 1101 1852 898 1852 896 1852 1112 1853 871 1853 891 1853 890 1854 888 1854 1113 1854 1113 1855 888 1855 887 1855 1113 1856 887 1856 1114 1856 1115 1857 870 1857 871 1857 1104 1858 872 1858 868 1858 872 1859 1104 1859 873 1859 873 1860 1104 1860 1103 1860 873 1861 1103 1861 874 1861 871 1862 1112 1862 1115 1862 1115 1863 1112 1863 1116 1863 1115 1864 1116 1864 1117 1864 1118 1865 1102 1865 1117 1865 1117 1866 1102 1866 1104 1866 1117 1867 1104 1867 1115 1867 1115 1868 1104 1868 868 1868 1115 1869 868 1869 870 1869 891 1870 890 1870 1112 1870 1112 1871 890 1871 1113 1871 1112 1872 1113 1872 1116 1872 1116 1873 1113 1873 1119 1873 1116 1874 1119 1874 1120 1874 887 1875 892 1875 1114 1875 1114 1876 892 1876 1111 1876 1114 1877 1111 1877 1113 1877 1113 1878 1111 1878 1121 1878 1113 1879 1121 1879 1119 1879 18 1880 1122 1880 1101 1880 1101 1881 1122 1881 1123 1881 1101 1882 1123 1882 1111 1882 1111 1883 1123 1883 1124 1883 1111 1884 1124 1884 1121 1884 1125 1885 1108 1885 1126 1885 1126 1886 1108 1886 922 1886 1126 1887 922 1887 920 1887 1041 1888 1127 1888 977 1888 977 1889 1127 1889 978 1889 1125 1890 1127 1890 1108 1890 1108 1891 1127 1891 1041 1891 1108 1892 1041 1892 1106 1892 1106 1893 1041 1893 937 1893 1106 1894 937 1894 936 1894 936 1895 112 1895 1106 1895 1106 1896 112 1896 7 1896 1106 1897 7 1897 1107 1897 1107 1898 7 1898 6 1898 1107 1899 6 1899 4 1899 913 1900 1105 1900 1109 1900 1109 1901 1105 1901 1107 1901 1109 1902 1107 1902 1110 1902 1110 1903 1107 1903 4 1903 1110 1904 4 1904 3 1904 1128 1905 1129 1905 1130 1905 1120 1906 1131 1906 1116 1906 1116 1907 1131 1907 1132 1907 1116 1908 1132 1908 1117 1908 1117 1909 1132 1909 1133 1909 1117 1910 1133 1910 1128 1910 1128 1911 1130 1911 1117 1911 1117 1912 1130 1912 1134 1912 1117 1913 1134 1913 1118 1913 3 1914 106 1914 1110 1914 1110 1915 106 1915 117 1915 1110 1916 117 1916 1101 1916 1101 1917 117 1917 20 1917 1101 1918 20 1918 19 1918 1122 1919 18 1919 17 1919 1058 1920 1057 1920 1135 1920 1136 1921 1137 1921 31 1921 1138 1922 34 1922 41 1922 1139 1923 38 1923 37 1923 34 1924 1138 1924 35 1924 35 1925 1138 1925 1140 1925 35 1926 1140 1926 37 1926 37 1927 1140 1927 1141 1927 37 1928 1141 1928 1139 1928 1142 1929 1143 1929 22 1929 22 1930 1143 1930 1144 1930 22 1931 1144 1931 23 1931 22 1932 29 1932 1142 1932 1142 1933 29 1933 28 1933 1142 1934 28 1934 1145 1934 1145 1935 28 1935 26 1935 1145 1936 26 1936 1146 1936 1146 1937 26 1937 25 1937 1146 1938 25 1938 1147 1938 1147 1939 25 1939 30 1939 1147 1940 30 1940 1148 1940 1148 1941 30 1941 13 1941 1148 1942 13 1942 1137 1942 1137 1943 13 1943 12 1943 1137 1944 12 1944 31 1944 1136 1945 31 1945 1139 1945 1139 1946 31 1946 33 1946 1139 1947 33 1947 38 1947 52 1948 1058 1948 53 1948 53 1949 1058 1949 1135 1949 53 1950 1135 1950 50 1950 1149 1951 42 1951 1135 1951 1135 1952 42 1952 51 1952 1135 1953 51 1953 50 1953 23 1954 1144 1954 24 1954 24 1955 1144 1955 1150 1955 24 1956 1150 1956 16 1956 16 1957 1150 1957 1151 1957 16 1958 1151 1958 17 1958 17 1959 1151 1959 1123 1959 17 1960 1123 1960 1122 1960 41 1961 40 1961 1138 1961 1138 1962 40 1962 48 1962 1138 1963 48 1963 1152 1963 1152 1964 48 1964 47 1964 1152 1965 47 1965 1153 1965 1153 1966 47 1966 46 1966 1153 1967 46 1967 1154 1967 1154 1968 46 1968 45 1968 1154 1969 45 1969 1149 1969 1149 1970 45 1970 43 1970 1149 1971 43 1971 42 1971 1155 1972 1156 1972 1157 1972 1158 1973 1159 1973 1142 1973 1142 1974 1159 1974 1143 1974 1143 1975 1159 1975 1160 1975 1143 1976 1160 1976 1144 1976 1142 1977 1145 1977 1158 1977 1158 1978 1145 1978 1146 1978 1158 1979 1146 1979 1161 1979 1161 1980 1146 1980 1147 1980 1161 1981 1147 1981 1162 1981 1162 1982 1147 1982 1148 1982 1162 1983 1148 1983 1137 1983 1163 1984 1164 1984 1165 1984 1165 1985 1164 1985 1166 1985 1165 1986 1166 1986 1167 1986 1167 1987 1166 1987 1168 1987 1167 1988 1168 1988 1169 1988 1136 1989 1164 1989 1170 1989 1170 1990 1164 1990 1163 1990 1170 1991 1163 1991 1171 1991 1171 1992 1163 1992 1172 1992 1171 1993 1172 1993 1173 1993 1174 1994 1172 1994 1175 1994 1175 1995 1172 1995 1163 1995 1175 1996 1163 1996 1176 1996 1176 1997 1163 1997 1165 1997 1177 1998 1160 1998 1178 1998 1178 1999 1160 1999 1159 1999 1178 2000 1159 2000 1179 2000 1179 2001 1159 2001 1158 2001 1179 2002 1158 2002 1180 2002 1180 2003 1158 2003 1161 2003 1180 2004 1161 2004 1181 2004 1181 2005 1161 2005 1162 2005 1182 2006 1177 2006 1183 2006 1183 2007 1177 2007 1178 2007 1183 2008 1178 2008 1184 2008 1184 2009 1178 2009 1179 2009 1184 2010 1179 2010 1185 2010 1185 2011 1179 2011 1180 2011 1185 2012 1180 2012 1173 2012 1173 2013 1180 2013 1181 2013 1173 2014 1181 2014 1171 2014 1171 2015 1181 2015 1162 2015 1171 2016 1162 2016 1170 2016 1170 2017 1162 2017 1137 2017 1170 2018 1137 2018 1136 2018 1186 2019 1187 2019 1188 2019 1188 2020 1187 2020 1189 2020 1188 2021 1189 2021 1190 2021 1190 2022 1189 2022 1191 2022 1190 2023 1191 2023 1129 2023 1128 2024 1133 2024 1192 2024 1192 2025 1133 2025 1132 2025 1192 2026 1132 2026 1193 2026 1193 2027 1132 2027 1131 2027 1194 2028 1195 2028 1196 2028 1196 2029 1195 2029 1197 2029 1196 2030 1197 2030 1186 2030 1186 2031 1197 2031 1198 2031 1186 2032 1198 2032 1187 2032 1199 2033 1200 2033 1201 2033 1201 2034 1200 2034 1202 2034 1201 2035 1202 2035 1194 2035 1194 2036 1202 2036 1203 2036 1194 2037 1203 2037 1195 2037 1174 2038 1199 2038 1172 2038 1172 2039 1199 2039 1201 2039 1172 2040 1201 2040 1173 2040 1173 2041 1201 2041 1194 2041 1173 2042 1194 2042 1185 2042 1185 2043 1194 2043 1196 2043 1185 2044 1196 2044 1184 2044 1184 2045 1196 2045 1186 2045 1184 2046 1186 2046 1183 2046 1183 2047 1186 2047 1188 2047 1183 2048 1188 2048 1182 2048 1182 2049 1188 2049 1190 2049 1204 2050 1205 2050 1206 2050 1207 2051 1208 2051 1209 2051 1209 2052 1208 2052 1210 2052 1209 2053 1210 2053 1211 2053 1211 2054 1210 2054 1212 2054 1211 2055 1212 2055 1169 2055 1207 2056 1209 2056 1213 2056 1213 2057 1209 2057 1214 2057 1213 2058 1214 2058 1215 2058 1215 2059 1214 2059 1204 2059 1215 2060 1204 2060 1157 2060 1157 2061 1204 2061 1206 2061 1157 2062 1206 2062 1155 2062 1211 2063 1154 2063 1209 2063 1209 2064 1154 2064 1149 2064 1209 2065 1149 2065 1214 2065 1214 2066 1149 2066 1135 2066 1214 2067 1135 2067 1204 2067 1204 2068 1135 2068 1057 2068 1204 2069 1057 2069 1205 2069 1129 2070 1128 2070 1190 2070 1190 2071 1128 2071 1192 2071 1190 2072 1192 2072 1182 2072 1182 2073 1192 2073 1193 2073 1182 2074 1193 2074 1177 2074 1177 2075 1193 2075 1216 2075 1177 2076 1216 2076 1160 2076 1160 2077 1216 2077 1150 2077 1160 2078 1150 2078 1144 2078 1131 2079 1120 2079 1193 2079 1193 2080 1120 2080 1119 2080 1193 2081 1119 2081 1216 2081 1216 2082 1119 2082 1121 2082 1216 2083 1121 2083 1150 2083 1150 2084 1121 2084 1124 2084 1150 2085 1124 2085 1151 2085 1151 2086 1124 2086 1123 2086 1212 2087 1217 2087 1169 2087 1169 2088 1217 2088 1218 2088 1169 2089 1218 2089 1167 2089 1167 2090 1218 2090 1219 2090 1167 2091 1219 2091 1165 2091 1165 2092 1219 2092 1220 2092 1165 2093 1220 2093 1176 2093 1136 2094 1139 2094 1164 2094 1164 2095 1139 2095 1141 2095 1164 2096 1141 2096 1166 2096 1166 2097 1141 2097 1140 2097 1166 2098 1140 2098 1168 2098 1168 2099 1140 2099 1138 2099 1168 2100 1138 2100 1169 2100 1169 2101 1138 2101 1152 2101 1169 2102 1152 2102 1211 2102 1211 2103 1152 2103 1153 2103 1211 2104 1153 2104 1154 2104 1221 2105 1222 2105 1223 2105 1224 2106 1223 2106 1225 2106 864 2107 863 2107 1226 2107 886 2108 885 2108 1227 2108 880 2109 878 2109 1228 2109 1228 2110 878 2110 877 2110 1228 2111 877 2111 874 2111 882 2112 876 2112 1228 2112 876 2113 875 2113 1228 2113 1228 2114 875 2114 881 2114 1228 2115 881 2115 880 2115 885 2116 884 2116 1224 2116 1224 2117 884 2117 883 2117 867 2118 1229 2118 862 2118 862 2119 1229 2119 1230 2119 862 2120 1230 2120 860 2120 860 2121 1230 2121 847 2121 864 2122 1226 2122 866 2122 847 2123 1230 2123 848 2123 848 2124 1230 2124 1231 2124 848 2125 1231 2125 857 2125 1232 2126 854 2126 853 2126 853 2127 851 2127 1232 2127 1232 2128 851 2128 859 2128 1232 2129 859 2129 1231 2129 1231 2130 859 2130 858 2130 1231 2131 858 2131 857 2131 1233 2132 855 2132 854 2132 856 2133 855 2133 1234 2133 1234 2134 855 2134 1233 2134 1234 2135 1233 2135 1235 2135 1127 2136 1125 2136 1234 2136 1234 2137 1125 2137 1126 2137 856 2138 1234 2138 919 2138 919 2139 1234 2139 1126 2139 919 2140 1126 2140 920 2140 874 2141 1103 2141 1228 2141 1228 2142 1103 2142 1102 2142 1228 2143 1102 2143 1236 2143 867 2144 866 2144 1229 2144 1229 2145 866 2145 1226 2145 1229 2146 1226 2146 1227 2146 1227 2147 1226 2147 863 2147 1227 2148 863 2148 886 2148 854 2149 1232 2149 1233 2149 1233 2150 1232 2150 1237 2150 1233 2151 1237 2151 1235 2151 1238 2152 1239 2152 1231 2152 1231 2153 1239 2153 1240 2153 1231 2154 1240 2154 1232 2154 1232 2155 1240 2155 1241 2155 1232 2156 1241 2156 1237 2156 1238 2157 1231 2157 1242 2157 1242 2158 1231 2158 1230 2158 1242 2159 1230 2159 1243 2159 1102 2160 1118 2160 1236 2160 1236 2161 1118 2161 1134 2161 1236 2162 1134 2162 1130 2162 1129 2163 1244 2163 1130 2163 1130 2164 1244 2164 1221 2164 1130 2165 1221 2165 1236 2165 1236 2166 1221 2166 1223 2166 1236 2167 1223 2167 1228 2167 1228 2168 1223 2168 1224 2168 1228 2169 1224 2169 882 2169 882 2170 1224 2170 883 2170 1245 2171 1246 2171 1225 2171 1245 2172 1225 2172 1247 2172 1222 2173 1248 2173 1223 2173 1223 2174 1248 2174 1249 2174 1223 2175 1249 2175 1225 2175 1225 2176 1249 2176 1250 2176 1225 2177 1250 2177 1247 2177 885 2178 1224 2178 1227 2178 1227 2179 1224 2179 1225 2179 1227 2180 1225 2180 1229 2180 1229 2181 1225 2181 1246 2181 1229 2182 1246 2182 1251 2182 978 2183 1127 2183 1252 2183 1252 2184 1127 2184 1234 2184 1252 2185 1234 2185 1253 2185 1253 2186 1234 2186 1235 2186 1251 2187 1254 2187 1229 2187 1229 2188 1254 2188 1255 2188 1229 2189 1255 2189 1230 2189 1230 2190 1255 2190 1256 2190 1230 2191 1256 2191 1243 2191 1257 2192 1258 2192 1259 2192 1260 2193 1261 2193 1262 2193 1263 2194 1264 2194 1265 2194 1266 2195 1267 2195 1268 2195 1269 2196 1081 2196 1270 2196 1271 2197 1081 2197 1080 2197 1069 2198 1068 2198 1272 2198 1273 2199 1274 2199 1275 2199 1276 2200 1070 2200 1277 2200 57 2201 961 2201 1052 2201 1052 2202 961 2202 1054 2202 961 2203 960 2203 1054 2203 1054 2204 960 2204 1028 2204 1054 2205 1028 2205 1027 2205 1027 2206 1026 2206 1054 2206 1054 2207 1026 2207 1025 2207 1054 2208 1025 2208 1023 2208 1034 2209 1278 2209 1024 2209 1024 2210 1278 2210 1022 2210 1033 2211 1031 2211 1279 2211 1279 2212 1031 2212 1030 2212 1280 2213 1274 2213 1281 2213 1281 2214 1274 2214 1273 2214 1281 2215 1273 2215 1282 2215 1282 2216 1273 2216 1283 2216 1276 2217 1277 2217 1278 2217 1070 2218 1276 2218 1284 2218 1284 2219 1276 2219 1278 2219 1284 2220 1278 2220 1279 2220 1279 2221 1278 2221 1034 2221 1279 2222 1034 2222 1033 2222 1285 2223 1286 2223 1287 2223 1269 2224 1270 2224 1288 2224 1030 2225 1283 2225 1287 2225 1287 2226 1283 2226 1273 2226 1287 2227 1273 2227 1285 2227 1285 2228 1273 2228 1275 2228 1285 2229 1275 2229 1289 2229 1289 2230 1275 2230 1290 2230 1289 2231 1290 2231 1291 2231 1291 2232 1290 2232 1292 2232 1291 2233 1292 2233 1293 2233 1293 2234 1292 2234 1294 2234 1293 2235 1294 2235 1295 2235 1070 2236 1049 2236 1277 2236 1277 2237 1049 2237 1051 2237 1277 2238 1051 2238 1050 2238 1272 2239 1296 2239 1297 2239 1297 2240 1296 2240 1070 2240 1297 2241 1070 2241 1298 2241 1272 2242 1068 2242 1296 2242 1296 2243 1068 2243 1076 2243 1296 2244 1076 2244 1070 2244 1299 2245 1047 2245 1300 2245 1300 2246 1047 2246 1301 2246 1300 2247 1301 2247 1302 2247 1286 2248 1285 2248 1302 2248 1302 2249 1285 2249 1289 2249 1302 2250 1289 2250 1300 2250 1300 2251 1289 2251 1291 2251 1300 2252 1291 2252 1299 2252 1299 2253 1291 2253 1293 2253 1299 2254 1293 2254 1303 2254 1303 2255 1293 2255 1295 2255 1303 2256 1295 2256 1044 2256 1046 2257 1047 2257 1299 2257 1046 2258 1299 2258 1075 2258 1075 2259 1299 2259 1303 2259 1075 2260 1303 2260 1043 2260 1043 2261 1303 2261 1044 2261 1030 2262 1287 2262 1279 2262 1279 2263 1287 2263 1286 2263 1279 2264 1286 2264 1284 2264 1284 2265 1286 2265 1302 2265 1284 2266 1302 2266 1070 2266 1070 2267 1302 2267 1301 2267 1070 2268 1301 2268 1298 2268 1298 2269 1301 2269 1047 2269 1298 2270 1047 2270 1297 2270 1297 2271 1047 2271 1065 2271 1297 2272 1065 2272 1272 2272 1272 2273 1065 2273 1067 2273 1272 2274 1067 2274 1069 2274 1081 2275 1264 2275 1304 2275 1304 2276 1264 2276 1305 2276 1306 2277 1307 2277 1308 2277 1288 2278 1308 2278 1309 2278 1309 2279 1308 2279 1307 2279 1309 2280 1307 2280 1310 2280 1310 2281 1307 2281 1081 2281 1268 2282 1311 2282 1266 2282 1266 2283 1311 2283 1312 2283 1266 2284 1312 2284 1313 2284 1313 2285 1312 2285 1314 2285 1315 2286 1316 2286 1314 2286 1314 2287 1316 2287 1317 2287 1314 2288 1317 2288 1318 2288 1315 2289 1314 2289 1319 2289 1319 2290 1314 2290 1312 2290 1319 2291 1312 2291 1320 2291 1320 2292 1312 2292 1311 2292 1320 2293 1311 2293 1321 2293 1322 2294 1323 2294 1324 2294 1263 2295 1265 2295 1268 2295 1268 2296 1265 2296 1322 2296 1268 2297 1322 2297 1311 2297 1311 2298 1322 2298 1324 2298 1311 2299 1324 2299 1321 2299 1081 2300 1325 2300 1264 2300 1264 2301 1325 2301 1326 2301 1264 2302 1326 2302 1265 2302 1265 2303 1326 2303 1262 2303 1265 2304 1262 2304 1322 2304 1322 2305 1262 2305 1261 2305 1322 2306 1261 2306 1323 2306 1327 2307 1328 2307 1329 2307 1329 2308 1328 2308 1330 2308 1081 2309 1307 2309 1325 2309 1325 2310 1307 2310 1306 2310 1325 2311 1306 2311 1326 2311 1326 2312 1306 2312 1329 2312 1326 2313 1329 2313 1262 2313 1262 2314 1329 2314 1330 2314 1262 2315 1330 2315 1260 2315 1288 2316 1309 2316 1269 2316 1269 2317 1309 2317 1310 2317 1269 2318 1310 2318 1081 2318 1258 2319 1327 2319 1259 2319 1259 2320 1327 2320 1329 2320 1259 2321 1329 2321 1331 2321 1331 2322 1329 2322 1306 2322 1331 2323 1306 2323 1332 2323 1332 2324 1306 2324 1308 2324 1332 2325 1308 2325 1333 2325 1333 2326 1308 2326 1288 2326 1333 2327 1288 2327 1334 2327 1334 2328 1288 2328 1270 2328 1334 2329 1270 2329 1271 2329 1271 2330 1270 2330 1081 2330 1050 2331 1084 2331 1277 2331 1277 2332 1084 2332 1054 2332 1277 2333 1054 2333 1278 2333 1278 2334 1054 2334 1023 2334 1278 2335 1023 2335 1022 2335 1280 2336 1335 2336 1274 2336 1274 2337 1335 2337 1257 2337 1274 2338 1257 2338 1275 2338 1275 2339 1257 2339 1259 2339 1275 2340 1259 2340 1290 2340 1290 2341 1259 2341 1331 2341 1290 2342 1331 2342 1292 2342 1292 2343 1331 2343 1332 2343 1292 2344 1332 2344 1294 2344 1294 2345 1332 2345 1333 2345 1294 2346 1333 2346 1295 2346 1295 2347 1333 2347 1334 2347 1295 2348 1334 2348 1044 2348 1044 2349 1334 2349 1271 2349 1044 2350 1271 2350 1078 2350 1078 2351 1271 2351 1080 2351 1078 2352 1080 2352 1079 2352 1089 2353 1081 2353 1336 2353 1314 2354 1337 2354 1313 2354 1098 2355 1097 2355 1338 2355 1339 2356 1340 2356 1341 2356 1313 2357 1337 2357 1266 2357 1318 2358 1342 2358 1314 2358 1314 2359 1342 2359 1343 2359 1314 2360 1343 2360 1344 2360 1345 2361 1346 2361 1347 2361 1347 2362 1346 2362 1348 2362 1347 2363 1348 2363 1349 2363 1340 2364 1350 2364 1341 2364 1341 2365 1350 2365 1351 2365 1341 2366 1351 2366 1338 2366 1352 2367 1353 2367 1354 2367 1355 2368 1356 2368 1354 2368 1354 2369 1356 2369 1357 2369 1355 2370 1358 2370 1356 2370 1356 2371 1358 2371 1359 2371 1356 2372 1359 2372 1360 2372 1360 2373 1359 2373 1361 2373 1360 2374 1361 2374 1081 2374 1268 2375 1362 2375 1363 2375 1364 2376 1365 2376 1366 2376 1364 2377 1367 2377 1368 2377 1369 2378 1081 2378 1370 2378 1349 2379 1371 2379 1347 2379 1347 2380 1371 2380 1339 2380 1347 2381 1339 2381 1370 2381 1370 2382 1339 2382 1341 2382 1370 2383 1341 2383 1369 2383 1369 2384 1341 2384 1338 2384 1369 2385 1338 2385 1372 2385 1267 2386 1373 2386 1374 2386 1375 2387 1268 2387 1376 2387 1376 2388 1268 2388 1267 2388 1344 2389 1377 2389 1314 2389 1314 2390 1377 2390 1359 2390 1314 2391 1359 2391 1337 2391 1337 2392 1359 2392 1358 2392 1337 2393 1358 2393 1266 2393 1266 2394 1358 2394 1355 2394 1266 2395 1355 2395 1267 2395 1267 2396 1355 2396 1354 2396 1372 2397 1378 2397 1369 2397 1369 2398 1378 2398 1336 2398 1369 2399 1336 2399 1081 2399 1377 2400 1345 2400 1359 2400 1359 2401 1345 2401 1347 2401 1359 2402 1347 2402 1361 2402 1361 2403 1347 2403 1370 2403 1361 2404 1370 2404 1081 2404 1364 2405 1081 2405 1304 2405 1364 2406 1379 2406 1365 2406 1365 2407 1379 2407 1268 2407 1365 2408 1268 2408 1366 2408 1366 2409 1268 2409 1363 2409 1366 2410 1363 2410 1364 2410 1364 2411 1363 2411 1362 2411 1364 2412 1362 2412 1367 2412 1367 2413 1362 2413 1268 2413 1367 2414 1268 2414 1368 2414 1368 2415 1268 2415 1375 2415 1368 2416 1375 2416 1364 2416 1364 2417 1375 2417 1081 2417 1304 2418 1305 2418 1364 2418 1364 2419 1305 2419 1264 2419 1364 2420 1264 2420 1379 2420 1379 2421 1264 2421 1263 2421 1379 2422 1263 2422 1268 2422 1354 2423 1353 2423 1267 2423 1267 2424 1353 2424 1352 2424 1267 2425 1352 2425 1373 2425 1373 2426 1352 2426 1354 2426 1373 2427 1354 2427 1374 2427 1374 2428 1354 2428 1357 2428 1374 2429 1357 2429 1267 2429 1267 2430 1357 2430 1356 2430 1267 2431 1356 2431 1376 2431 1376 2432 1356 2432 1360 2432 1376 2433 1360 2433 1375 2433 1375 2434 1360 2434 1081 2434 1338 2435 1097 2435 1372 2435 1372 2436 1097 2436 1095 2436 1372 2437 1095 2437 1378 2437 1378 2438 1095 2438 1093 2438 1378 2439 1093 2439 1336 2439 1336 2440 1093 2440 1091 2440 1336 2441 1091 2441 1089 2441 1371 2442 1380 2442 1339 2442 1339 2443 1380 2443 1156 2443 1339 2444 1156 2444 1340 2444 1340 2445 1156 2445 1155 2445 1340 2446 1155 2446 1350 2446 1350 2447 1155 2447 1206 2447 1350 2448 1206 2448 1056 2448 1056 2449 1206 2449 1205 2449 1056 2450 1205 2450 1057 2450 1056 2451 1099 2451 1350 2451 1350 2452 1099 2452 1100 2452 1350 2453 1100 2453 1351 2453 1351 2454 1100 2454 1062 2454 1351 2455 1062 2455 1338 2455 1338 2456 1062 2456 1060 2456 1338 2457 1060 2457 1098 2457 1381 2458 1382 2458 1383 2458 1283 2459 1030 2459 1032 2459 1384 2460 1385 2460 1386 2460 1387 2461 1388 2461 1389 2461 1389 2462 1388 2462 1390 2462 1389 2463 1390 2463 1391 2463 1390 2464 1392 2464 1391 2464 1391 2465 1392 2465 1393 2465 1391 2466 1393 2466 1394 2466 1394 2467 1393 2467 1395 2467 1394 2468 1395 2468 1396 2468 1396 2469 1395 2469 1397 2469 1396 2470 1397 2470 1398 2470 1399 2471 1381 2471 964 2471 1398 2472 1382 2472 1396 2472 1396 2473 1382 2473 1381 2473 1396 2474 1381 2474 1394 2474 1394 2475 1381 2475 1399 2475 1394 2476 1399 2476 1391 2476 1391 2477 1399 2477 1400 2477 1391 2478 1400 2478 1389 2478 1401 2479 1402 2479 1403 2479 1252 2480 1253 2480 1404 2480 1403 2481 968 2481 967 2481 1405 2482 1401 2482 1406 2482 1406 2483 1401 2483 1403 2483 1406 2484 1403 2484 1407 2484 1407 2485 1403 2485 967 2485 1407 2486 967 2486 978 2486 1402 2487 950 2487 1403 2487 1403 2488 950 2488 970 2488 1403 2489 970 2489 968 2489 1385 2490 1387 2490 1386 2490 1386 2491 1387 2491 1389 2491 1386 2492 1389 2492 1408 2492 1408 2493 1389 2493 1400 2493 1408 2494 1400 2494 1409 2494 1409 2495 1400 2495 1399 2495 964 2496 973 2496 1399 2496 1399 2497 973 2497 972 2497 1399 2498 972 2498 1409 2498 1409 2499 972 2499 971 2499 1409 2500 971 2500 1410 2500 1410 2501 971 2501 951 2501 1411 2502 1281 2502 1282 2502 1282 2503 1283 2503 1411 2503 1411 2504 1283 2504 1032 2504 1411 2505 1032 2505 1412 2505 1032 2506 1036 2506 1412 2506 1412 2507 1036 2507 1040 2507 1412 2508 1040 2508 1413 2508 1414 2509 1405 2509 1415 2509 1415 2510 1405 2510 1406 2510 1415 2511 1406 2511 1404 2511 1404 2512 1406 2512 1407 2512 1404 2513 1407 2513 1252 2513 1252 2514 1407 2514 978 2514 1239 2515 1238 2515 1414 2515 1253 2516 1235 2516 1404 2516 1404 2517 1235 2517 1237 2517 1404 2518 1237 2518 1415 2518 1415 2519 1237 2519 1241 2519 1415 2520 1241 2520 1414 2520 1414 2521 1241 2521 1240 2521 1414 2522 1240 2522 1239 2522 951 2523 950 2523 1410 2523 1410 2524 950 2524 1402 2524 1410 2525 1402 2525 1409 2525 1409 2526 1402 2526 1401 2526 1409 2527 1401 2527 1408 2527 1408 2528 1401 2528 1405 2528 1408 2529 1405 2529 1386 2529 1386 2530 1405 2530 1414 2530 1386 2531 1414 2531 1384 2531 1384 2532 1414 2532 1238 2532 1384 2533 1238 2533 1242 2533 1040 2534 1039 2534 1413 2534 1413 2535 1039 2535 1038 2535 1413 2536 1038 2536 1383 2536 1383 2537 1038 2537 1037 2537 1383 2538 1037 2538 1381 2538 1381 2539 1037 2539 962 2539 1381 2540 962 2540 964 2540 1280 2541 1281 2541 1416 2541 1416 2542 1281 2542 1411 2542 1416 2543 1411 2543 1417 2543 1417 2544 1411 2544 1412 2544 1417 2545 1412 2545 1418 2545 1418 2546 1412 2546 1413 2546 1418 2547 1413 2547 1419 2547 1419 2548 1413 2548 1383 2548 1419 2549 1383 2549 1420 2549 1420 2550 1383 2550 1382 2550 1420 2551 1382 2551 1421 2551 1421 2552 1382 2552 1398 2552 536 2553 537 2553 1422 2553 493 2554 492 2554 1423 2554 1424 2555 695 2555 699 2555 1424 2556 699 2556 1422 2556 1422 2557 699 2557 535 2557 1422 2558 535 2558 536 2558 492 2559 534 2559 831 2559 1423 2560 492 2560 1425 2560 1425 2561 492 2561 831 2561 1425 2562 831 2562 846 2562 540 2563 1426 2563 539 2563 539 2564 1426 2564 1427 2564 539 2565 1427 2565 538 2565 538 2566 1427 2566 1428 2566 538 2567 1428 2567 537 2567 537 2568 1428 2568 1429 2568 537 2569 1429 2569 1422 2569 493 2570 1423 2570 495 2570 495 2571 1423 2571 1430 2571 495 2572 1430 2572 496 2572 496 2573 1430 2573 1431 2573 496 2574 1431 2574 498 2574 498 2575 1431 2575 1432 2575 498 2576 1432 2576 500 2576 500 2577 1432 2577 1433 2577 500 2578 1433 2578 501 2578 501 2579 1433 2579 1434 2579 501 2580 1434 2580 503 2580 503 2581 1434 2581 1435 2581 503 2582 1435 2582 505 2582 505 2583 1435 2583 1436 2583 505 2584 1436 2584 506 2584 506 2585 1436 2585 1437 2585 506 2586 1437 2586 541 2586 541 2587 1437 2587 1438 2587 541 2588 1438 2588 540 2588 540 2589 1438 2589 1439 2589 540 2590 1439 2590 1426 2590 842 2591 841 2591 1440 2591 1441 2592 1442 2592 1443 2592 1444 2593 1445 2593 1446 2593 683 2594 690 2594 1447 2594 696 2595 695 2595 1424 2595 1448 2596 1449 2596 1450 2596 1450 2597 1449 2597 1451 2597 1452 2598 1453 2598 1454 2598 1454 2599 1453 2599 1455 2599 1454 2600 1455 2600 1456 2600 1457 2601 1458 2601 1459 2601 1459 2602 1458 2602 1460 2602 1459 2603 1460 2603 1461 2603 1456 2604 1462 2604 1454 2604 1454 2605 1462 2605 1463 2605 1454 2606 1463 2606 1452 2606 1452 2607 1463 2607 1464 2607 1452 2608 1464 2608 1465 2608 1465 2609 1464 2609 1466 2609 1465 2610 1466 2610 1467 2610 1467 2611 1466 2611 1468 2611 1467 2612 1468 2612 1469 2612 1469 2613 1468 2613 1470 2613 1471 2614 1472 2614 1473 2614 1473 2615 1472 2615 1470 2615 1473 2616 1470 2616 1474 2616 1474 2617 1470 2617 1468 2617 1474 2618 1468 2618 1475 2618 1475 2619 1468 2619 1466 2619 1475 2620 1466 2620 1476 2620 1476 2621 1466 2621 1464 2621 1476 2622 1464 2622 1457 2622 1457 2623 1464 2623 1463 2623 1457 2624 1463 2624 1458 2624 1477 2625 1478 2625 1479 2625 837 2626 1480 2626 839 2626 839 2627 1480 2627 1481 2627 1478 2628 1440 2628 1481 2628 1481 2629 1480 2629 1478 2629 1478 2630 1480 2630 1482 2630 1478 2631 1482 2631 1479 2631 1479 2632 1483 2632 1477 2632 1477 2633 1483 2633 1484 2633 1477 2634 1484 2634 1485 2634 1440 2635 841 2635 1481 2635 1481 2636 841 2636 840 2636 1481 2637 840 2637 839 2637 1486 2638 1487 2638 1488 2638 1488 2639 1487 2639 1489 2639 1488 2640 1489 2640 1436 2640 1425 2641 1490 2641 1423 2641 1423 2642 1490 2642 1491 2642 1423 2643 1491 2643 1430 2643 1430 2644 1491 2644 1492 2644 1430 2645 1492 2645 1431 2645 1431 2646 1492 2646 1493 2646 1431 2647 1493 2647 1432 2647 1432 2648 1493 2648 1494 2648 1432 2649 1494 2649 1486 2649 1486 2650 1494 2650 1495 2650 1486 2651 1495 2651 1487 2651 1436 2652 1435 2652 1488 2652 1488 2653 1435 2653 1434 2653 1488 2654 1434 2654 1486 2654 1486 2655 1434 2655 1433 2655 1486 2656 1433 2656 1432 2656 688 2657 687 2657 1496 2657 1496 2658 687 2658 697 2658 1497 2659 1428 2659 1498 2659 1498 2660 1428 2660 1427 2660 1498 2661 1427 2661 1499 2661 697 2662 696 2662 1496 2662 1496 2663 696 2663 1424 2663 1496 2664 1424 2664 1500 2664 1500 2665 1424 2665 1422 2665 1500 2666 1422 2666 1497 2666 1497 2667 1422 2667 1429 2667 1497 2668 1429 2668 1428 2668 1501 2669 1502 2669 1503 2669 677 2670 544 2670 1504 2670 543 2671 680 2671 1444 2671 1442 2672 1502 2672 1443 2672 1443 2673 1502 2673 1501 2673 1443 2674 1501 2674 1505 2674 685 2675 684 2675 1445 2675 680 2676 679 2676 1444 2676 1444 2677 679 2677 678 2677 1444 2678 678 2678 1445 2678 1445 2679 678 2679 686 2679 1445 2680 686 2680 685 2680 1506 2681 1507 2681 1508 2681 1508 2682 1507 2682 1509 2682 1510 2683 1509 2683 1441 2683 684 2684 683 2684 1445 2684 1445 2685 683 2685 1447 2685 1445 2686 1447 2686 1446 2686 1446 2687 1447 2687 1511 2687 1446 2688 1511 2688 1512 2688 544 2689 543 2689 1504 2689 1504 2690 543 2690 1444 2690 1504 2691 1444 2691 1513 2691 1513 2692 1444 2692 1446 2692 1513 2693 1446 2693 1514 2693 1514 2694 1446 2694 1512 2694 1514 2695 1512 2695 1515 2695 1441 2696 1443 2696 1510 2696 1510 2697 1443 2697 1505 2697 1510 2698 1505 2698 1516 2698 1516 2699 1505 2699 1517 2699 1516 2700 1517 2700 1518 2700 1518 2701 1517 2701 1519 2701 1518 2702 1519 2702 1520 2702 1521 2703 1522 2703 1523 2703 1523 2704 1522 2704 1524 2704 1523 2705 1524 2705 1506 2705 1506 2706 1508 2706 1523 2706 1523 2707 1508 2707 1525 2707 1523 2708 1525 2708 1521 2708 1521 2709 1525 2709 1526 2709 1521 2710 1526 2710 1522 2710 1526 2711 1459 2711 1451 2711 1451 2712 1459 2712 1461 2712 1451 2713 1461 2713 1450 2713 1509 2714 1510 2714 1508 2714 1508 2715 1510 2715 1516 2715 1508 2716 1516 2716 1525 2716 1525 2717 1516 2717 1518 2717 1525 2718 1518 2718 1526 2718 1526 2719 1518 2719 1520 2719 1526 2720 1520 2720 1459 2720 673 2721 672 2721 1503 2721 1503 2722 672 2722 677 2722 1503 2723 677 2723 1501 2723 1501 2724 677 2724 1504 2724 1501 2725 1504 2725 1505 2725 1505 2726 1504 2726 1513 2726 1505 2727 1513 2727 1517 2727 1517 2728 1513 2728 1514 2728 1517 2729 1514 2729 1519 2729 1519 2730 1514 2730 1515 2730 1519 2731 1515 2731 1520 2731 1520 2732 1515 2732 1527 2732 1520 2733 1527 2733 1459 2733 1459 2734 1527 2734 1528 2734 1459 2735 1528 2735 1457 2735 1457 2736 1528 2736 1529 2736 1457 2737 1529 2737 1476 2737 1476 2738 1529 2738 1530 2738 1476 2739 1530 2739 1475 2739 1475 2740 1530 2740 1531 2740 1475 2741 1531 2741 1474 2741 1425 2742 846 2742 845 2742 1425 2743 845 2743 1490 2743 1490 2744 845 2744 844 2744 1490 2745 844 2745 843 2745 843 2746 842 2746 1490 2746 1490 2747 842 2747 1440 2747 1490 2748 1440 2748 1491 2748 1491 2749 1440 2749 1478 2749 1491 2750 1478 2750 1492 2750 1492 2751 1478 2751 1477 2751 1492 2752 1477 2752 1493 2752 1493 2753 1477 2753 1485 2753 1493 2754 1485 2754 1494 2754 1494 2755 1485 2755 1532 2755 1494 2756 1532 2756 1495 2756 1495 2757 1532 2757 1533 2757 1495 2758 1533 2758 1487 2758 1427 2759 1426 2759 1499 2759 1499 2760 1426 2760 1439 2760 1499 2761 1439 2761 1534 2761 1534 2762 1439 2762 1438 2762 1534 2763 1438 2763 1489 2763 1489 2764 1438 2764 1437 2764 1489 2765 1437 2765 1436 2765 1484 2766 1471 2766 1485 2766 1485 2767 1471 2767 1473 2767 1485 2768 1473 2768 1532 2768 1532 2769 1473 2769 1474 2769 1532 2770 1474 2770 1533 2770 1533 2771 1474 2771 1531 2771 1533 2772 1531 2772 1487 2772 1487 2773 1531 2773 1530 2773 1487 2774 1530 2774 1489 2774 1489 2775 1530 2775 1529 2775 1489 2776 1529 2776 1534 2776 1534 2777 1529 2777 1528 2777 1534 2778 1528 2778 1499 2778 1499 2779 1528 2779 1527 2779 1499 2780 1527 2780 1498 2780 1498 2781 1527 2781 1515 2781 1498 2782 1515 2782 1497 2782 1497 2783 1515 2783 1512 2783 1497 2784 1512 2784 1500 2784 1500 2785 1512 2785 1511 2785 1500 2786 1511 2786 1496 2786 1496 2787 1511 2787 1447 2787 1496 2788 1447 2788 688 2788 688 2789 1447 2789 690 2789 1535 2790 1536 2790 775 2790 1441 2791 1537 2791 1442 2791 1538 2792 836 2792 835 2792 1539 2793 1540 2793 1541 2793 1542 2794 1452 2794 1465 2794 1543 2795 1544 2795 1545 2795 1546 2796 1456 2796 1547 2796 1548 2797 1549 2797 1550 2797 1551 2798 1552 2798 1553 2798 1554 2799 1555 2799 1556 2799 1557 2800 1558 2800 1559 2800 1560 2801 1561 2801 1562 2801 1562 2802 1561 2802 1557 2802 1559 2803 1558 2803 1563 2803 768 2804 766 2804 1556 2804 768 2805 1564 2805 769 2805 769 2806 1564 2806 1565 2806 768 2807 1556 2807 1564 2807 1564 2808 1556 2808 1566 2808 1564 2809 1566 2809 1565 2809 758 2810 764 2810 1567 2810 1567 2811 764 2811 763 2811 1567 2812 763 2812 1565 2812 1565 2813 763 2813 761 2813 1565 2814 761 2814 769 2814 1568 2815 1569 2815 1570 2815 1570 2816 1569 2816 1571 2816 1570 2817 1571 2817 1572 2817 1572 2818 1571 2818 1555 2818 1572 2819 1555 2819 1573 2819 1573 2820 1555 2820 1554 2820 1573 2821 1554 2821 1574 2821 1556 2822 1555 2822 1566 2822 1566 2823 1555 2823 1571 2823 1566 2824 1571 2824 1565 2824 1565 2825 1571 2825 1569 2825 1565 2826 1569 2826 1567 2826 832 2827 205 2827 1575 2827 1575 2828 205 2828 754 2828 1557 2829 1561 2829 1558 2829 1558 2830 1561 2830 1576 2830 1558 2831 1576 2831 1563 2831 1563 2832 1576 2832 1463 2832 1563 2833 1463 2833 1462 2833 1577 2834 1578 2834 1579 2834 1579 2835 1578 2835 1580 2835 1579 2836 1580 2836 1581 2836 1581 2837 1580 2837 1582 2837 1583 2838 1582 2838 1584 2838 1584 2839 1582 2839 1580 2839 1584 2840 1580 2840 1585 2840 1585 2841 1580 2841 1578 2841 1585 2842 1578 2842 1586 2842 1586 2843 1578 2843 1577 2843 1586 2844 1577 2844 1551 2844 1456 2845 1546 2845 1550 2845 1550 2846 1546 2846 1587 2846 1550 2847 1587 2847 1548 2847 1588 2848 1451 2848 1449 2848 1449 2849 1450 2849 1588 2849 1588 2850 1450 2850 1461 2850 1588 2851 1461 2851 1460 2851 1576 2852 1589 2852 1463 2852 1463 2853 1589 2853 1588 2853 1463 2854 1588 2854 1458 2854 1458 2855 1588 2855 1460 2855 1590 2856 1591 2856 1592 2856 1591 2857 1542 2857 1592 2857 1592 2858 1542 2858 1593 2858 1592 2859 1593 2859 1594 2859 1595 2860 1596 2860 1597 2860 1552 2861 1543 2861 1553 2861 1553 2862 1543 2862 1545 2862 1553 2863 1545 2863 1539 2863 1452 2864 1542 2864 1453 2864 1453 2865 1542 2865 1591 2865 1453 2866 1591 2866 1455 2866 1455 2867 1591 2867 1590 2867 1455 2868 1590 2868 1456 2868 1456 2869 1590 2869 1592 2869 1456 2870 1592 2870 1547 2870 1547 2871 1592 2871 1594 2871 1547 2872 1594 2872 1546 2872 1546 2873 1594 2873 1598 2873 1546 2874 1598 2874 1587 2874 1551 2875 1553 2875 1586 2875 1586 2876 1553 2876 1539 2876 1586 2877 1539 2877 1585 2877 1585 2878 1539 2878 1541 2878 1585 2879 1541 2879 1584 2879 1584 2880 1541 2880 1599 2880 1584 2881 1599 2881 1583 2881 1600 2882 1601 2882 1602 2882 1602 2883 1601 2883 1603 2883 1602 2884 1603 2884 1575 2884 1568 2885 1604 2885 1569 2885 1569 2886 1604 2886 1605 2886 1569 2887 1605 2887 1567 2887 1567 2888 1605 2888 1606 2888 1567 2889 1606 2889 758 2889 758 2890 1606 2890 756 2890 1471 2891 1604 2891 1472 2891 1472 2892 1604 2892 1568 2892 1472 2893 1568 2893 1470 2893 1470 2894 1568 2894 1607 2894 766 2895 765 2895 1556 2895 1556 2896 765 2896 1560 2896 1556 2897 1560 2897 1554 2897 1554 2898 1560 2898 1562 2898 1554 2899 1562 2899 1574 2899 1574 2900 1562 2900 1557 2900 1574 2901 1557 2901 1581 2901 1581 2902 1557 2902 1559 2902 1581 2903 1559 2903 1579 2903 1579 2904 1559 2904 1608 2904 1579 2905 1608 2905 1577 2905 1577 2906 1608 2906 1609 2906 1577 2907 1609 2907 1551 2907 1551 2908 1609 2908 1610 2908 1551 2909 1610 2909 1552 2909 1552 2910 1610 2910 1611 2910 1552 2911 1611 2911 1543 2911 1543 2912 1611 2912 1612 2912 1543 2913 1612 2913 1544 2913 1544 2914 1612 2914 1597 2914 1544 2915 1597 2915 1545 2915 1545 2916 1597 2916 1596 2916 1545 2917 1596 2917 1539 2917 1539 2918 1596 2918 1607 2918 1539 2919 1607 2919 1540 2919 1540 2920 1607 2920 1568 2920 1540 2921 1568 2921 1541 2921 1541 2922 1568 2922 1570 2922 1541 2923 1570 2923 1599 2923 1599 2924 1570 2924 1572 2924 1599 2925 1572 2925 1583 2925 1583 2926 1572 2926 1573 2926 1583 2927 1573 2927 1582 2927 1582 2928 1573 2928 1574 2928 1582 2929 1574 2929 1581 2929 1479 2930 1601 2930 1483 2930 1483 2931 1601 2931 1600 2931 1483 2932 1600 2932 1484 2932 754 2933 756 2933 1575 2933 1575 2934 756 2934 1606 2934 1575 2935 1606 2935 1602 2935 1602 2936 1606 2936 1605 2936 1602 2937 1605 2937 1600 2937 1600 2938 1605 2938 1604 2938 1600 2939 1604 2939 1484 2939 1484 2940 1604 2940 1471 2940 1462 2941 1456 2941 1563 2941 1563 2942 1456 2942 1550 2942 1563 2943 1550 2943 1559 2943 1559 2944 1550 2944 1549 2944 1559 2945 1549 2945 1608 2945 1608 2946 1549 2946 1548 2946 1608 2947 1548 2947 1609 2947 1609 2948 1548 2948 1587 2948 1609 2949 1587 2949 1610 2949 1610 2950 1587 2950 1598 2950 1610 2951 1598 2951 1611 2951 1611 2952 1598 2952 1594 2952 1611 2953 1594 2953 1612 2953 1612 2954 1594 2954 1593 2954 1612 2955 1593 2955 1597 2955 1597 2956 1593 2956 1542 2956 1597 2957 1542 2957 1595 2957 1595 2958 1542 2958 1465 2958 1595 2959 1465 2959 1596 2959 1596 2960 1465 2960 1467 2960 1596 2961 1467 2961 1607 2961 1607 2962 1467 2962 1469 2962 1607 2963 1469 2963 1470 2963 1535 2964 1613 2964 1614 2964 1613 2965 710 2965 1614 2965 1614 2966 710 2966 709 2966 1614 2967 709 2967 716 2967 1502 2968 715 2968 1503 2968 1503 2969 715 2969 714 2969 714 2970 713 2970 1503 2970 1503 2971 713 2971 712 2971 1503 2972 712 2972 673 2972 1506 2973 1537 2973 1507 2973 1507 2974 1537 2974 1441 2974 1507 2975 1441 2975 1509 2975 1506 2976 1524 2976 1536 2976 1506 2977 1536 2977 1537 2977 1537 2978 1536 2978 1535 2978 1537 2979 1535 2979 1442 2979 1442 2980 1535 2980 1614 2980 1442 2981 1614 2981 1502 2981 1502 2982 1614 2982 716 2982 1502 2983 716 2983 715 2983 1451 2984 1588 2984 1526 2984 1526 2985 1588 2985 1615 2985 1526 2986 1615 2986 1522 2986 1522 2987 1615 2987 1616 2987 1522 2988 1616 2988 1524 2988 725 2989 718 2989 1613 2989 1613 2990 718 2990 717 2990 1613 2991 717 2991 710 2991 1524 2992 1616 2992 1536 2992 1536 2993 1616 2993 773 2993 1536 2994 773 2994 775 2994 726 2995 725 2995 730 2995 730 2996 725 2996 1613 2996 730 2997 1613 2997 778 2997 778 2998 1613 2998 1535 2998 778 2999 1535 2999 776 2999 776 3000 1535 3000 775 3000 837 3001 836 3001 1480 3001 1480 3002 836 3002 1538 3002 1480 3003 1538 3003 1482 3003 1479 3004 1482 3004 1601 3004 1601 3005 1482 3005 1538 3005 1601 3006 1538 3006 1603 3006 1603 3007 1538 3007 835 3007 1603 3008 835 3008 1575 3008 1575 3009 835 3009 833 3009 1575 3010 833 3010 832 3010 765 3011 739 3011 1560 3011 1560 3012 739 3012 740 3012 1560 3013 740 3013 1561 3013 1561 3014 740 3014 741 3014 1561 3015 741 3015 1576 3015 1576 3016 741 3016 790 3016 1576 3017 790 3017 1589 3017 1589 3018 790 3018 789 3018 1589 3019 789 3019 1588 3019 1588 3020 789 3020 787 3020 1588 3021 787 3021 1615 3021 1615 3022 787 3022 785 3022 1615 3023 785 3023 1616 3023 1616 3024 785 3024 771 3024 1616 3025 771 3025 773 3025 901 3026 1617 3026 905 3026 905 3027 1617 3027 1618 3027 905 3028 1618 3028 903 3028 903 3029 1618 3029 929 3029 929 3030 1618 3030 1619 3030 929 3031 1619 3031 930 3031 930 3032 1619 3032 1620 3032 930 3033 1620 3033 931 3033 1621 3034 933 3034 1620 3034 1620 3035 933 3035 932 3035 1620 3036 932 3036 931 3036 901 3037 897 3037 1617 3037 1617 3038 897 3038 893 3038 1617 3039 893 3039 1622 3039 1622 3040 893 3040 889 3040 1622 3041 889 3041 1621 3041 1621 3042 889 3042 869 3042 1621 3043 869 3043 933 3043 1623 3044 926 3044 1624 3044 1624 3045 926 3045 925 3045 1624 3046 925 3046 1625 3046 1625 3047 925 3047 924 3047 1625 3048 924 3048 1626 3048 1626 3049 924 3049 879 3049 1626 3050 879 3050 1627 3050 1627 3051 879 3051 865 3051 1627 3052 865 3052 1628 3052 1628 3053 865 3053 861 3053 1628 3054 861 3054 1629 3054 1629 3055 861 3055 849 3055 1629 3056 849 3056 1630 3056 1630 3057 849 3057 850 3057 1630 3058 850 3058 1631 3058 1631 3059 850 3059 852 3059 1631 3060 852 3060 1632 3060 1632 3061 852 3061 921 3061 1632 3062 921 3062 1633 3062 1633 3063 921 3063 928 3063 1633 3064 928 3064 1634 3064 1634 3065 928 3065 927 3065 1634 3066 927 3066 1623 3066 1623 3067 927 3067 926 3067 1635 3068 1636 3068 1637 3068 1637 3069 1636 3069 1638 3069 1639 3070 1640 3070 1641 3070 1642 3071 1643 3071 1638 3071 1638 3072 1643 3072 1644 3072 1638 3073 1644 3073 1637 3073 1641 3074 1645 3074 1639 3074 1639 3075 1645 3075 1646 3075 1639 3076 1646 3076 1647 3076 1647 3077 1646 3077 1648 3077 1647 3078 1648 3078 1642 3078 1642 3079 1648 3079 1649 3079 1642 3080 1649 3080 1643 3080 1635 3081 1650 3081 1636 3081 1636 3082 1650 3082 1651 3082 1636 3083 1651 3083 1640 3083 1640 3084 1651 3084 1652 3084 1640 3085 1652 3085 1641 3085 1653 3086 1640 3086 1654 3086 1654 3087 1640 3087 1639 3087 1654 3088 1639 3088 1655 3088 1655 3089 1639 3089 1647 3089 1655 3090 1647 3090 1656 3090 1656 3091 1647 3091 1642 3091 1656 3092 1642 3092 1657 3092 1657 3093 1642 3093 1638 3093 1657 3094 1638 3094 1658 3094 1658 3095 1638 3095 1636 3095 1658 3096 1636 3096 1653 3096 1653 3097 1636 3097 1640 3097 1629 3098 1644 3098 1628 3098 1628 3099 1644 3099 1643 3099 1628 3100 1643 3100 1627 3100 1627 3101 1643 3101 1649 3101 1627 3102 1649 3102 1626 3102 1626 3103 1649 3103 1648 3103 1626 3104 1648 3104 1625 3104 1625 3105 1648 3105 1646 3105 1625 3106 1646 3106 1624 3106 1624 3107 1646 3107 1645 3107 1624 3108 1645 3108 1623 3108 1623 3109 1645 3109 1641 3109 1623 3110 1641 3110 1634 3110 1634 3111 1641 3111 1652 3111 1634 3112 1652 3112 1633 3112 1633 3113 1652 3113 1651 3113 1633 3114 1651 3114 1632 3114 1632 3115 1651 3115 1650 3115 1632 3116 1650 3116 1631 3116 1631 3117 1650 3117 1635 3117 1631 3118 1635 3118 1630 3118 1630 3119 1635 3119 1637 3119 1630 3120 1637 3120 1629 3120 1629 3121 1637 3121 1644 3121 1659 3122 1660 3122 1654 3122 1654 3123 1660 3123 1661 3123 1654 3124 1661 3124 1653 3124 1659 3125 1662 3125 1660 3125 1660 3126 1662 3126 1663 3126 1660 3127 1663 3127 1664 3127 1664 3128 1663 3128 1665 3128 1664 3129 1665 3129 1666 3129 1666 3130 1665 3130 1667 3130 1666 3131 1667 3131 1668 3131 1668 3132 1667 3132 1620 3132 1668 3133 1620 3133 1619 3133 1654 3134 1655 3134 1669 3134 1670 3135 1662 3135 1669 3135 1669 3136 1662 3136 1659 3136 1669 3137 1659 3137 1654 3137 1667 3138 1665 3138 1670 3138 1670 3139 1665 3139 1663 3139 1670 3140 1663 3140 1662 3140 1670 3141 1671 3141 1667 3141 1667 3142 1671 3142 1621 3142 1667 3143 1621 3143 1620 3143 1655 3144 1656 3144 1672 3144 1655 3145 1672 3145 1669 3145 1669 3146 1672 3146 1673 3146 1669 3147 1673 3147 1670 3147 1670 3148 1673 3148 1674 3148 1670 3149 1674 3149 1671 3149 1671 3150 1674 3150 1622 3150 1671 3151 1622 3151 1621 3151 1656 3152 1657 3152 1675 3152 1656 3153 1675 3153 1672 3153 1672 3154 1675 3154 1676 3154 1672 3155 1676 3155 1673 3155 1673 3156 1676 3156 1677 3156 1673 3157 1677 3157 1674 3157 1674 3158 1677 3158 1617 3158 1674 3159 1617 3159 1622 3159 1657 3160 1658 3160 1678 3160 1657 3161 1678 3161 1675 3161 1675 3162 1678 3162 1679 3162 1675 3163 1679 3163 1676 3163 1676 3164 1679 3164 1680 3164 1676 3165 1680 3165 1677 3165 1677 3166 1680 3166 1618 3166 1677 3167 1618 3167 1617 3167 1658 3168 1653 3168 1661 3168 1658 3169 1661 3169 1678 3169 1678 3170 1661 3170 1660 3170 1678 3171 1660 3171 1679 3171 1660 3172 1664 3172 1679 3172 1679 3173 1664 3173 1666 3173 1679 3174 1666 3174 1680 3174 1666 3175 1668 3175 1680 3175 1680 3176 1668 3176 1619 3176 1680 3177 1619 3177 1618 3177 1681 3178 1248 3178 1222 3178 1682 3179 1683 3179 1684 3179 1685 3180 1686 3180 1687 3180 1688 3181 1689 3181 1690 3181 1691 3182 1692 3182 1693 3182 1694 3183 1695 3183 1696 3183 1697 3184 1698 3184 1699 3184 1187 3185 1198 3185 1700 3185 1701 3186 1702 3186 1703 3186 1199 3187 1704 3187 1705 3187 1706 3188 1707 3188 1708 3188 1708 3189 1707 3189 1705 3189 1198 3190 1197 3190 1700 3190 1700 3191 1197 3191 1195 3191 1700 3192 1195 3192 1706 3192 1706 3193 1195 3193 1203 3193 1706 3194 1203 3194 1707 3194 1707 3195 1203 3195 1202 3195 1707 3196 1202 3196 1705 3196 1705 3197 1202 3197 1200 3197 1705 3198 1200 3198 1199 3198 1709 3199 1710 3199 1711 3199 1711 3200 1710 3200 1712 3200 1711 3201 1712 3201 1713 3201 1713 3202 1712 3202 1714 3202 1713 3203 1714 3203 1715 3203 1715 3204 1714 3204 1716 3204 1715 3205 1716 3205 1717 3205 1717 3206 1716 3206 1718 3206 1717 3207 1718 3207 1719 3207 1701 3208 1719 3208 1702 3208 1702 3209 1719 3209 1718 3209 1702 3210 1718 3210 1704 3210 1704 3211 1718 3211 1716 3211 1704 3212 1716 3212 1705 3212 1705 3213 1716 3213 1714 3213 1705 3214 1714 3214 1708 3214 1708 3215 1714 3215 1712 3215 1708 3216 1712 3216 1706 3216 1706 3217 1712 3217 1710 3217 1706 3218 1710 3218 1700 3218 1244 3219 1129 3219 1720 3219 1720 3220 1129 3220 1191 3220 1721 3221 1722 3221 1723 3221 1724 3222 1725 3222 1726 3222 1726 3223 1725 3223 1727 3223 1726 3224 1727 3224 1728 3224 1728 3225 1727 3225 1729 3225 1730 3226 1729 3226 1731 3226 1731 3227 1729 3227 1727 3227 1731 3228 1727 3228 1732 3228 1732 3229 1727 3229 1725 3229 1732 3230 1725 3230 1733 3230 1733 3231 1725 3231 1724 3231 1733 3232 1724 3232 1697 3232 1692 3233 1691 3233 1696 3233 1696 3234 1691 3234 1734 3234 1696 3235 1734 3235 1694 3235 1735 3236 1736 3236 1737 3236 1738 3237 1735 3237 1739 3237 1739 3238 1735 3238 1737 3238 1739 3239 1737 3239 1740 3239 1738 3240 1741 3240 1735 3240 1735 3241 1741 3241 1742 3241 1735 3242 1742 3242 1722 3242 1743 3243 1744 3243 1745 3243 1744 3244 1685 3244 1745 3244 1745 3245 1685 3245 1746 3245 1745 3246 1746 3246 1747 3246 1748 3247 1749 3247 1750 3247 1698 3248 1688 3248 1699 3248 1699 3249 1688 3249 1690 3249 1699 3250 1690 3250 1682 3250 1686 3251 1685 3251 1751 3251 1751 3252 1685 3252 1744 3252 1751 3253 1744 3253 1752 3253 1752 3254 1744 3254 1743 3254 1752 3255 1743 3255 1692 3255 1692 3256 1743 3256 1745 3256 1692 3257 1745 3257 1693 3257 1693 3258 1745 3258 1747 3258 1693 3259 1747 3259 1691 3259 1691 3260 1747 3260 1753 3260 1691 3261 1753 3261 1734 3261 1697 3262 1699 3262 1733 3262 1733 3263 1699 3263 1682 3263 1733 3264 1682 3264 1732 3264 1732 3265 1682 3265 1684 3265 1732 3266 1684 3266 1731 3266 1731 3267 1684 3267 1754 3267 1731 3268 1754 3268 1730 3268 1755 3269 1756 3269 1757 3269 1757 3270 1756 3270 1758 3270 1757 3271 1758 3271 1720 3271 1709 3272 1759 3272 1710 3272 1710 3273 1759 3273 1760 3273 1710 3274 1760 3274 1700 3274 1700 3275 1760 3275 1761 3275 1700 3276 1761 3276 1187 3276 1187 3277 1761 3277 1189 3277 1762 3278 1759 3278 1763 3278 1763 3279 1759 3279 1709 3279 1763 3280 1709 3280 1764 3280 1764 3281 1709 3281 1765 3281 1766 3282 1756 3282 1767 3282 1767 3283 1756 3283 1755 3283 1767 3284 1755 3284 1768 3284 1191 3285 1189 3285 1720 3285 1720 3286 1189 3286 1761 3286 1720 3287 1761 3287 1757 3287 1757 3288 1761 3288 1760 3288 1757 3289 1760 3289 1755 3289 1755 3290 1760 3290 1759 3290 1755 3291 1759 3291 1768 3291 1768 3292 1759 3292 1762 3292 1723 3293 1692 3293 1721 3293 1721 3294 1692 3294 1696 3294 1721 3295 1696 3295 1769 3295 1769 3296 1696 3296 1695 3296 1769 3297 1695 3297 1770 3297 1770 3298 1695 3298 1694 3298 1770 3299 1694 3299 1771 3299 1771 3300 1694 3300 1734 3300 1771 3301 1734 3301 1772 3301 1772 3302 1734 3302 1753 3302 1772 3303 1753 3303 1773 3303 1773 3304 1753 3304 1747 3304 1773 3305 1747 3305 1774 3305 1774 3306 1747 3306 1746 3306 1774 3307 1746 3307 1750 3307 1750 3308 1746 3308 1685 3308 1750 3309 1685 3309 1748 3309 1748 3310 1685 3310 1687 3310 1748 3311 1687 3311 1749 3311 1749 3312 1687 3312 1775 3312 1749 3313 1775 3313 1765 3313 1765 3314 1775 3314 1776 3314 1765 3315 1776 3315 1764 3315 1371 3316 1349 3316 1777 3316 1777 3317 1349 3317 1348 3317 1777 3318 1348 3318 1778 3318 1348 3319 1346 3319 1778 3319 1778 3320 1346 3320 1345 3320 1778 3321 1345 3321 1779 3321 1779 3322 1345 3322 1377 3322 1779 3323 1377 3323 1780 3323 1780 3324 1377 3324 1344 3324 1344 3325 1343 3325 1780 3325 1780 3326 1343 3326 1342 3326 1780 3327 1342 3327 1318 3327 1781 3328 1782 3328 1783 3328 1783 3329 1782 3329 1784 3329 1783 3330 1784 3330 1785 3330 1736 3331 1735 3331 1786 3331 1786 3332 1735 3332 1787 3332 1786 3333 1787 3333 1788 3333 1788 3334 1787 3334 1789 3334 1788 3335 1789 3335 1790 3335 1790 3336 1789 3336 1781 3336 1790 3337 1781 3337 1791 3337 1791 3338 1781 3338 1783 3338 1791 3339 1783 3339 1792 3339 1792 3340 1783 3340 1785 3340 1792 3341 1785 3341 1793 3341 1371 3342 1777 3342 1380 3342 1380 3343 1777 3343 1157 3343 1380 3344 1157 3344 1156 3344 1779 3345 1784 3345 1778 3345 1778 3346 1784 3346 1782 3346 1778 3347 1782 3347 1777 3347 1777 3348 1782 3348 1215 3348 1777 3349 1215 3349 1157 3349 1789 3350 1210 3350 1208 3350 1789 3351 1208 3351 1781 3351 1781 3352 1208 3352 1207 3352 1781 3353 1207 3353 1782 3353 1782 3354 1207 3354 1213 3354 1782 3355 1213 3355 1215 3355 1249 3356 1248 3356 1794 3356 1794 3357 1248 3357 1681 3357 1794 3358 1681 3358 1795 3358 1766 3359 1795 3359 1756 3359 1756 3360 1795 3360 1681 3360 1756 3361 1681 3361 1758 3361 1758 3362 1681 3362 1222 3362 1758 3363 1222 3363 1720 3363 1720 3364 1222 3364 1221 3364 1720 3365 1221 3365 1244 3365 1199 3366 1174 3366 1704 3366 1704 3367 1174 3367 1175 3367 1704 3368 1175 3368 1702 3368 1702 3369 1175 3369 1176 3369 1702 3370 1176 3370 1703 3370 1703 3371 1176 3371 1220 3371 1703 3372 1220 3372 1796 3372 1796 3373 1220 3373 1219 3373 1796 3374 1219 3374 1218 3374 1728 3375 1769 3375 1726 3375 1726 3376 1769 3376 1770 3376 1726 3377 1770 3377 1724 3377 1724 3378 1770 3378 1771 3378 1724 3379 1771 3379 1697 3379 1697 3380 1771 3380 1772 3380 1697 3381 1772 3381 1698 3381 1698 3382 1772 3382 1773 3382 1698 3383 1773 3383 1688 3383 1688 3384 1773 3384 1774 3384 1688 3385 1774 3385 1689 3385 1689 3386 1774 3386 1750 3386 1689 3387 1750 3387 1690 3387 1690 3388 1750 3388 1749 3388 1690 3389 1749 3389 1682 3389 1682 3390 1749 3390 1765 3390 1682 3391 1765 3391 1683 3391 1683 3392 1765 3392 1709 3392 1683 3393 1709 3393 1684 3393 1684 3394 1709 3394 1711 3394 1684 3395 1711 3395 1754 3395 1754 3396 1711 3396 1713 3396 1754 3397 1713 3397 1730 3397 1730 3398 1713 3398 1715 3398 1730 3399 1715 3399 1729 3399 1729 3400 1715 3400 1717 3400 1729 3401 1717 3401 1728 3401 1728 3402 1717 3402 1719 3402 1728 3403 1719 3403 1769 3403 1769 3404 1719 3404 1701 3404 1769 3405 1701 3405 1721 3405 1721 3406 1701 3406 1703 3406 1721 3407 1703 3407 1722 3407 1722 3408 1703 3408 1796 3408 1722 3409 1796 3409 1735 3409 1735 3410 1796 3410 1218 3410 1735 3411 1218 3411 1787 3411 1787 3412 1218 3412 1217 3412 1787 3413 1217 3413 1789 3413 1789 3414 1217 3414 1212 3414 1789 3415 1212 3415 1210 3415 1246 3416 1245 3416 1797 3416 1786 3417 1798 3417 1799 3417 1800 3418 1801 3418 1802 3418 1328 3419 1327 3419 1803 3419 1258 3420 1257 3420 1804 3420 1722 3421 1742 3421 1805 3421 1805 3422 1742 3422 1741 3422 1741 3423 1738 3423 1805 3423 1805 3424 1738 3424 1739 3424 1805 3425 1739 3425 1806 3425 1806 3426 1739 3426 1740 3426 1806 3427 1740 3427 1737 3427 1686 3428 1751 3428 1807 3428 1807 3429 1751 3429 1752 3429 1807 3430 1752 3430 1692 3430 1692 3431 1723 3431 1807 3431 1807 3432 1723 3432 1722 3432 1807 3433 1722 3433 1686 3433 1686 3434 1722 3434 1808 3434 1686 3435 1808 3435 1687 3435 1687 3436 1808 3436 1809 3436 1687 3437 1809 3437 1775 3437 1775 3438 1809 3438 1810 3438 1775 3439 1810 3439 1776 3439 1776 3440 1810 3440 1764 3440 1737 3441 1736 3441 1806 3441 1806 3442 1736 3442 1786 3442 1806 3443 1786 3443 1805 3443 1805 3444 1786 3444 1799 3444 1805 3445 1799 3445 1722 3445 1722 3446 1799 3446 1811 3446 1722 3447 1811 3447 1808 3447 1808 3448 1811 3448 1812 3448 1808 3449 1812 3449 1809 3449 1809 3450 1812 3450 1813 3450 1809 3451 1813 3451 1810 3451 1810 3452 1813 3452 1814 3452 1810 3453 1814 3453 1764 3453 1764 3454 1814 3454 1815 3454 1764 3455 1815 3455 1763 3455 1763 3456 1815 3456 1762 3456 1816 3457 1817 3457 1766 3457 1249 3458 1794 3458 1250 3458 1250 3459 1794 3459 1818 3459 1817 3460 1797 3460 1818 3460 1818 3461 1794 3461 1817 3461 1817 3462 1794 3462 1795 3462 1817 3463 1795 3463 1766 3463 1766 3464 1767 3464 1816 3464 1816 3465 1767 3465 1768 3465 1816 3466 1768 3466 1819 3466 1797 3467 1245 3467 1818 3467 1818 3468 1245 3468 1247 3468 1818 3469 1247 3469 1250 3469 1820 3470 1821 3470 1822 3470 1822 3471 1821 3471 1823 3471 1823 3472 1824 3472 1822 3472 1822 3473 1824 3473 1825 3473 1822 3474 1825 3474 1826 3474 1826 3475 1825 3475 1827 3475 1826 3476 1827 3476 1828 3476 1828 3477 1827 3477 1829 3477 1830 3478 1831 3478 1832 3478 1832 3479 1831 3479 1833 3479 1832 3480 1833 3480 1834 3480 1834 3481 1833 3481 1835 3481 1834 3482 1835 3482 1836 3482 1836 3483 1835 3483 1837 3483 1836 3484 1837 3484 1838 3484 1838 3485 1837 3485 1829 3485 1838 3486 1829 3486 1839 3486 1839 3487 1829 3487 1827 3487 1824 3488 1840 3488 1825 3488 1825 3489 1840 3489 1841 3489 1825 3490 1841 3490 1827 3490 1827 3491 1841 3491 1842 3491 1827 3492 1842 3492 1839 3492 1327 3493 1258 3493 1803 3493 1803 3494 1258 3494 1804 3494 1803 3495 1804 3495 1843 3495 1318 3496 1844 3496 1780 3496 1780 3497 1844 3497 1779 3497 1319 3498 1320 3498 1845 3498 1318 3499 1317 3499 1844 3499 1844 3500 1317 3500 1316 3500 1844 3501 1316 3501 1315 3501 1784 3502 1779 3502 1846 3502 1846 3503 1779 3503 1844 3503 1846 3504 1844 3504 1847 3504 1791 3505 1792 3505 1848 3505 1848 3506 1792 3506 1793 3506 1849 3507 1793 3507 1785 3507 1321 3508 1324 3508 1850 3508 1850 3509 1324 3509 1851 3509 1850 3510 1851 3510 1800 3510 1800 3511 1851 3511 1852 3511 1800 3512 1852 3512 1801 3512 1324 3513 1323 3513 1851 3513 1851 3514 1323 3514 1261 3514 1851 3515 1261 3515 1852 3515 1852 3516 1261 3516 1260 3516 1852 3517 1260 3517 1330 3517 1320 3518 1321 3518 1845 3518 1845 3519 1321 3519 1850 3519 1845 3520 1850 3520 1853 3520 1853 3521 1850 3521 1800 3521 1853 3522 1800 3522 1854 3522 1854 3523 1800 3523 1802 3523 1854 3524 1802 3524 1855 3524 1793 3525 1849 3525 1848 3525 1848 3526 1849 3526 1856 3526 1848 3527 1856 3527 1857 3527 1791 3528 1848 3528 1858 3528 1858 3529 1848 3529 1857 3529 1858 3530 1857 3530 1859 3530 1856 3531 1860 3531 1857 3531 1857 3532 1860 3532 1786 3532 1857 3533 1786 3533 1859 3533 1859 3534 1786 3534 1788 3534 1859 3535 1788 3535 1858 3535 1858 3536 1788 3536 1790 3536 1858 3537 1790 3537 1791 3537 1798 3538 1786 3538 1861 3538 1861 3539 1786 3539 1860 3539 1861 3540 1860 3540 1862 3540 1862 3541 1860 3541 1856 3541 1862 3542 1856 3542 1847 3542 1847 3543 1856 3543 1849 3543 1847 3544 1849 3544 1846 3544 1846 3545 1849 3545 1785 3545 1846 3546 1785 3546 1784 3546 1315 3547 1319 3547 1844 3547 1844 3548 1319 3548 1845 3548 1844 3549 1845 3549 1847 3549 1847 3550 1845 3550 1853 3550 1847 3551 1853 3551 1862 3551 1862 3552 1853 3552 1854 3552 1862 3553 1854 3553 1861 3553 1861 3554 1854 3554 1855 3554 1861 3555 1855 3555 1798 3555 1798 3556 1855 3556 1863 3556 1798 3557 1863 3557 1799 3557 1799 3558 1863 3558 1864 3558 1799 3559 1864 3559 1811 3559 1811 3560 1864 3560 1865 3560 1811 3561 1865 3561 1812 3561 1812 3562 1865 3562 1866 3562 1812 3563 1866 3563 1813 3563 1813 3564 1866 3564 1867 3564 1813 3565 1867 3565 1814 3565 1830 3566 1256 3566 1255 3566 1830 3567 1255 3567 1831 3567 1831 3568 1255 3568 1254 3568 1831 3569 1254 3569 1251 3569 1251 3570 1246 3570 1831 3570 1831 3571 1246 3571 1797 3571 1831 3572 1797 3572 1833 3572 1833 3573 1797 3573 1817 3573 1833 3574 1817 3574 1835 3574 1835 3575 1817 3575 1816 3575 1835 3576 1816 3576 1837 3576 1837 3577 1816 3577 1819 3577 1837 3578 1819 3578 1829 3578 1829 3579 1819 3579 1868 3579 1829 3580 1868 3580 1828 3580 1828 3581 1868 3581 1869 3581 1828 3582 1869 3582 1826 3582 1804 3583 1870 3583 1843 3583 1843 3584 1870 3584 1871 3584 1843 3585 1871 3585 1872 3585 1872 3586 1871 3586 1873 3586 1872 3587 1873 3587 1874 3587 1874 3588 1873 3588 1875 3588 1874 3589 1875 3589 1876 3589 1876 3590 1875 3590 1877 3590 1876 3591 1877 3591 1820 3591 1820 3592 1877 3592 1878 3592 1820 3593 1878 3593 1821 3593 1768 3594 1762 3594 1819 3594 1819 3595 1762 3595 1815 3595 1819 3596 1815 3596 1868 3596 1868 3597 1815 3597 1814 3597 1868 3598 1814 3598 1869 3598 1869 3599 1814 3599 1867 3599 1869 3600 1867 3600 1826 3600 1826 3601 1867 3601 1866 3601 1826 3602 1866 3602 1822 3602 1822 3603 1866 3603 1865 3603 1822 3604 1865 3604 1820 3604 1820 3605 1865 3605 1864 3605 1820 3606 1864 3606 1876 3606 1876 3607 1864 3607 1863 3607 1876 3608 1863 3608 1874 3608 1874 3609 1863 3609 1855 3609 1874 3610 1855 3610 1872 3610 1872 3611 1855 3611 1802 3611 1872 3612 1802 3612 1843 3612 1843 3613 1802 3613 1801 3613 1843 3614 1801 3614 1803 3614 1803 3615 1801 3615 1852 3615 1803 3616 1852 3616 1328 3616 1328 3617 1852 3617 1330 3617 1243 3618 1256 3618 1830 3618 1416 3619 1417 3619 1870 3619 1390 3620 1839 3620 1392 3620 1392 3621 1839 3621 1842 3621 1392 3622 1842 3622 1393 3622 1393 3623 1842 3623 1841 3623 1393 3624 1841 3624 1395 3624 1395 3625 1841 3625 1840 3625 1395 3626 1840 3626 1397 3626 1397 3627 1840 3627 1824 3627 1397 3628 1824 3628 1398 3628 1398 3629 1824 3629 1823 3629 1398 3630 1823 3630 1421 3630 1804 3631 1257 3631 1335 3631 1804 3632 1335 3632 1870 3632 1870 3633 1335 3633 1280 3633 1870 3634 1280 3634 1416 3634 1242 3635 1243 3635 1384 3635 1384 3636 1243 3636 1830 3636 1384 3637 1830 3637 1385 3637 1385 3638 1830 3638 1832 3638 1385 3639 1832 3639 1387 3639 1387 3640 1832 3640 1834 3640 1387 3641 1834 3641 1388 3641 1388 3642 1834 3642 1836 3642 1388 3643 1836 3643 1390 3643 1390 3644 1836 3644 1838 3644 1390 3645 1838 3645 1839 3645 1823 3646 1821 3646 1421 3646 1421 3647 1821 3647 1878 3647 1421 3648 1878 3648 1420 3648 1420 3649 1878 3649 1877 3649 1420 3650 1877 3650 1419 3650 1419 3651 1877 3651 1875 3651 1419 3652 1875 3652 1418 3652 1418 3653 1875 3653 1873 3653 1418 3654 1873 3654 1417 3654 1417 3655 1873 3655 1871 3655 1417 3656 1871 3656 1870 3656 1879 3657 1880 3657 1881 3657 1882 3658 1883 3658 1884 3658 432 3659 431 3659 1885 3659 452 3660 450 3660 1886 3660 451 3661 455 3661 1887 3661 318 3662 317 3662 1888 3662 243 3663 1889 3663 1890 3663 476 3664 1891 3664 199 3664 199 3665 1891 3665 200 3665 211 3666 203 3666 1892 3666 1892 3667 203 3667 202 3667 1892 3668 202 3668 1891 3668 1891 3669 202 3669 201 3669 1891 3670 201 3670 200 3670 1893 3671 249 3671 248 3671 248 3672 132 3672 1893 3672 1893 3673 132 3673 131 3673 1893 3674 131 3674 213 3674 1894 3675 252 3675 1893 3675 1893 3676 252 3676 250 3676 1893 3677 250 3677 249 3677 224 3678 1894 3678 1895 3678 224 3679 255 3679 1894 3679 1894 3680 255 3680 254 3680 1894 3681 254 3681 252 3681 217 3682 219 3682 1895 3682 219 3683 221 3683 1895 3683 1895 3684 221 3684 225 3684 1895 3685 225 3685 224 3685 238 3686 237 3686 1896 3686 238 3687 1896 3687 226 3687 235 3688 233 3688 1897 3688 1897 3689 233 3689 231 3689 1897 3690 231 3690 1898 3690 1898 3691 231 3691 229 3691 1898 3692 229 3692 227 3692 235 3693 1897 3693 236 3693 236 3694 1897 3694 1899 3694 236 3695 1899 3695 256 3695 256 3696 1899 3696 257 3696 257 3697 1899 3697 1900 3697 257 3698 1900 3698 259 3698 259 3699 1900 3699 1901 3699 259 3700 1901 3700 261 3700 243 3701 246 3701 1889 3701 1889 3702 246 3702 245 3702 1889 3703 245 3703 1901 3703 1901 3704 245 3704 262 3704 1901 3705 262 3705 261 3705 1902 3706 241 3706 1890 3706 1890 3707 241 3707 242 3707 1890 3708 242 3708 243 3708 290 3709 289 3709 1902 3709 1902 3710 289 3710 287 3710 1902 3711 287 3711 241 3711 285 3712 284 3712 278 3712 278 3713 284 3713 314 3713 278 3714 314 3714 279 3714 279 3715 314 3715 358 3715 358 3716 314 3716 313 3716 358 3717 313 3717 312 3717 318 3718 1888 3718 320 3718 312 3719 320 3719 358 3719 358 3720 320 3720 1888 3720 358 3721 1888 3721 357 3721 357 3722 1888 3722 1903 3722 333 3723 332 3723 1904 3723 1904 3724 332 3724 356 3724 1904 3725 356 3725 1905 3725 1905 3726 356 3726 355 3726 1905 3727 355 3727 354 3727 1887 3728 455 3728 1904 3728 1904 3729 455 3729 454 3729 1904 3730 454 3730 333 3730 1886 3731 450 3731 1887 3731 1887 3732 450 3732 449 3732 1887 3733 449 3733 451 3733 481 3734 1906 3734 482 3734 482 3735 1906 3735 1907 3735 482 3736 1907 3736 483 3736 481 3737 480 3737 1906 3737 1906 3738 480 3738 478 3738 1906 3739 478 3739 1886 3739 1886 3740 478 3740 479 3740 1886 3741 479 3741 452 3741 421 3742 422 3742 1908 3742 1908 3743 422 3743 423 3743 1908 3744 423 3744 1907 3744 1907 3745 423 3745 484 3745 1907 3746 484 3746 483 3746 421 3747 1908 3747 419 3747 419 3748 1908 3748 1909 3748 419 3749 1909 3749 417 3749 1879 3750 439 3750 1880 3750 1880 3751 439 3751 435 3751 1880 3752 435 3752 1885 3752 1885 3753 435 3753 434 3753 1885 3754 434 3754 432 3754 436 3755 441 3755 1879 3755 1879 3756 441 3756 440 3756 1879 3757 440 3757 439 3757 474 3758 473 3758 1883 3758 1883 3759 473 3759 438 3759 1883 3760 438 3760 1884 3760 1884 3761 438 3761 437 3761 212 3762 211 3762 1910 3762 1910 3763 211 3763 1892 3763 1910 3764 1892 3764 1911 3764 213 3765 212 3765 1893 3765 1893 3766 212 3766 1910 3766 1893 3767 1910 3767 1894 3767 1894 3768 1910 3768 1911 3768 1894 3769 1911 3769 1895 3769 317 3770 290 3770 1888 3770 1888 3771 290 3771 1902 3771 1888 3772 1902 3772 1903 3772 1903 3773 1902 3773 1890 3773 1903 3774 1890 3774 1912 3774 1912 3775 1890 3775 1889 3775 1912 3776 1889 3776 1913 3776 1913 3777 1889 3777 1901 3777 1913 3778 1901 3778 1914 3778 1914 3779 1901 3779 1900 3779 1914 3780 1900 3780 1915 3780 1915 3781 1900 3781 1899 3781 1915 3782 1899 3782 1916 3782 1916 3783 1899 3783 1897 3783 1916 3784 1897 3784 1917 3784 1917 3785 1897 3785 1898 3785 1917 3786 1898 3786 1918 3786 1919 3787 1920 3787 1921 3787 1921 3788 1920 3788 1922 3788 1921 3789 1922 3789 1923 3789 1923 3790 1922 3790 477 3790 1923 3791 477 3791 475 3791 476 3792 477 3792 1891 3792 1891 3793 477 3793 1922 3793 1891 3794 1922 3794 1892 3794 1892 3795 1922 3795 1920 3795 1892 3796 1920 3796 1911 3796 1911 3797 1920 3797 1919 3797 1911 3798 1919 3798 1895 3798 1895 3799 1919 3799 1896 3799 1895 3800 1896 3800 217 3800 217 3801 1896 3801 237 3801 431 3802 444 3802 1885 3802 1885 3803 444 3803 417 3803 1885 3804 417 3804 1880 3804 1880 3805 417 3805 1909 3805 1880 3806 1909 3806 1881 3806 475 3807 474 3807 1923 3807 1923 3808 474 3808 1883 3808 1923 3809 1883 3809 1921 3809 1921 3810 1883 3810 1882 3810 1921 3811 1882 3811 1919 3811 1919 3812 1882 3812 1918 3812 1919 3813 1918 3813 1896 3813 1896 3814 1918 3814 1898 3814 1896 3815 1898 3815 226 3815 226 3816 1898 3816 227 3816 437 3817 436 3817 1884 3817 1884 3818 436 3818 1879 3818 1884 3819 1879 3819 1882 3819 1882 3820 1879 3820 1881 3820 1882 3821 1881 3821 1918 3821 1918 3822 1881 3822 1909 3822 1918 3823 1909 3823 1917 3823 1917 3824 1909 3824 1908 3824 1917 3825 1908 3825 1916 3825 1916 3826 1908 3826 1907 3826 1916 3827 1907 3827 1915 3827 1915 3828 1907 3828 1906 3828 1915 3829 1906 3829 1914 3829 1914 3830 1906 3830 1886 3830 1914 3831 1886 3831 1913 3831 1913 3832 1886 3832 1887 3832 1913 3833 1887 3833 1912 3833 1912 3834 1887 3834 1904 3834 1912 3835 1904 3835 1903 3835 1903 3836 1904 3836 1905 3836 1903 3837 1905 3837 357 3837 357 3838 1905 3838 354 3838

+
+
+
+
+ + + + + 0.6858805 -0.3173701 0.6548619 7.481132 0.7276338 0.3124686 -0.6106656 -6.50764 -0.01081678 0.8953432 0.4452454 5.343665 0 0 0 1 + + + + -0.2908646 -0.7711008 0.5663932 4.076245 0.9551712 -0.1998834 0.2183912 1.005454 -0.05518906 0.6045247 0.7946723 5.903862 0 0 0 1 + + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + +
\ No newline at end of file diff --git a/libraries/SITL/examples/Webots_Python/protos/meshes/iris_prop_cw.dae b/libraries/SITL/examples/Webots_Python/protos/meshes/iris_prop_cw.dae new file mode 100644 index 0000000000..f939111fdb --- /dev/null +++ b/libraries/SITL/examples/Webots_Python/protos/meshes/iris_prop_cw.dae @@ -0,0 +1,160 @@ + + + + + Blender User + Blender 2.73.0 commit date:2015-01-07, commit time:13:17, hash:b4d8fb5 + + 2015-01-13T10:40:36 + 2015-01-13T10:40:36 + + Z_UP + + + + + + + 49.13434 + 1.777778 + 0.1 + 100 + + + + + + 0 + 0 + 0 + + + + + + + + + 1 1 1 + 1 + 0 + 0.00111109 + + + + + 0.000999987 + 1 + 0.1 + 0.1 + 1 + 1 + 1 + 2 + 0 + 1 + 1 + 1 + 1 + 1 + 0 + 2880 + 2 + 30.002 + 1.000799 + 0.04999995 + 29.99998 + 1 + 2 + 0 + 0 + 1 + 1 + 1 + 1 + 8192 + 1 + 1 + 0 + 1 + 1 + 1 + 3 + 0 + 0 + 0 + 0 + 0 + 1 + 1 + 1 + 3 + 0.15 + 75 + 1 + 1 + 0 + 1 + 1 + 0 + + + + + + + + + + 0.004280924 -3.49388e-4 0.005053937 8.01072e-4 9.88087e-5 0.005053937 7.80612e-4 -1.48083e-4 0.005053937 3.16992e-4 -0.001004755 0.005053937 0.003346145 -0.002840101 0.005053937 6.20291e-4 -6.15112e-4 0.005053937 0.003805875 -0.002070605 0.005053937 0.004120886 -0.001231372 0.005053937 -9.63807e-5 -0.001274824 0.005053937 0.002055525 -0.004074037 0.005053937 0.002756357 -0.003515124 0.005053937 -5.75051e-4 -0.001396059 0.005053937 -0.001067101 -0.00135529 0.005053937 -0.001370072 -0.00485593 0.005053937 -0.005618572 -7.93976e-4 0.005053937 -0.002117633 -3.8824e-4 0.005053937 -0.002198874 9.88087e-5 0.005053937 -0.002117633 5.85858e-4 0.005053937 -0.005618572 9.91593e-4 0.005053937 -0.005698919 9.88087e-5 0.005053937 -0.001882612 0.001020073 0.005053937 -0.004991114 0.002663254 0.005053937 -0.005380094 0.001855671 0.005053937 -4.74602e-4 -0.004896104 0.005053937 4.13686e-4 -0.004775822 0.005053937 0.001266181 -0.004498779 0.005053937 -0.001882612 -8.22511e-4 0.005053937 -0.003816366 -0.003810346 0.005053937 -0.001519322 -0.001156926 0.005053937 -0.003068268 -0.004304111 0.005053937 -0.002243995 -0.004656434 0.005053937 -0.005380094 -0.001658022 0.005053937 -0.004991114 -0.002465665 0.005053937 -0.004464268 -0.003190875 0.005053937 -5.75051e-4 0.001593649 0.005053937 -0.001370072 0.00505352 0.005053937 -0.001067101 0.001552879 0.005053937 -0.002243995 0.004854083 0.005053937 -0.001519322 0.001354515 0.005053937 -9.63807e-5 0.001472413 0.005053937 4.13686e-4 0.004973411 0.005053937 -4.74602e-4 0.005093753 0.005053937 -0.003068268 0.00450176 0.005053937 -0.003816366 0.004007935 0.005053937 -0.004464268 0.003388464 0.005053937 3.16992e-4 0.001202344 0.005053937 0.002055525 0.004271626 0.005053937 0.001266181 0.004696428 0.005053937 6.20291e-4 8.12729e-4 0.005053937 0.003346145 0.003037691 0.005053937 0.002756357 0.003712773 0.005053937 0.004301071 9.88087e-5 0.005053937 0.004280924 5.47005e-4 0.005053937 7.80612e-4 3.457e-4 0.005053937 0.004120886 0.001428961 0.005053937 0.003805875 0.002268195 0.005053937 7.80612e-4 3.457e-4 -0.0023247 8.01072e-4 9.88087e-5 -0.0023247 7.80612e-4 -1.48083e-4 -0.0023247 6.20291e-4 -6.15112e-4 -0.0023247 3.16992e-4 -0.001004755 -0.0023247 -9.63807e-5 -0.001274824 -0.0023247 -5.75051e-4 -0.001396059 -0.0023247 -0.001067101 -0.00135529 -0.0023247 -0.001519322 -0.001156926 -0.0023247 -0.001882612 -8.22511e-4 -0.0023247 -0.002117633 -3.8824e-4 -0.0023247 -0.002198874 9.88087e-5 -0.0023247 -0.002117633 5.85858e-4 -0.0023247 -0.001882612 0.001020073 -0.0023247 -0.001519322 0.001354515 -0.0023247 -0.001067101 0.001552879 -0.0023247 -5.75051e-4 0.001593649 -0.0023247 -9.63807e-5 0.001472413 -0.0023247 3.16992e-4 0.001202344 -0.0023247 6.20291e-4 8.12729e-4 -0.0023247 0.004280924 -3.49388e-4 -0.004945993 0.004301071 9.88087e-5 -0.004945993 0.004280924 5.47005e-4 -0.004945993 0.004120886 0.001428961 -0.004945993 0.003805875 0.002268195 -0.004945993 0.003346145 0.003037691 -0.004945993 0.002756357 0.003712773 -0.004945993 0.002055525 0.004271626 -0.004945993 0.001266181 0.004696428 -0.004945993 4.13686e-4 0.004973411 -0.004945993 -4.74602e-4 0.005093753 -0.004945993 -0.001370072 0.00505352 -0.004945993 -0.002243995 0.004854083 -0.004945993 -0.003068268 0.00450176 -0.004945993 -0.003816366 0.004007935 -0.004945993 -0.004464268 0.003388464 -0.004945993 -0.004991114 0.002663254 -0.004945993 -0.005380094 0.001855671 -0.004945993 -0.005618572 9.91593e-4 -0.004945993 -0.005698919 9.88087e-5 -0.004945993 -0.005618572 -7.93976e-4 -0.004945993 -0.005380094 -0.001658022 -0.004945993 -0.004991114 -0.002465665 -0.004945993 -0.004464268 -0.003190875 -0.004945993 -0.003816366 -0.003810346 -0.004945993 -0.003068268 -0.004304111 -0.004945993 -0.002243995 -0.004656434 -0.004945993 -0.001370072 -0.00485593 -0.004945993 -4.74602e-4 -0.004896104 -0.004945993 4.13686e-4 -0.004775822 -0.004945993 0.001266181 -0.004498779 -0.004945993 0.002055525 -0.004074037 -0.004945993 0.002756357 -0.003515124 -0.004945993 0.003346145 -0.002840101 -0.004945993 0.003805875 -0.002070605 -0.004945993 0.004120886 -0.001231372 -0.004945993 0.002231001 0.001790404 -0.004845976 0.002231001 0.001790404 -0.0023247 -6.98924e-4 0.003482043 -0.004845976 -6.98924e-4 0.003482043 -0.0023247 -0.003628849 0.001790404 -0.004845976 -0.003628849 0.001790404 -0.0023247 -0.003628849 -0.001592755 -0.004845976 -0.003628849 -0.001592755 -0.0023247 -6.98924e-4 -0.003284394 -0.004845976 -6.98924e-4 -0.003284394 -0.0023247 0.002231001 -0.001592755 -0.0023247 0.002231001 -0.001592755 -0.004845976 0.002260327 -0.001609683 -0.004916667 0.002238631 -0.001597166 -0.004884243 0.002238631 0.001794815 -0.004884243 0.002244412 0.001798152 -0.004895985 0.002262711 0.001808702 -0.004914283 0.002292752 -0.001628398 -0.004938364 0.00228101 0.001819252 -0.004932582 0.002293467 0.001826405 -0.00493592 0.002331018 0.001848161 -0.004945993 0.002331018 -0.001650512 -0.004945993 -6.98924e-4 0.003490805 -0.004884243 -6.98924e-4 0.003497481 -0.004895985 -6.98924e-4 0.00351864 -0.004914283 -6.98924e-4 0.003539741 -0.004932582 -6.98924e-4 0.003554105 -0.00493592 -6.98924e-4 0.003597497 -0.004945993 -0.003636479 0.001794815 -0.004884243 -0.003658175 0.001807332 -0.004916667 -0.0036906 0.001826047 -0.004938364 -0.003728866 0.001848161 -0.004945993 -0.003636479 -0.001597166 -0.004884243 -0.003658175 -0.001609683 -0.004916667 -0.0036906 -0.001628398 -0.004938364 -0.003728866 -0.001650512 -0.004945993 -6.98924e-4 -0.003293216 -0.004884243 -6.98924e-4 -0.00331819 -0.004916667 -6.98924e-4 -0.003355681 -0.004938364 -6.98924e-4 -0.003399848 -0.004945993 -7.03156e-4 -0.004901885 1.64569e-5 -7.03722e-4 -0.00490117 1.074e-5 -6.98924e-4 -0.00490117 1.03028e-4 -7.02426e-4 -0.00490278 2.45213e-5 -7.00653e-4 -0.00490427 4.84451e-5 -7.01174e-4 -0.004903972 4.05125e-5 -7.0177e-4 -0.004903435 3.2539e-5 -6.99505e-4 -0.004904031 7.20192e-5 -6.99818e-4 -0.00490427 6.41956e-5 -7.00206e-4 -0.004904389 5.63385e-5 -6.98969e-4 -0.004902184 9.53143e-5 -6.99073e-4 -0.004902958 8.7576e-5 -6.99252e-4 -0.004903614 7.9812e-5 -0.003919541 0.003923654 -0.001075148 -0.003919363 0.003923535 -0.001073122 -0.003922164 0.003921151 -0.001142859 -0.003920853 0.003924369 -0.001095473 -0.003920435 0.00392425 -0.001088619 -0.003920018 0.003924012 -0.001081705 -0.003921687 0.003923833 -0.001115918 -0.003921449 0.003924131 -0.001109123 -0.003921151 0.00392431 -0.001102328 -0.003922104 0.003922045 -0.001136183 -0.003922045 0.00392276 -0.001129448 -0.003921866 0.003923356 -0.001122713 0.009114444 -0.006102979 2.46061e-4 0.009207785 -0.005899012 1.12609e-4 0.01076149 -0.006091773 -1.28075e-5 0.01595389 -0.004363059 -0.001631557 0.01678526 -0.004452288 -0.001654803 0.01675945 -0.005290865 -0.001281142 0.01892793 -0.004682242 -0.001714646 0.01976054 -0.004718661 -0.001699626 0.01973795 -0.00538659 -0.001391708 0.03863102 -0.003488719 7.54078e-5 0.04343777 -0.003348231 6.30885e-4 0.04336595 -0.005101799 0.001442909 0.09390139 -0.003329336 0.001717686 0.09685456 -0.003185212 0.001672565 0.09682905 -0.004158496 0.001975178 0.09982579 -0.003040194 0.001627147 0.1011865 -0.009222269 0.002714812 0.1011025 -0.009727358 0.002804994 0.09968066 -0.01007646 0.002980828 0.1010371 -0.01012384 0.002869725 0.1008503 -0.01125639 0.003054678 0.1022341 -0.002922654 0.001590371 0.1017608 -0.005768775 0.002098381 0.1012549 -0.005756855 0.002109467 0.08463895 -0.003566741 0.001703023 0.09049308 -0.003416657 0.001712322 0.09089452 -0.004016876 0.001995205 0.09091544 -0.003405869 0.001712977 0.06710135 -0.005227744 0.002506852 0.07123064 -0.003616154 0.001637279 0.07897782 -0.005310237 0.002562403 0.07868301 -0.003588676 0.001673817 0.07904326 -0.003587365 0.001675605 0.05505269 -0.003453433 0.001496374 0.05528962 -0.00345689 0.00150609 0.05528175 -0.003612101 0.001617491 0.0557484 -0.003463566 0.001524806 0.06686091 -0.00357306 0.00160551 0.0671693 -0.003576099 0.001607775 0.05043619 -0.00338608 0.001307666 0.04934704 -0.00356853 0.001339077 0.04935801 -0.003374576 0.001206517 0.0437566 -0.003338873 6.67731e-4 0.04436421 -0.003321111 7.37948e-4 0.04934102 -0.003374397 0.001204907 0.03156125 -0.005112588 -2.09279e-4 0.03160762 -0.00398755 -7.45664e-4 0.03286665 -0.003898143 -5.98475e-4 0.03828549 -0.003513216 3.50187e-5 0.02477592 -0.004671275 -0.001462996 0.02568829 -0.004578411 -0.001367807 0.02566146 -0.005280494 -0.001026093 0.02746218 -0.004397928 -0.001182734 0.03123688 -0.004013895 -7.8901e-4 0.02174133 -0.004805326 -0.001663744 0.02178055 -0.004803597 -0.001661121 0.02470213 -0.004674553 -0.001467883 0.01884055 -0.004672825 -0.001712203 0.009541928 -0.005169332 -3.6484e-4 0.009791314 -0.004624783 -7.21134e-4 0.01078283 -0.004748225 -8.03023e-4 0.009864985 -0.004463851 -8.26405e-4 0.01544487 -0.004308462 -0.001617312 0.01377236 -0.005075275 -0.001058816 0.01379477 -0.004034936 -0.001536011 0.01078724 -0.003536403 -0.001387774 0.01031249 -0.003457725 -0.001364409 0.008373081 -0.007505238 0.001708865 0.008585751 -0.007166981 0.00120002 0.01072508 -0.007341563 0.001001656 0.008840322 -0.006654679 7.40685e-4 0.008306145 -0.007611751 0.001869082 0.008318901 -0.007591485 0.001838564 0.01069509 -0.008162498 0.002285778 0.010706 -0.00785464 0.001646161 0.01122009 -0.008283495 0.002377331 0.01367348 -0.008134782 0.001424491 0.01959258 -0.008956611 0.001797735 0.01659268 -0.009353935 0.003216624 0.0166226 -0.008801639 0.001937508 0.01374161 -0.00882852 0.002796053 0.01365345 -0.008561015 0.00215274 0.0136407 -0.008809924 0.002781152 0.01295733 -0.008683979 0.002680361 0.01954734 -0.009831488 0.003607749 0.01929605 -0.00979793 0.003579199 0.01955235 -0.009742319 0.00333029 0.0182287 -0.009655416 0.003457903 0.02546972 -0.01055914 0.004184007 0.02489006 -0.01049864 0.004143953 0.02547484 -0.01038539 0.003857016 0.02329915 -0.01033252 0.004034101 0.02272558 -0.01025593 0.003968954 0.03139436 -0.01114964 0.004450738 0.03044682 -0.0110597 0.004430949 0.03139567 -0.01104831 0.004341363 0.02929192 -0.01095008 0.004406809 0.02843815 -0.01086908 0.004388988 0.03392773 -0.01139008 0.004503607 0.03731662 -0.01134318 0.004209578 0.03731691 -0.01169645 0.004481554 0.04160404 -0.01208394 0.004453599 0.04323399 -0.01163011 0.00420022 0.04323881 -0.01223164 0.004442989 0.04915237 -0.01187723 0.004308164 0.04720389 -0.01254558 0.004402935 0.04360812 -0.01226502 0.004440546 0.05507856 -0.01205283 0.004413783 0.05281603 -0.0129835 0.004344165 0.04916256 -0.01269841 0.004382431 0.06071335 -0.01335126 0.004174113 0.0550903 -0.0130952 0.004297256 0.05306774 -0.01300311 0.004341542 0.06102395 -0.01335519 0.004166245 0.06101745 -0.01090151 0.004360496 0.06483685 -0.01340305 0.004069745 0.06696373 -0.01096022 0.004173398 0.07687914 -0.0132988 0.003767967 0.07884395 -0.01249754 0.003832936 0.07749384 -0.0132876 0.003752648 0.07884353 -0.01322591 0.003725111 0.06858897 -0.01345014 0.003974735 0.06696212 -0.01342976 0.004015922 0.07885181 -0.01108962 0.003910839 0.09299784 -0.01234978 0.00340712 0.09072732 -0.01253491 0.003463804 0.09073483 -0.01128083 0.003645539 0.08890467 -0.01268357 0.003509342 0.08844 -0.01272147 0.003520965 0.09913939 -0.01153665 0.003149151 0.09835696 -0.01166486 0.003192305 0.09668153 -0.01145279 0.00332266 0.09667766 -0.01187944 0.003259658 0.09489548 -0.01210725 0.003331065 0.0166679 -0.00782752 6.1091e-4 0.01961505 -0.008476018 0.00112611 0.01369488 -0.007624149 7.88715e-4 0.01963865 -0.007943153 5.14291e-4 0.02260351 -0.007966935 5.55349e-4 0.0255388 -0.008492231 0.00131601 0.02555984 -0.007916986 7.78756e-4 0.03146505 -0.007832586 0.001383543 0.01809751 -0.009631216 0.003438591 0.01957154 -0.009380221 0.002531766 0.02550268 -0.009524881 0.002505362 0.02551972 -0.00902903 0.001891076 0.03143179 -0.009032905 0.002284944 0.03734052 -0.00913918 0.002739846 0.04327642 -0.007990419 0.002698481 0.05507814 -0.01081603 0.004389584 0.04915153 -0.01070338 0.004108011 0.04323559 -0.01051533 0.003745138 0.03732287 -0.01029765 0.003462016 0.03140866 -0.01010835 0.003268718 0.02548766 -0.009977638 0.003160357 0.0670098 -0.008175015 0.003677427 0.06698107 -0.009588181 0.0040102 0.0610606 -0.008165538 0.003859281 0.06103259 -0.009560823 0.004202246 0.05511736 -0.008138656 0.003844022 0.0550909 -0.009511828 0.004202425 0.04919022 -0.008089601 0.003385663 0.04916417 -0.009439527 0.003804028 0.04324984 -0.009300708 0.00324577 0.090752 -0.009798884 0.003642857 0.09077757 -0.008338928 0.00344634 0.09670072 -0.009956121 0.003301143 0.09672772 -0.008499085 0.003073334 0.09970879 -0.008626639 0.002716422 0.1011968 -0.0086717 0.002621233 0.1012777 -0.008673787 0.002616941 0.09965819 -0.01145166 0.003120481 0.06704998 -0.006721377 0.003175139 0.06110179 -0.006715238 0.003323435 0.06115639 -0.005209565 0.002587258 0.09084969 -0.005454301 0.002597272 0.09976834 -0.005714297 0.00216943 0.09679305 -0.005609214 0.002377092 0.09081047 -0.006893157 0.003088116 0.0788958 -0.008230209 0.003575921 0.0788691 -0.009667277 0.00382626 0.0866025 -0.01287132 0.003566861 0.07893204 -0.00677812 0.003155291 0.01968795 -0.00674051 -5.40949e-4 0.01671493 -0.006635069 -4.47127e-4 0.01373714 -0.006419301 -2.5213e-4 0.05521261 -0.005188047 0.002560138 0.05515784 -0.006697058 0.003300666 0.04928183 -0.005150139 0.002160131 0.0492295 -0.006658315 0.002840757 0.04331517 -0.006589412 0.002098679 0.03150826 -0.006521701 5.54719e-4 0.02560728 -0.006661176 -1.89344e-4 0.0226528 -0.006742775 -4.74975e-4 0.09816354 0.007497012 -1.7873e-4 0.1038953 0.007092833 -8.31988e-5 0.1027694 2.96789e-4 0.001004755 0.03976333 0.002555072 -0.00234884 0.04529958 0.003440022 -0.001649498 0.04449719 -1.6207e-4 -4.67702e-4 0.01229608 0.001552522 -0.002744674 0.01230841 0.001597285 -0.002725601 0.01526743 0.001454293 -0.003397941 0.04954272 0.01013648 -0.003240704 0.04664981 0.009504079 -0.003528475 0.04684549 0.01042914 -0.003768384 0.04114824 0.008654236 -0.004291355 0.05271077 0.011675 -0.003260076 0.05871486 0.01238644 -0.002815723 0.05845838 0.01126611 -0.002518773 0.06665015 0.01352864 -0.002515792 0.07033759 0.01346588 -0.002305209 0.06929093 0.008346915 -0.001141667 0.1041265 0.008486807 -3.14278e-4 0.09892398 0.0120607 -9.83956e-4 0.104611 0.01140755 -7.98459e-4 0.1045539 0.01106309 -7.41353e-4 0.06461393 0.01343512 -0.002648234 0.0635094 0.008332788 -0.001403033 0.06764322 2.19451e-4 6.44472e-4 0.07769387 0.01334065 -0.001885175 0.08084756 0.008092463 -6.88597e-4 0.0817784 0.01311379 -0.001708269 0.09239667 0.007703363 -3.18953e-4 0.09722757 0.01225554 -0.001039266 0.09321534 0.01247841 -0.001213014 0.05889314 0.01315557 -0.003021657 0.05287671 0.01232516 -0.003453552 0.05134356 0.01211357 -0.003563582 0.04991424 0.01173901 -0.003674328 0.04699164 0.01097303 -0.003900825 0.04975593 0.01112812 -0.003508985 0.05248069 0.01062667 -0.002970993 0.0577358 0.008126497 -0.00168389 0.02368932 0.002654731 -0.00493288 0.02425444 0.002662837 -0.005073606 0.02128726 0.002171874 -0.004630386 0.01356196 0.001955389 -0.002693951 0.01537483 0.002007722 -0.003140568 0.0153712 0.00185436 -0.003220617 0.01833391 0.002093136 -0.003869652 0.01832246 0.001936674 -0.003975272 0.01996546 0.002140223 -0.004271626 0.02129507 0.002323925 -0.00450772 0.02424615 0.002823889 -0.004968285 0.02714419 0.00370419 -0.005152821 0.02714836 0.00356549 -0.005221247 0.02723896 0.003732979 -0.005158841 0.02994394 0.00471723 -0.005140364 0.01236635 0.001808643 -0.002635538 0.01535016 0.001752376 -0.003296792 0.01821196 0.001479268 -0.004125356 0.01829987 0.001817762 -0.004046201 0.02117747 0.001653671 -0.004742324 0.02126562 0.00203526 -0.004692196 0.02415466 0.002080857 -0.005140125 0.02423685 0.002508163 -0.005123198 0.02706211 0.002914905 -0.005242824 0.02713572 0.003392279 -0.005257725 0.02984565 0.003994941 -0.005124151 0.02992755 0.004525184 -0.005165159 0.0354107 0.005988895 -0.004674911 0.03553217 0.006633162 -0.004776835 0.04098933 0.007874071 -0.004118859 0.0355677 0.006868064 -0.004781961 0.04493612 0.01043432 -0.004060089 0.04126048 0.009103894 -0.004335522 0.03584432 0.007143378 -0.00474137 0.03558856 0.00704205 -0.004753828 0.02996206 0.00481218 -0.005026757 0.01178622 1.47263e-4 -0.002626061 0.01199358 7.18727e-4 -0.002674281 0.01493102 4.76282e-4 -0.003353834 0.01225477 0.001438617 -0.002735078 0.01785618 3.9762e-4 -0.003988683 0.02081209 4.59662e-4 -0.004504799 0.02379214 7.61879e-4 -0.004803895 0.02671062 0.001448631 -0.004825055 0.02947765 0.002368271 -0.004648447 0.03496617 0.004036664 -0.004088163 0.04047447 0.005564212 -0.003423273 0.04606401 0.006834924 -0.002740144 0.05182242 0.007663428 -0.002123892 0.03898537 -6.77845e-4 -0.00110048 0.03769552 -7.98549e-4 -0.001248598 0.0343042 0.001434743 -0.003053307 0.03354859 -0.001438558 -0.001742243 0.02887207 1.66199e-4 -0.003682672 0.02813684 -0.002273797 -0.00238645 0.02611666 -5.44473e-4 -0.003911852 0.02721524 -0.002416074 -0.002496182 0.02022337 -0.001193106 -0.003810465 0.01797717 -0.002950251 -0.00268805 0.01728749 -0.001123607 -0.003440678 0.01660698 -0.002784729 -0.00255078 0.01439094 -9.24482e-4 -0.00295484 0.02536857 -0.002657651 -0.002620518 0.02247339 -0.003036439 -0.002815425 0.02319467 -0.001042485 -0.003981769 0.02246224 -0.00303626 -0.002815127 0.0195105 -0.002979636 -0.002731502 0.0108934 -0.002094626 -0.001978158 0.01108181 -0.001629829 -0.002131402 0.07376223 1.93009e-4 7.62843e-4 0.09695792 2.16133e-4 0.00102663 0.09431344 1.79432e-4 0.001036584 0.09110814 1.8155e-4 9.93905e-4 0.07938075 1.89297e-4 8.37686e-4 0.01240569 0.00201267 -0.002452135 0.01239597 0.001944422 -0.002533555 0.01239359 0.001927554 -0.002553701 0.01238787 0.001886904 -0.002602159 0.05907517 0.01318073 -0.003008604 0.0115047 -5.86395e-4 -0.00247544 0.01165127 -2.24818e-4 -0.002594649 0.05099332 0.003964781 -0.001039147 0.05683743 0.004238247 -6.47306e-4 0.06177538 2.44808e-4 5.3096e-4 0.05628144 2.68549e-4 4.24682e-4 0.05591791 2.5952e-4 4.0007e-4 0.05014276 1.16061e-4 9.04733e-6 0.04650324 2.56533e-5 -2.37379e-4 0.01239359 0.002042293 -0.002322971 0.01238787 0.002056419 -0.002261281 0.01536321 0.001989603 -0.002911627 0.01232606 0.002007246 -0.002003312 0.01232051 0.002000391 -0.001984953 0.01529085 0.002011179 -0.002662658 0.03558754 0.007201969 -0.004679083 0.03559046 0.0071612 -0.004710912 0.02993214 0.004956424 -0.005012869 0.0123676 0.002040266 -0.002176642 0.01235532 0.002030551 -0.00212562 0.01533758 0.001982748 -0.00277704 0.03554517 0.007250785 -0.004501163 0.0355603 0.007255792 -0.004553079 0.02986907 0.005031466 -0.004795134 0.03840762 0.008359134 -0.004409492 0.04689514 0.01140433 -0.003898322 0.04702985 0.01143729 -0.003890693 0.04703146 0.01144349 -0.003901839 0.04557681 0.01098096 -0.004003822 0.04703354 0.01144003 -0.003918349 0.04703354 0.0114358 -0.003921151 0.05447763 0.01310962 -0.003458797 0.05297106 0.0128898 -0.003554642 0.05320841 0.01294785 -0.003541171 0.1046841 0.01184576 -8.80739e-4 0.09900712 0.01256084 -0.001083314 0.1046864 0.01185953 -8.84102e-4 0.1046867 0.01186126 -8.84622e-4 0.1046881 0.0118696 -8.87304e-4 0.1046885 0.01187157 -8.88169e-4 0.1046886 0.01187223 -8.88985e-4 0.1046879 0.01186859 -8.86834e-4 0.1046875 0.01186591 -8.86022e-4 0.08473533 0.01351094 -0.001692771 0.08759152 0.01334029 -0.00156778 0.08189767 0.0136578 -0.001805245 0.09330403 0.01299899 -0.001317799 0.09329879 0.01297581 -0.00130397 0.09742277 0.01275289 -0.001137554 0.08185648 0.01358044 -0.001766324 0.09328383 0.01291102 -0.001264035 0.09899359 0.01249659 -0.0010522 0.1046831 0.01184004 -8.79344e-4 0.06470197 0.01392221 -0.002747654 0.06735479 0.01411634 -0.002611994 0.07042402 0.01396536 -0.002388715 0.0704503 0.01404911 -0.002433419 0.07874172 0.0138691 -0.001955091 0.05894804 0.01341438 -0.003086566 0.05294698 0.01278299 -0.003541171 0.05898708 0.01358985 -0.003132224 0.05296444 0.01287472 -0.003557443 0.03842097 0.008327245 -0.004479408 0.04126548 0.009424686 -0.004294812 0.04126572 0.009409189 -0.004305601 0.04413104 0.01045531 -0.004116952 0.04412955 0.01043653 -0.004122853 0.04702627 0.01136875 -0.00393331 0.04703158 0.01140964 -0.003929495 0.04557669 0.01095443 -0.004020571 0.04413175 0.0104705 -0.004109919 0.04703295 0.01142454 -0.003925859 0.04557734 0.01096767 -0.00401467 0.04413163 0.01048225 -0.004101693 0.04126447 0.009436845 -0.004282891 0.03841876 0.008339881 -0.004463732 0.03558152 0.007231354 -0.004642128 0.05523276 0.01320588 -0.003409802 0.05561113 0.0132541 -0.003385245 0.05599033 0.01330244 -0.003360629 0.04851585 0.01180082 -0.003807127 0.04703229 0.01144748 -0.003908276 0.05000162 0.01216381 -0.003722608 0.0470333 0.01144337 -0.00391525 0.04557716 0.01097738 -0.004007697 0.04413002 0.01049339 -0.004087269 0.04412907 0.01049542 -0.004081904 0.04125684 0.009453833 -0.004240095 0.04125279 0.009452998 -0.004223644 0.04557627 0.01098358 -0.00399959 0.04412662 0.01049685 -0.004070401 0.04124796 0.009449064 -0.004206061 0.04851573 0.01180052 -0.00380665 0.02124285 0.002390801 -0.004182517 0.02120316 0.002417504 -0.003980696 0.02224731 0.002522587 -0.004210829 0.02418857 0.002921342 -0.00465089 0.02412617 0.002984762 -0.004434347 0.02584874 0.003408491 -0.004639267 0.02706032 0.003854334 -0.004836082 0.02699321 0.00386846 -0.004646182 0.01831459 0.002108931 -0.00366187 0.01828795 0.002111017 -0.003520131 0.02127271 0.002380669 -0.004325807 0.02422434 0.002905368 -0.004790067 0.02710163 0.003836274 -0.004966557 0.02990686 0.005013346 -0.004915118 0.0355724 0.007249295 -0.004600107 0.03841578 0.008349359 -0.004446804 0.04126268 0.009445726 -0.004269778 0.04126018 0.009451389 -0.004255533 0.04413074 0.01049053 -0.004092395 0.02953279 0.00488913 -0.004661619 0.02982181 0.005001902 -0.004650413 0.03552877 0.007228553 -0.004429221 0.03872895 0.00847721 -0.004305243 0.04126232 0.009385287 -0.004179 0.04125046 0.009246647 -0.00434488 0.03559035 0.007109224 -0.004737496 0.04700553 0.01124149 -0.003926634 0.04993897 0.01201432 -0.003716289 0.05291455 0.01262462 -0.003505587 0.05148684 0.01252692 -0.003638565 0.05296468 0.01288384 -0.003555774 0.03842198 0.008246183 -0.004529833 0.03842306 0.008292853 -0.004507124 0.04125875 0.009314119 -0.004336714 0.04126381 0.0093683 -0.004323601 0.04412412 0.01038843 -0.004131138 0.04701763 0.01131278 -0.003932356 0.04849082 0.01178431 -0.003836691 0.02994018 0.004913866 -0.005053281 0.02424716 0.002857506 -0.004906237 0.02128988 0.002341032 -0.004447162 0.02713012 0.003783106 -0.005073964 0.01239651 0.00203514 -0.002354145 0.01537704 0.001970231 -0.003029167 0.01832896 0.002079129 -0.003783822 0.02992105 0.004989624 -0.004966795 0.1046808 0.01182651 -8.76541e-4 0.1046701 0.0117619 -8.63167e-4 0.1046566 0.01168107 -8.48407e-4 0.08187931 0.01368159 -0.001817762 0.018251 0.002120614 -0.003330111 0.01723313 0.002018213 -0.003105819 0.05751544 0.01349681 -0.003261685 0.05902242 0.01368892 -0.003163874 0.06009376 0.01382547 -0.003094315 0.06473308 0.01401132 -0.002786159 0.01178419 0.001010656 -8.78131e-4 0.01153957 5.46128e-4 -3.99795e-4 0.01448857 4.80399e-4 -7.90174e-4 0.05769592 0.008141756 -0.001211106 0.05785888 0.004312157 -2.06479e-5 0.06261628 0.004347145 1.38751e-4 0.1045536 0.01107043 -6.8177e-4 0.1046022 0.01136052 -7.46045e-4 0.09892004 0.01207476 -8.94051e-4 0.1046565 0.01168507 -8.17969e-4 0.104668 0.01175361 -8.33152e-4 0.09899091 0.01248997 -0.001013696 0.1046885 0.01187199 -8.85736e-4 0.01108086 -4.638e-4 2.18396e-4 0.01093131 -7.93152e-4 4.19997e-4 0.0138486 -8.74206e-4 2.75653e-4 0.104155 0.008688271 -1.53891e-4 0.1043247 0.009702801 -3.78708e-4 0.09862154 0.01030075 -4.89405e-4 0.1041265 0.008517324 -1.22238e-4 0.06417208 0.01154088 -0.001860857 0.06538528 0.00436747 2.31527e-4 0.06992107 0.01155894 -0.001555562 0.06844288 0.004309296 2.90329e-4 0.08140653 0.01120173 -0.001048862 0.1033134 0.003629744 7.82746e-4 0.09753519 0.003747344 7.57675e-4 0.09172487 0.003865599 7.32465e-4 0.09288567 0.01063144 -6.51071e-4 0.09134888 0.003873229 7.30833e-4 0.08008897 0.004087567 5.14294e-4 0.02241867 -2.87815e-4 -6.4303e-4 0.01959055 -6.45687e-4 -3.77127e-4 0.01885569 -0.00227493 9.41604e-4 0.01808822 -0.002346336 9.74657e-4 0.01672828 -8.22505e-4 -4.55114e-5 0.01603287 -0.002329111 0.001071035 0.02164328 -0.002015531 8.21552e-4 0.02325618 -0.001865446 7.52089e-4 0.02519553 3.43026e-4 -7.67349e-4 0.02439594 -0.001639127 7.48668e-4 0.02803742 0.001143634 -7.63818e-4 0.02723437 -0.001075506 7.40151e-4 0.03278148 2.5942e-5 7.23506e-4 0.03390818 0.002754032 -8.27413e-4 0.033104 9.91365e-5 7.06737e-4 0.03978019 0.004495263 -0.001037776 0.03897476 0.001431465 4.01489e-4 0.04569375 0.006184697 -0.001257479 0.05599027 0.01330286 -0.003359973 0.0529747 0.01289379 -0.003541767 0.05901652 0.01372063 -0.003152668 0.04997628 0.01219838 -0.003682434 0.05296963 0.01288652 -0.003530621 0.04704284 0.01142609 -0.003854215 0.0529558 0.01287031 -0.003501594 0.04996246 0.01221776 -0.003661096 0.04993027 0.0121079 -0.003569245 0.0469684 0.01127982 -0.00369656 0.04700607 0.01139605 -0.003806591 0.04120612 0.009378492 -0.004063427 0.0268405 0.003676593 -0.004254341 0.02966058 0.004832983 -0.004240274 0.0411539 0.009253025 -0.003911674 0.03540503 0.007039964 -0.004088819 0.02398788 0.002754747 -0.004052281 0.01793462 0.001619517 -0.002458214 0.0208643 0.001912534 -0.003059089 0.01499879 0.001472532 -0.00181061 0.01226395 0.001921892 -0.001816272 0.01225823 0.001910984 -0.001805126 0.01201719 0.001453161 -0.001333713 0.1046878 0.01186859 -8.80268e-4 0.1046881 0.01187008 -8.82682e-4 0.1046883 0.01187092 -8.84006e-4 0.09900259 0.0125404 -0.001064419 0.1046856 0.01185649 -8.70684e-4 0.1046867 0.01186245 -8.75389e-4 0.1046745 0.01179283 -8.41852e-4 0.1046808 0.01182889 -8.58189e-4 0.1046835 0.01184481 -8.65379e-4 0.08187896 0.01370567 -0.001787781 0.09330362 0.01302492 -0.001286268 0.09616088 0.01284837 -0.001181185 0.09329909 0.01300668 -0.001264035 0.09330356 0.01302987 -0.001280367 0.0818789 0.01371109 -0.001781165 0.09328085 0.01290649 -0.001220941 0.0761649 0.01397162 -0.002084612 0.07044923 0.01410508 -0.00240314 0.07044935 0.01409679 -0.002407491 0.06472939 0.01405471 -0.002766788 0.06472867 0.01406329 -0.002763152 0.05901503 0.01372873 -0.003149986 0.08187395 0.01368725 -0.001761972 0.0704438 0.01408153 -0.002381205 0.06472295 0.01404035 -0.002740263 0.05900889 0.0137068 -0.00312674 0.08185362 0.01358318 -0.001711547 0.05292773 0.01276636 -0.003424465 0.05594515 0.01326066 -0.003258347 0.05898362 0.01360714 -0.003063976 0.06469911 0.01393741 -0.002679407 0.07042127 0.01397699 -0.002323329 0.09320497 0.01247537 -0.001090884 0.08176809 0.01313281 -0.001559913 0.07032585 0.01352113 -0.00214827 0.0645985 0.01348638 -0.002493798 0.05887752 0.01316845 -0.002870082 0.05584007 0.01282554 -0.003053426 0.05281925 0.01232838 -0.003196597 0.04981476 0.01166439 -0.003309071 0.04684281 0.01083093 -0.003397226 0.04099965 0.0088045 -0.003523349 0.03521728 0.006613969 -0.003614962 0.02943706 0.004456043 -0.00370872 0.02660977 0.003334641 -0.003710091 0.02377182 0.002438724 -0.003506898 0.01318794 -0.002305269 0.001204431 0.01213121 -0.002296388 0.001253962 0.01031249 -0.002155482 0.001253902 0.04395401 0.00256145 1.42596e-4 0.04488813 0.002723932 1.08691e-4 0.0486806 0.006896734 -0.001329481 0.05084222 0.003759682 -1.07422e-4 0.05168563 0.007465183 -0.001356184 0.05107909 0.003800868 -1.16017e-4 0.05469232 0.007880866 -0.001322925 0.05382794 0.004008173 -7.73496e-5 0.0567975 0.004232108 -3.55779e-5 0.01740044 5.98747e-4 -0.001293241 0.02029931 8.54927e-4 -0.001779794 0.02316826 0.001321434 -0.002156555 0.02597552 0.002114593 -0.002336859 0.02881407 0.003108918 -0.002346456 0.03465402 0.005061626 -0.002352654 0.04049432 0.007101714 -0.002429544 0.04638528 0.009032309 -0.002488136 0.04937118 0.009836673 -0.002483665 0.05238258 0.01047921 -0.002442181 0.05540257 0.01095598 -0.002352774 0.058429 0.01127183 -0.002200782 0.127301 0.00509876 -1.12772e-4 0.1246753 0.006482362 -2.19259e-4 0.1259892 0.005790054 -1.65976e-4 0.1105068 0.01052999 -6.70665e-4 0.1076027 0.01129508 -7.94702e-4 0.123362 0.007174491 -2.72526e-4 0.1220685 0.007728159 -3.08566e-4 0.1177737 0.009132862 -4.62362e-4 0.1163222 0.009446561 -5.09794e-4 0.1177173 0.009150862 -4.64213e-4 0.1212672 0.006399571 -1.6073e-4 0.1227788 0.001810848 2.86692e-4 0.1197593 0.006616413 -1.67396e-4 0.12106 0.001420378 3.75246e-4 0.1166622 0.007018923 -1.81989e-4 0.1243859 0.002175986 2.03902e-4 0.1227192 0.006170034 -1.55646e-4 0.1256383 0.002886116 9.02945e-5 0.1240602 0.005946516 -1.58082e-4 0.1163315 0.009434759 -5.03647e-4 0.1164072 0.008882462 -4.24234e-4 0.1193438 0.008250296 -3.4725e-4 0.1221945 0.007426679 -2.76372e-4 0.1248487 0.006372094 -2.11775e-4 0.1227063 0.00751996 -2.99116e-4 0.1224986 0.007629394 -3.07538e-4 0.1220169 0.007782697 -3.23324e-4 0.1206027 0.008232712 -3.69665e-4 0.1192439 0.008642256 -3.94406e-4 0.1191872 0.008683085 -4.16045e-4 0.1263098 0.005433917 -1.53476e-4 0.1252357 0.005714356 -1.62642e-4 0.1104037 0.007756054 -2.41931e-4 0.1104868 0.009993433 -5.83392e-4 0.1060914 0.01161545 -8.44081e-4 0.1105116 0.01065629 -6.93689e-4 0.1105093 0.01067888 -6.99731e-4 0.1134158 0.01006275 -6.04762e-4 0.116346 0.009329497 -4.86835e-4 0.1270681 0.004525125 -1.16847e-4 0.1269757 0.004404485 -1.02085e-4 0.1264106 0.003666162 -1.17528e-5 0.1259478 0.003061711 6.22091e-5 0.115354 9.59343e-4 6.41541e-4 0.1174682 0.001130163 5.42869e-4 0.1030377 0.001969933 0.001074373 0.1027694 3.5392e-4 0.001352608 0.1101418 6.87812e-4 0.001101672 0.1105117 0.01065862 -6.76881e-4 0.1174471 -0.007552564 0.001846015 0.118615 -0.007251143 0.001726806 0.1186151 -0.007229685 0.001745343 0.1097947 -0.008674323 0.002418935 0.1098781 -0.006425321 0.002146959 0.1014125 -0.007839322 0.002649247 0.1016464 -0.006421864 0.002455294 0.1275644 0.004252016 -8.75536e-5 0.127193 0.004763901 -1.00075e-4 0.1280632 -0.001006901 4.62034e-4 0.1281205 -8.58814e-4 4.41136e-4 0.1281238 -4.58027e-4 3.89399e-4 0.1248498 0.006374359 -1.8628e-4 0.1192446 0.008644998 -3.68077e-4 0.1008517 -0.01124686 0.003060638 0.100851 -0.01125138 0.003057837 0.109762 -0.009364485 0.002441942 0.1008508 -0.01125288 0.003056883 0.1163318 0.009436428 -4.89542e-4 0.1220689 0.007730126 -2.87308e-4 0.1221954 0.007430911 -2.30786e-4 0.1166651 0.007036089 -4.54313e-5 0.1197621 0.006629705 -4.50774e-5 0.1193451 0.008256256 -2.90791e-4 0.1276975 0.001542687 2.24064e-4 0.1269899 0.004396975 -5.51534e-5 0.1264685 0.00363332 8.13901e-5 0.1263105 0.005435526 -1.25119e-4 0.125238 0.005719363 -1.074e-4 0.1206084 -0.006736636 0.001523315 0.1208071 -0.006641328 0.001513719 0.1186009 -0.007121384 0.001749038 0.1207882 -0.006539106 0.001518368 0.1185402 -0.006668686 0.001725196 0.1229175 -0.005781948 0.001280307 0.1229324 -0.00586605 0.001263618 0.1208078 -0.006661951 0.001501023 0.1207077 -0.006111562 0.001500308 0.1228182 -0.005385458 0.00126785 0.1249276 -0.004750669 0.001052677 0.1248121 -0.004394292 0.001044869 0.1258955 -0.00421375 9.25828e-4 0.1258949 -0.004213094 9.25799e-4 0.1249262 -0.004802405 0.001036882 0.1239561 -0.005391597 0.001148104 0.1235651 -0.005629003 0.001192927 0.1182862 -0.004796504 0.001541256 0.1203708 -0.004342913 0.001344501 0.1224034 -0.00374484 0.001140296 0.1243306 -0.002919197 9.42979e-4 0.1260554 -0.001799881 7.44642e-4 0.1276689 0.003356873 -8.86293e-6 0.1240628 0.005954325 -7.8171e-5 0.125674 0.002846777 2.44687e-4 0.1261228 0.003238022 1.62117e-4 0.1272834 -2.67854e-4 5.00848e-4 0.1275754 6.28147e-4 3.60671e-4 0.1277896 -0.001251637 5.5342e-4 0.128032 -1.96275e-4 3.99275e-4 0.1267057 -0.003366053 8.27289e-4 0.1266791 -0.00340116 8.05273e-4 0.1274482 -0.002559781 6.93736e-4 0.1274538 -0.002579987 6.83993e-4 0.1274553 -0.002575814 6.8942e-4 0.1274468 -0.002597928 6.86526e-4 0.1270713 -0.002990841 7.44614e-4 0.1274183 -0.002494513 6.99344e-4 0.1272919 -0.002221226 6.96911e-4 0.1267646 -0.001090049 6.30826e-4 0.1250886 0.002491354 3.2028e-4 0.122721 0.006179511 -5.68782e-5 0.1276556 -0.002058744 6.1045e-4 0.1212691 0.006410777 -4.85354e-5 0.1278825 0.00302869 -4.2594e-6 0.1276815 0.004090726 -8.86936e-5 0.1281332 6.73593e-4 2.43322e-4 0.1281403 0.001534461 1.3219e-4 0.128084 8.82422e-4 2.49567e-4 0.1280959 0.001798987 1.08238e-4 0.1279075 0.002919197 6.80936e-6 0.1277097 0.004051923 -9.11234e-5 0.1278132 0.003480076 -4.39729e-5 0.1277164 0.004042685 -9.26885e-5 0.12772 0.004034519 -9.4173e-5 0.12786 -0.001531362 5.36036e-4 0.1281285 1.0744e-4 3.16405e-4 0.1259122 -0.004203557 9.23906e-4 0.1265798 -0.003061354 8.23147e-4 0.100855 -0.01122516 0.003066658 0.1008527 -0.01123929 0.003065407 0.1008523 -0.01124233 0.003063499 0.1097698 -0.009348988 0.002458691 0.1097746 -0.009218633 0.002460122 0.1008824 -0.01105517 0.003067016 0.1008693 -0.01113545 0.003071367 0.1008657 -0.01115739 0.003072559 0.1008582 -0.01120531 0.003068387 0.1009851 -0.01042914 0.003003597 0.1009297 -0.01076459 0.003049552 0.100922 -0.01081174 0.003053724 0.1111451 -0.009070813 0.002346813 0.1243887 0.002194106 3.85093e-4 0.1228004 0.001750886 4.94031e-4 0.1210837 0.001448452 5.98644e-4 0.1192979 0.001254498 7.04702e-4 0.1174767 0.001127541 8.0489e-4 0.110507 0.01053494 -6.35637e-4 0.1104874 0.0100041 -5.08287e-4 0.1164086 0.008890211 -3.61199e-4 0.1163466 0.009333074 -4.57438e-4 0.1104048 0.007779657 -7.92374e-5 0.127718 0.004039525 -9.4261e-5 0.1275097 0.004568755 -1.0351e-4 0.008014023 0.002546131 -0.001899242 0.007406651 0.002687275 -0.001830697 0.00738573 0.002683579 -0.00173068 0.001493036 -0.00565958 7.15594e-4 0.003685474 -0.006418168 0.001328229 0.003687381 -0.0063591 0.001431643 0.003705203 -0.006259977 0.001524209 -3.7609e-4 -0.004883587 3.92943e-4 -6.11365e-4 -0.004900634 2.33384e-4 -6.10009e-4 -0.004900634 2.35416e-4 0.001820027 -0.004220187 0.001236021 0.003793001 -0.005932688 0.001666784 0.001906394 -0.004155695 0.001244068 0.004185438 -0.004768252 0.0017277 0.002721726 -0.003547072 0.001319885 8.38801e-4 -0.004658997 9.81736e-4 2.20433e-4 -0.004796683 7.21453e-4 -6.94692e-5 -0.004861235 5.99431e-4 0.003361403 -0.002818822 0.001257538 0.004801034 -0.003128409 0.001461684 0.00337404 -0.002796411 0.001252889 0.00548011 -0.001425504 9.63154e-4 0.004113674 -0.001138269 8.45304e-4 0.003890693 -0.001884162 0.001063108 0.006167948 2.13698e-4 2.92928e-4 0.004290461 4.15125e-4 3.31873e-4 0.004226684 -7.60314e-4 7.34911e-4 0.006811141 0.001651823 -5.17518e-4 0.004097461 0.001463115 -4.92618e-5 0.004256129 6.01529e-4 2.64084e-4 0.004389703 0.002149403 -3.98071e-4 0.003772675 0.002287983 -3.45725e-4 0.00407505 0.001584768 -9.34899e-5 0.00366503 0.002538204 -4.35485e-4 0.004790723 0.003031373 -0.001066505 0.003006756 0.00345546 -7.56515e-4 0.002956807 0.003504872 -7.80712e-4 0.004891872 0.003208518 -0.001353025 0.002617061 0.003840923 -9.45312e-4 0.002524316 0.003921151 -0.001142859 0.002523601 0.00392419 -0.001108467 0.003912806 0.003499269 -0.001436591 0.004917919 0.003234386 -0.001478612 0.004942119 0.003260076 -0.0015527 0.002544343 0.003904283 -0.001018524 0.002535939 0.003911316 -0.001038551 0.002521514 0.003923535 -0.001073122 0.007147729 -0.003598272 0.001782298 0.009718716 -0.003549396 0.001880049 0.007873415 -0.001846909 0.001146733 0.01001965 -0.002836108 0.001576364 0.008315622 -0.007216572 0.002608716 0.006061732 -0.006521403 0.002180635 0.008296906 -0.007271647 0.002605915 0.005964457 -0.006873011 0.002051889 0.008259117 -0.007420361 0.002525389 0.008230745 -0.007531821 0.002465009 0.008372783 -0.00704813 0.002617418 0.008615851 -0.006331622 0.002654254 0.006486833 -0.005298435 0.002169013 0.008836865 -0.00577414 0.002499163 0.00911653 -0.0050686 0.002302825 0.009544849 -0.003987967 0.00200212 0.008229136 -0.007545232 0.002447426 0.005943715 -0.006982684 0.001960933 0.008227169 -0.007561445 0.002426147 0.005952358 -0.007022023 0.001834928 0.008219361 -0.007625877 0.002341628 0.0072456 0.002509236 -0.001285433 0.007356524 0.002667903 -0.00159794 0.009900629 0.002316951 -0.002136766 0.00988835 0.002285182 -0.001956045 0.009858965 0.002277135 -0.001815378 0.009744286 0.002130746 -0.001476109 0.009287416 0.001281559 -6.11996e-4 0.008605599 -1.73e-4 3.34635e-4 0.009896755 0.002186119 -0.002182006 0.003698527 -0.00644046 0.001212 5.60015e-4 -0.004740178 -3.64659e-4 0.001428186 -0.004414916 -5.62872e-4 0.002004563 -0.00463891 -4.43314e-4 0.004295766 3.20387e-4 -0.002023935 0.004190742 9.69087e-4 -0.002054154 0.004453778 0.001678764 -0.002098977 0.004926085 0.003174543 -0.001694798 0.002743363 0.00371474 -0.001401603 0.002658486 0.003804087 -0.001340568 0.002604663 0.003851175 -0.001267611 0.002533972 0.003913044 -0.001171767 0.003174066 0.003261685 -0.00171107 0.003145456 0.003291845 -0.001690506 0.004824101 0.002786397 -0.001951992 0.004908323 0.003087401 -0.001790761 0.004110097 0.001467347 -0.002077341 0.003970086 0.0018211 -0.00204122 0.003746032 0.002387225 -0.001983463 0.00689882 0.001011371 -0.002246379 0.006283223 -6.28489e-4 -0.001980364 0.004268944 -3.694e-5 -0.001964271 0.00327748 -0.00293231 -0.001213788 0.003888726 -0.001889586 -0.001561641 0.005604147 -0.002331316 -0.001481831 0.003914296 -0.001807332 -0.00158286 0.004206717 -8.65753e-4 -0.001825869 0.002914667 -0.003308355 -0.001062095 0.00491631 -0.003970563 -8.11608e-4 0.002474009 -0.003765046 -8.77864e-4 0.004273116 -0.005408763 -1.16089e-6 0.002326428 -0.003860712 -8.32237e-4 0.001531064 -0.004376351 -5.86369e-4 -4.07487e-4 -0.004892647 -1.56356e-4 -6.33597e-5 -0.004838407 -2.30448e-4 0.001603543 -0.005520939 2.25147e-4 0.001502394 -0.005698084 5.11676e-4 -5.57139e-4 -0.004897832 -8.75308e-5 0.001476347 -0.005723893 6.3727e-4 -6.97717e-4 -0.004904389 5.76489e-5 -6.47351e-4 -0.004900991 -4.60381e-5 -6.82756e-4 -0.004901111 -3.06452e-6 -6.94126e-4 -0.00490117 1.074e-5 0.009876012 0.002076447 -0.002272903 0.009778738 0.001724839 -0.002401709 0.009353637 5.01888e-4 -0.002390027 0.008692741 -0.001198172 -0.002003312 0.007396876 0.002602219 -0.001950323 0.007379055 0.002503037 -0.002042889 0.007291257 0.002175807 -0.002185463 0.003727734 -0.006424784 0.001079261 0.003838658 -0.006266117 7.66811e-4 0.008270561 -0.007642924 0.002011835 0.008240163 -0.007669568 0.002133846 0.008232295 -0.007653117 0.002212285 0.008229255 -0.007646739 0.002242624 0.007967114 -0.002949595 -0.001367747 0.01059901 -0.002792 -0.001680135 0.1025055 -0.001290798 0.001294136 0.01256054 -0.003786146 0.001989483 0.03240305 -0.00239408 0.001808047 0.02763932 -0.003124594 0.002006173 0.02655082 -0.003252089 0.002000212 0.02370041 -0.003585994 0.001984536 0.02106517 -0.003894746 0.001970112 0.02095371 -0.003894805 0.001971185 0.01817679 -0.003896355 0.00199896 0.05542755 4.8326e-4 0.001013934 0.05003625 1.0498e-4 0.001054108 0.04755407 -6.91842e-5 0.001072585 0.04414618 -5.92321e-4 0.001252412 0.03812664 -0.001516342 0.001570045 0.09110099 2.67808e-4 0.001385211 0.09695261 3.10993e-4 0.00136888 0.06177872 4.81646e-4 0.001149892 0.06400668 4.81081e-4 0.001197576 0.06764745 4.373e-4 0.001232445 0.08530133 2.25008e-4 0.001401424 0.07938003 2.96212e-4 0.00134474 0.01391273 -0.003898799 0.002041578 0.01537311 -0.003897964 0.002026975 0.05591577 4.83137e-4 0.001024365 0.01367104 -0.008870184 0.003109037 0.09953963 -0.01099246 0.003128528 0.09497296 -0.01152753 0.003302633 0.09491968 -0.01200783 0.003361642 0.02476155 -0.01040768 0.004602015 0.0247699 -0.01045173 0.004558861 0.03038078 -0.01098132 0.004760742 0.01924186 -0.009834825 0.003761529 0.04580122 -0.01244246 0.004455089 0.04720294 -0.01255697 0.004441618 0.04720509 -0.01254314 0.00444734 0.03599971 -0.01158076 0.004603385 0.03599768 -0.01157093 0.004620671 0.03039926 -0.01107525 0.004634261 0.07687962 -0.01330339 0.003773212 0.09788227 -0.01173907 0.003217697 0.09490454 -0.01210433 0.00335735 0.08891224 -0.0126776 0.003533124 0.07688528 -0.0132687 0.003786563 0.06484353 -0.01339447 0.00409305 0.07688075 -0.013296 0.003778457 0.05281752 -0.01297587 0.004358947 0.05281984 -0.01296365 0.004363715 0.05282312 -0.01294732 0.004367351 0.05283272 -0.01290172 0.004371106 0.05284637 -0.0128386 0.004370093 0.06486487 -0.01328414 0.004099011 0.07690399 -0.01316195 0.003792405 0.08892834 -0.01257687 0.003537714 0.03879868 -0.0117926 0.004585027 0.04160255 -0.01202517 0.004533886 0.04160571 -0.01200157 0.004540681 0.04721206 -0.01250338 0.004455149 0.04440075 -0.01231318 0.004476249 0.04720813 -0.01252532 0.004451811 0.04440265 -0.01229792 0.004483401 0.04160022 -0.01204496 0.004525899 0.03879809 -0.01180893 0.004573166 0.0304051 -0.01108074 0.004608511 0.03600257 -0.01158732 0.004584848 0.03879827 -0.01182174 0.004560053 0.03879928 -0.01183104 0.004545688 0.04159879 -0.01206099 0.004516661 0.0415982 -0.01207327 0.00450623 0.04439973 -0.01232457 0.004467964 0.04299867 -0.01220411 0.004480957 0.04159939 -0.0120868 0.004481911 0.04159837 -0.01208186 0.004494667 0.03880369 -0.01183915 0.004513561 0.03880113 -0.01183682 0.004530251 0.04580044 -0.01245123 0.004447042 0.04439955 -0.01233214 0.004458546 0.04439973 -0.01233452 0.00445342 0.04299908 -0.01221042 0.004469931 0.04720169 -0.0125668 0.004434704 0.04720139 -0.0125702 0.00443089 0.04720127 -0.0125727 0.004426717 0.04720163 -0.01256942 0.004423856 0.05281358 -0.01298356 0.004349589 0.05281507 -0.01298195 0.004352748 0.05281674 -0.0129804 0.004356145 0.04160022 -0.01208794 0.004475116 0.04160124 -0.01208817 0.004468023 0.04440021 -0.01233601 0.004447996 0.04160243 -0.01208752 0.004460692 0.04440081 -0.01233649 0.004442274 0.03042721 -0.01107972 0.004523515 0.03601056 -0.0115906 0.004544198 0.03041166 -0.0110833 0.004581451 0.03600621 -0.0115906 0.004565119 0.03043609 -0.01107358 0.00449264 0.02483481 -0.01053136 0.004328072 0.03601574 -0.01158732 0.004522144 0.0136981 -0.008871793 0.002965033 0.01920557 -0.009818255 0.0039047 0.024796 -0.01051127 0.004455089 0.03039419 -0.01106685 0.004658758 0.05038148 -0.01224386 0.004359483 0.04166454 -0.01165699 0.004581034 0.04162704 -0.01186841 0.004555046 0.03600221 -0.01144111 0.004698157 0.03880554 -0.01172184 0.00461322 0.03038382 -0.01102423 0.004724025 0.03319042 -0.01126676 0.004721581 0.03599745 -0.01149791 0.004677474 0.03394484 -0.0111373 0.004777312 0.03038692 -0.0108391 0.004739642 0.03038096 -0.01092702 0.004791975 0.0255956 -0.01043754 0.004688978 0.03602224 -0.01127713 0.004724502 0.02476239 -0.01033288 0.004605948 0.01918238 -0.00976926 0.004024207 0.01918619 -0.009632527 0.004049956 0.01678436 -0.009330928 0.003810465 0.01365649 -0.008840262 0.003232777 0.01367807 -0.00871253 0.003277778 0.02478134 -0.01048636 0.004509925 0.03038996 -0.01105558 0.004681825 0.03319269 -0.01130336 0.004687368 0.03599596 -0.01154112 0.004651606 0.09061902 -0.01203769 0.003468632 0.03599637 -0.01155769 0.004636764 0.03880012 -0.01177263 0.004595696 0.04161459 -0.0119428 0.004550457 0.0528863 -0.01265746 0.004352927 0.05294579 -0.01235085 0.004306852 0.08899486 -0.01212739 0.003502845 0.07979273 -0.01263564 0.003696382 0.0769822 -0.01267093 0.003764986 0.06495374 -0.01282197 0.00405848 0.0644021 -0.01282888 0.004071891 0.01136904 -0.006799042 0.003091394 0.09575003 -0.00696069 0.002663016 0.01190429 -0.005409359 0.002698779 0.04834836 -0.007296442 0.003241062 0.04256522 -0.007437348 0.003512203 0.04198223 -0.01010894 0.004251718 0.07733386 -0.01080518 0.003477692 0.07791644 -0.007638752 0.002918303 0.06534916 -0.01087272 0.003726303 0.06600397 -0.007640242 0.003070652 0.05337917 -0.01048898 0.003913462 0.0541014 -0.007347583 0.003140807 0.04769116 -0.01026242 0.004030466 0.08981561 -0.007323324 0.002777338 0.04178744 -0.01104003 0.00445646 0.05312198 -0.0116145 0.004163503 0.01366311 -0.008697569 0.003425717 0.01917505 -0.009572386 0.004195988 0.01368552 -0.008579254 0.003496944 0.0137726 -0.008242964 0.003577232 0.01927393 -0.008991003 0.004268586 0.01919245 -0.009417533 0.004247426 0.02485346 -0.009482026 0.004694163 0.024773 -0.01001375 0.004725754 0.03055781 -0.009794354 0.004768729 0.03043794 -0.01044237 0.004853785 0.03626942 -0.009981632 0.004549086 0.03611153 -0.01076722 0.004695713 0.02475714 -0.01020741 0.00469619 0.03040313 -0.01068001 0.00484997 0.0367816 -0.007670223 0.00389111 0.03099817 -0.007843196 0.004208683 0.02521741 -0.007859289 0.004235506 0.01963323 -0.007678747 0.00394237 0.01412498 -0.007169663 0.003445506 0.0491752 -0.003605961 0.002169549 0.04332643 -0.004051268 0.002434909 0.03748989 -0.004670381 0.00282979 0.03165572 -0.005251705 0.003186345 0.02581834 -0.005668163 0.003281354 0.02022576 -0.005885481 0.003130555 0.01468867 -0.005659699 0.002905368 0.05499774 -0.003467619 0.002117455 -0.09451276 0.01253479 0.003403484 -0.09212523 0.01273173 0.003463387 -0.09213346 0.01146745 0.003613054 -0.03614205 0.01166248 0.004503786 -0.03279221 0.01134741 0.004452347 -0.03279376 0.01124739 0.004334449 -0.015136 0.009039282 0.002802789 -0.01503735 0.009021759 0.002788603 -0.01505154 0.008762419 0.00214672 -0.01735174 0.004560649 -0.001631498 -0.01818305 0.004649877 -0.001654744 -0.01815795 0.00549519 -0.001295924 -0.09189093 0.003614008 0.001712083 -0.09231328 0.0036031 0.001712739 -0.09224891 0.005635678 0.002544522 -0.1025844 0.009419918 0.002714693 -0.1024982 0.009937644 0.00280714 -0.1010786 0.01027369 0.002977967 -0.1024348 0.01032233 0.002869904 -0.1022481 0.01145398 0.003054678 -0.1012237 0.003237962 0.001627385 -0.103632 0.003120243 0.001590371 -0.1026529 0.005954563 0.00210613 -0.1011665 0.005910575 0.002158403 -0.09819149 0.005800664 0.002355217 -0.09825241 0.003383159 0.001672983 -0.0953654 0.003524303 0.001717329 -0.06850612 0.005394995 0.002248108 -0.06856715 0.003772854 0.001607358 -0.07284498 0.003814876 0.00163865 -0.0803802 0.00547558 0.002397775 -0.08008086 0.003786742 0.001673936 -0.08044099 0.003785371 0.001675724 -0.08610922 0.003763318 0.001703381 -0.05668735 0.00365442 0.001508295 -0.05704474 0.003659665 0.001523077 -0.05662256 0.005351603 0.002127766 -0.06825876 0.003769814 0.001605093 -0.05073881 0.003571867 0.001204967 -0.05075573 0.003572106 0.001206576 -0.05068802 0.005316972 0.001838028 -0.05183541 0.00358355 0.001307904 -0.05645048 0.003650963 0.00149852 -0.0447691 0.005278885 0.001253724 -0.04515445 0.003536462 6.67843e-4 -0.04575556 0.003518819 7.37331e-4 -0.03426456 0.004095852 -5.98482e-4 -0.03968334 0.003710746 3.49758e-5 -0.04002296 0.003686606 7.46795e-5 -0.04483544 0.003545761 6.30968e-4 -0.02617037 0.004869222 -0.001463294 -0.02708619 0.004776 -0.001367807 -0.02705991 0.005484521 -0.001042366 -0.02886003 0.004595518 -0.001182794 -0.03296011 0.005315721 -2.44772e-4 -0.03262728 0.004212141 -7.89875e-4 -0.03300547 0.004185318 -7.45665e-4 -0.02313643 0.005002975 -0.001663863 -0.02410405 0.005578637 -0.001339912 -0.02115839 0.00491631 -0.001699566 -0.02113658 0.005591869 -0.001409411 -0.02032381 0.004879713 -0.001714646 -0.02317839 0.005001127 -0.001661062 -0.02412378 0.004959404 -0.001598596 -0.02610003 0.004872322 -0.001467943 -0.02023833 0.004870533 -0.001712203 -0.01218074 0.004947125 -8.04962e-4 -0.01118898 0.004822731 -7.2111e-4 -0.01126128 0.004664957 -8.24423e-4 -0.01684015 0.004505693 -0.001617193 -0.01517063 0.005277574 -0.001068234 -0.01519256 0.004232585 -0.001536011 -0.01218509 0.003733992 -0.001387774 -0.01171034 0.003655314 -0.001364409 -0.0105111 0.006303071 2.47928e-4 -0.01060545 0.006097018 1.13031e-4 -0.01215952 0.006291985 -1.71452e-5 -0.01093977 0.005366921 -3.6488e-4 -0.0121231 0.007542073 9.97412e-4 -0.01023811 0.006852269 7.40644e-4 -0.009982943 0.007365763 0.001201272 -0.01210397 0.008054316 0.001643896 -0.009716391 0.007789552 0.001839339 -0.009770929 0.007702887 0.001708805 -0.009703993 0.00780934 0.001869082 -0.01209372 0.008352994 0.002281308 -0.01265221 0.008480072 0.002377688 -0.01501697 0.009018123 0.002785623 -0.02419501 0.01045548 0.003967463 -0.02094459 0.01003932 0.003615438 -0.02095043 0.009943068 0.003324866 -0.02069127 0.0100069 0.00358802 -0.02028977 0.009955465 0.003544509 -0.02687305 0.01058673 0.003847718 -0.02686744 0.01075911 0.00418806 -0.02628684 0.01069962 0.004151642 -0.02392041 0.01009792 0.003174543 -0.0253567 0.0106042 0.004093289 -0.02688652 0.01018452 0.003133654 -0.03280824 0.01031351 0.003211736 -0.03184425 0.0112583 0.004437744 -0.03056436 0.0111379 0.004418075 -0.0305255 0.01113426 0.004417479 -0.03871554 0.01154053 0.004169106 -0.03871494 0.01189416 0.004485607 -0.04463523 0.01181298 0.004093945 -0.04463678 0.01242733 0.004443705 -0.043002 0.01228016 0.004455268 -0.0549364 0.01323026 0.004332423 -0.05421429 0.01317512 0.004340589 -0.05648571 0.01222223 0.004079937 -0.04860144 0.01274639 0.004403948 -0.04582548 0.01253437 0.0044353 -0.07921159 0.01347517 0.003745317 -0.07827693 0.01349312 0.003768503 -0.0802437 0.0126785 0.003763735 -0.07040911 0.01364433 0.003963828 -0.06623458 0.0136007 0.004069685 -0.06253463 0.01356202 0.004163503 -0.05648839 0.01329803 0.004297912 -0.08983898 0.01292032 0.003520786 -0.08807498 0.01306581 0.003565013 -0.0802415 0.01342761 0.003724336 -0.1005318 0.01173514 0.003149509 -0.0997703 0.01185989 0.00319159 -0.09807944 0.01164931 0.003320395 -0.09807556 0.01207745 0.003259897 -0.0962935 0.01230621 0.00333172 -0.1025947 0.008870005 0.002620697 -0.1011068 0.008823394 0.002708017 -0.09812605 0.008688747 0.003053605 -0.09217727 0.008512854 0.003374814 -0.08030098 0.008369565 0.00331062 -0.05653703 0.008271634 0.003067612 -0.05060398 0.008219301 0.002826392 -0.03290808 0.006729483 4.86922e-4 -0.03286534 0.008042275 0.001299381 -0.02700674 0.006874322 -2.30487e-4 -0.02695959 0.008133411 7.26848e-4 -0.02405244 0.006958007 -5.17484e-4 -0.0240035 0.008185744 5.03406e-4 -0.02108764 0.006956398 -5.84214e-4 -0.02103853 0.008161187 4.66193e-4 -0.01811403 0.00684601 -4.76615e-4 -0.018067 0.008039355 5.79773e-4 -0.0151357 0.006625294 -2.69117e-4 -0.01956319 0.009826302 0.003439962 -0.02099186 0.00916922 0.001763045 -0.02395892 0.009239792 0.001731634 -0.0269193 0.009243428 0.001843154 -0.03283202 0.00924164 0.002203285 -0.01799076 0.009546756 0.003213644 -0.01802122 0.009008288 0.001918494 -0.0150718 0.008339226 0.001411795 -0.01509338 0.007830262 7.72115e-4 -0.04468411 0.008145153 0.002368748 -0.03872412 0.01049214 0.003336489 -0.04465734 0.009454309 0.002933025 -0.101056 0.01164925 0.003120541 -0.09809881 0.01014775 0.003290057 -0.0921514 0.009976506 0.003584206 -0.08027356 0.009809076 0.003588259 -0.08025443 0.01124519 0.00374031 -0.05649262 0.01096314 0.003792166 -0.05056232 0.01083892 0.00369668 -0.04464107 0.01067805 0.003506183 -0.09030252 0.01288211 0.003509163 -0.1031586 0.005966722 0.002098381 -0.1026754 0.008872091 0.002616941 -0.04116117 -0.002357423 -0.00234884 -0.04669743 -0.003242373 -0.001649498 -0.04589504 3.597e-4 -4.67706e-4 -0.01369392 -0.001354932 -0.002744674 -0.0137062 -0.001399636 -0.002725601 -0.01666527 -0.001256704 -0.003397941 -0.05094057 -0.009938836 -0.003240704 -0.04804766 -0.00930643 -0.003528475 -0.04824334 -0.01023149 -0.003768384 -0.04254609 -0.008456647 -0.004291355 -0.05410856 -0.01147735 -0.003260076 -0.06011271 -0.01218885 -0.002815723 -0.05985623 -0.01106852 -0.002518773 -0.06804662 -0.01333099 -0.002515852 -0.07173544 -0.01326823 -0.002305209 -0.07068878 -0.008149266 -0.001141667 -0.1059517 -0.01086544 -7.41353e-4 -0.1055244 -0.008289158 -3.14278e-4 -0.09956139 -0.007299363 -1.7873e-4 -0.1052932 -0.006895244 -8.31988e-5 -0.1041673 -9.91719e-5 0.001004755 -0.06601178 -0.01323747 -0.002648234 -0.06490725 -0.008135199 -0.001403033 -0.06904107 -2.18274e-5 6.44467e-4 -0.07908946 -0.01314312 -0.001885294 -0.0822454 -0.007894873 -6.88597e-4 -0.08317625 -0.01291614 -0.001708269 -0.09379452 -0.007505714 -3.18953e-4 -0.1060089 -0.01120996 -7.98459e-4 -0.1003218 -0.01186311 -9.83956e-4 -0.09862506 -0.01205796 -0.001039266 -0.09461319 -0.01228082 -0.001213014 -0.06029099 -0.01295804 -0.003021657 -0.05427455 -0.01212751 -0.003453552 -0.05273973 -0.01191562 -0.003563702 -0.05131208 -0.01154142 -0.003674328 -0.04838955 -0.01077538 -0.003900825 -0.05115371 -0.01093053 -0.003508985 -0.05387854 -0.01042902 -0.002970993 -0.05913364 -0.007928848 -0.00168389 -0.02508324 -0.002456307 -0.004932343 -0.02565228 -0.002465248 -0.005073606 -0.02268511 -0.001974284 -0.004630386 -0.01495194 -0.001758098 -0.002692162 -0.01677262 -0.001810371 -0.003140747 -0.01676905 -0.001656711 -0.003220617 -0.0197317 -0.001895427 -0.003869771 -0.01972025 -0.001739025 -0.003975272 -0.02135896 -0.001942217 -0.004270613 -0.02269291 -0.002126336 -0.00450766 -0.02564394 -0.002626538 -0.004968106 -0.0285421 -0.003506302 -0.005153059 -0.02854621 -0.0033679 -0.005221247 -0.02863317 -0.003533959 -0.005158841 -0.03134179 -0.004519581 -0.005140364 -0.0137642 -0.001610994 -0.002635538 -0.01674801 -0.001554727 -0.003296792 -0.0196098 -0.001281678 -0.004125356 -0.01969772 -0.001620173 -0.004046201 -0.02257531 -0.001456081 -0.004742324 -0.02266347 -0.00183767 -0.004692196 -0.02555251 -0.001883268 -0.005140125 -0.0256347 -0.002310574 -0.005123198 -0.0284599 -0.002717316 -0.005242824 -0.02853357 -0.003194689 -0.005257725 -0.0312435 -0.003797352 -0.005124151 -0.03132539 -0.004327535 -0.005165159 -0.03680855 -0.005791246 -0.004674911 -0.03693002 -0.006435573 -0.004776835 -0.04238718 -0.007676422 -0.004118859 -0.03696554 -0.006670415 -0.004781961 -0.04633194 -0.01023608 -0.004060268 -0.04265832 -0.008906245 -0.004335522 -0.03723818 -0.006944239 -0.004741668 -0.03698641 -0.00684446 -0.004753887 -0.03135985 -0.004614591 -0.005026638 -0.01318407 5.03547e-5 -0.002626061 -0.01339143 -5.21109e-4 -0.002674281 -0.01632881 -2.78665e-4 -0.003353834 -0.01365262 -0.001241028 -0.002735078 -0.01925402 -2.00002e-4 -0.003988683 -0.02220994 -2.62044e-4 -0.004504799 -0.02518999 -5.64261e-4 -0.004803895 -0.02810847 -0.001251041 -0.004825055 -0.0308755 -0.002170681 -0.004648447 -0.03636401 -0.003839075 -0.004088163 -0.04187232 -0.005366563 -0.003423273 -0.04746186 -0.006637334 -0.002740144 -0.05322027 -0.007465839 -0.002123892 -0.04038321 8.75465e-4 -0.00110048 -0.03909343 9.96158e-4 -0.001248598 -0.03570204 -0.001237094 -0.003053307 -0.03494644 0.001636147 -0.001742243 -0.03026992 3.14182e-5 -0.003682672 -0.02953469 0.002471446 -0.00238645 -0.02751451 7.4209e-4 -0.003911852 -0.02861368 0.002613544 -0.002496123 -0.02162122 0.001390695 -0.003810465 -0.01937532 0.00314784 -0.002688109 -0.01868534 0.001321196 -0.003440678 -0.01800483 0.002982318 -0.002550721 -0.01578879 0.001122057 -0.00295484 -0.02676641 0.0028553 -0.002620518 -0.02387183 0.003234028 -0.002815425 -0.02459251 0.001240074 -0.003981769 -0.02386009 0.00323379 -0.002815127 -0.02090835 0.003177225 -0.002731502 -0.01229125 0.002292275 -0.001978158 -0.01247966 0.001827478 -0.002131402 -0.07516407 4.64264e-6 7.62908e-4 -0.09835577 -1.85268e-5 0.00102669 -0.09571981 1.80509e-5 0.001036643 -0.09250599 1.59545e-5 9.93849e-4 -0.08077859 8.30553e-6 8.37676e-4 -0.01380354 -0.00181508 -0.002452135 -0.01379382 -0.001746833 -0.002533555 -0.01379144 -0.001729965 -0.002553701 -0.01378571 -0.001689255 -0.002602159 -0.06047153 -0.01298296 -0.003008723 -0.01290255 7.84012e-4 -0.00247544 -0.01304906 4.22449e-4 -0.002594649 -0.05239117 -0.003767192 -0.001039147 -0.05823528 -0.004040658 -6.47306e-4 -0.06317323 -4.71938e-5 5.30962e-4 -0.05768013 -7.09416e-5 4.24706e-4 -0.05731576 -6.1892e-5 4.00038e-4 -0.05154061 8.15531e-5 9.04407e-6 -0.04790151 1.71942e-4 -2.37335e-4 -0.01379144 -0.001844644 -0.002322971 -0.01378571 -0.00185883 -0.002261281 -0.01676106 -0.001791954 -0.002911627 -0.0137239 -0.001809597 -0.002003312 -0.0137183 -0.001802802 -0.001984953 -0.01668876 -0.001813411 -0.002662599 -0.03698539 -0.00700438 -0.004679083 -0.03698831 -0.00696361 -0.004710912 -0.03132998 -0.004758775 -0.005012869 -0.01376539 -0.001842677 -0.002176642 -0.01375317 -0.001832962 -0.00212562 -0.01673543 -0.001785159 -0.00277704 -0.03694301 -0.007053196 -0.004501163 -0.03695815 -0.007058143 -0.004553079 -0.03126692 -0.004833817 -0.004795134 -0.03980547 -0.008161544 -0.004409492 -0.04829275 -0.01120662 -0.003898322 -0.0484277 -0.01123964 -0.003890693 -0.04842931 -0.0112459 -0.003901839 -0.04697465 -0.01078331 -0.004003822 -0.04843139 -0.01124244 -0.003918349 -0.04843139 -0.01123815 -0.003921151 -0.05587548 -0.01291197 -0.003458797 -0.05436891 -0.01269215 -0.003554642 -0.05460625 -0.0127502 -0.003541171 -0.1060819 -0.01164817 -8.80739e-4 -0.1004049 -0.01236319 -0.001083314 -0.1060842 -0.01166194 -8.84102e-4 -0.1060845 -0.01166367 -8.84622e-4 -0.106086 -0.01167201 -8.87304e-4 -0.1060863 -0.01167392 -8.88169e-4 -0.1060864 -0.01167458 -8.88985e-4 -0.1060858 -0.01167094 -8.86834e-4 -0.1060854 -0.01166826 -8.86022e-4 -0.08613318 -0.01331335 -0.001692771 -0.08898937 -0.01314264 -0.00156778 -0.08329552 -0.01346009 -0.001805245 -0.09470188 -0.01280134 -0.001317799 -0.09469664 -0.01277822 -0.00130397 -0.09882026 -0.0125553 -0.001137554 -0.08325433 -0.01338279 -0.001766324 -0.09468168 -0.01271343 -0.001264035 -0.1003915 -0.012299 -0.0010522 -0.106081 -0.01164245 -8.79344e-4 -0.06609982 -0.01372456 -0.002747654 -0.06875121 -0.01391869 -0.002612113 -0.07182186 -0.01376777 -0.002388715 -0.07184815 -0.01385146 -0.002433419 -0.08013713 -0.01367157 -0.001955211 -0.06034588 -0.01321673 -0.003086566 -0.05434483 -0.0125854 -0.003541171 -0.06038492 -0.01339226 -0.003132224 -0.05436223 -0.01267713 -0.003557443 -0.03981882 -0.008129656 -0.004479408 -0.04266333 -0.009227037 -0.004294812 -0.04266357 -0.009211599 -0.004305601 -0.04552888 -0.01025766 -0.004116952 -0.04552739 -0.01023894 -0.004122853 -0.04842412 -0.01117116 -0.00393331 -0.04842942 -0.01121205 -0.003929495 -0.04697453 -0.01075679 -0.004020571 -0.0455296 -0.01027292 -0.004109919 -0.0484308 -0.01122695 -0.003925859 -0.04697519 -0.01077008 -0.00401467 -0.04552948 -0.01028466 -0.004101693 -0.04266232 -0.009239256 -0.004282891 -0.03981661 -0.008142232 -0.004463732 -0.03697937 -0.007033765 -0.004642128 -0.05663061 -0.01300823 -0.003409802 -0.05700898 -0.01305651 -0.003385245 -0.05738818 -0.01310485 -0.003360629 -0.0499137 -0.01160323 -0.003807127 -0.04843014 -0.01124984 -0.003908276 -0.05139946 -0.01196616 -0.003722608 -0.04843115 -0.01124578 -0.00391525 -0.04697501 -0.01077979 -0.004007697 -0.04552787 -0.0102958 -0.004087269 -0.04552692 -0.01029777 -0.004081904 -0.04265469 -0.009256184 -0.004240095 -0.04265064 -0.009255409 -0.004223644 -0.04697406 -0.01078599 -0.00399959 -0.04552447 -0.01029926 -0.004070401 -0.04264581 -0.009251415 -0.004206061 -0.04991358 -0.01160293 -0.00380665 -0.0226407 -0.002193152 -0.004182517 -0.022601 -0.002219855 -0.003980755 -0.02364265 -0.002324521 -0.004210412 -0.02558642 -0.002723693 -0.00465089 -0.02552402 -0.002787113 -0.004434347 -0.02724426 -0.003210067 -0.004639089 -0.02845811 -0.003656744 -0.004836082 -0.02839106 -0.00367093 -0.004646122 -0.01971244 -0.001911282 -0.00366187 -0.0196858 -0.001913428 -0.003520131 -0.0226705 -0.002183079 -0.004325807 -0.02562218 -0.002707719 -0.004790067 -0.02849942 -0.003638684 -0.004966557 -0.03130471 -0.004815757 -0.004915118 -0.03697025 -0.007051706 -0.004600107 -0.03981363 -0.00815171 -0.004446804 -0.04266053 -0.009248137 -0.004269778 -0.04265803 -0.009253799 -0.004255533 -0.04552859 -0.01029294 -0.004092395 -0.03092795 -0.004690349 -0.004661738 -0.03121972 -0.004804193 -0.004650413 -0.03692662 -0.007030904 -0.004429221 -0.04012602 -0.008279263 -0.004305243 -0.04266017 -0.009187638 -0.004179 -0.04264831 -0.009049057 -0.00434488 -0.03698819 -0.006911575 -0.004737496 -0.04840338 -0.0110439 -0.003926634 -0.05133682 -0.01181674 -0.003716289 -0.0543124 -0.01242703 -0.003505587 -0.05288469 -0.01232933 -0.003638565 -0.05436253 -0.01268625 -0.003555774 -0.03981983 -0.008048534 -0.004529833 -0.0398209 -0.008095264 -0.004507124 -0.0426566 -0.00911653 -0.004336714 -0.04266166 -0.009170711 -0.004323601 -0.04552197 -0.01019078 -0.004131138 -0.04841548 -0.01111519 -0.003932356 -0.04988867 -0.01158672 -0.003836691 -0.03133803 -0.004716217 -0.005053281 -0.02564501 -0.002659857 -0.004906237 -0.02268773 -0.002143442 -0.004447162 -0.02852797 -0.003585457 -0.005073964 -0.01379436 -0.001837551 -0.002354145 -0.01677489 -0.001772582 -0.003029167 -0.01972681 -0.00188148 -0.003783822 -0.0313189 -0.004792034 -0.004966795 -0.1060787 -0.01162886 -8.76541e-4 -0.1060679 -0.01156431 -8.63167e-4 -0.1060544 -0.01148349 -8.48407e-4 -0.08327716 -0.01348394 -0.001817762 -0.01964884 -0.001923084 -0.003330051 -0.01862692 -0.001820385 -0.003104805 -0.05891323 -0.01329922 -0.003261685 -0.06042027 -0.01349133 -0.003163874 -0.06149011 -0.0136277 -0.003094434 -0.06613093 -0.01381367 -0.002786159 -0.01318204 -8.13079e-4 -8.78134e-4 -0.01293742 -3.4851e-4 -3.99795e-4 -0.01588636 -2.82782e-4 -7.90174e-4 -0.05909377 -0.007944166 -0.001211106 -0.05925327 -0.004114449 -2.07736e-5 -0.06401413 -0.004149556 1.38759e-4 -0.1059515 -0.01087284 -6.8177e-4 -0.106 -0.01116287 -7.46045e-4 -0.1003179 -0.01187711 -8.94051e-4 -0.1060543 -0.01148748 -8.17969e-4 -0.1060658 -0.01155596 -8.33152e-4 -0.1003888 -0.01229232 -0.001013696 -0.1060863 -0.01167434 -8.85736e-4 -0.0124787 6.61417e-4 2.18396e-4 -0.01232916 9.9077e-4 4.19997e-4 -0.01524645 0.00107181 2.75653e-4 -0.1055528 -0.008490681 -1.53891e-4 -0.1057226 -0.009505212 -3.78708e-4 -0.1000194 -0.0101031 -4.89405e-4 -0.1055244 -0.008319735 -1.22238e-4 -0.06556993 -0.01134324 -0.001860857 -0.06677943 -0.004169881 2.31422e-4 -0.07131892 -0.01136136 -0.001555562 -0.06984072 -0.004111647 2.90298e-4 -0.08280438 -0.01100414 -0.001048862 -0.1047112 -0.003432095 7.82746e-4 -0.09893304 -0.003549695 7.57673e-4 -0.09312272 -0.00366795 7.32461e-4 -0.09428352 -0.01043385 -6.51071e-4 -0.09274619 -0.003675639 7.30826e-4 -0.08148682 -0.003889977 5.14281e-4 -0.02381652 4.85432e-4 -6.4303e-4 -0.0209884 8.43304e-4 -3.77127e-4 -0.02025353 0.00247246 9.41613e-4 -0.01948511 0.002543985 9.74711e-4 -0.01812613 0.001020073 -4.55114e-5 -0.01743066 0.0025267 0.001070976 -0.02304112 0.00221318 8.21542e-4 -0.02465337 0.002063155 7.52097e-4 -0.02659338 -1.45408e-4 -7.67349e-4 -0.02579379 0.001836717 7.48675e-4 -0.02943527 -9.46063e-4 -7.63818e-4 -0.02863222 0.001273095 7.40159e-4 -0.03417903 1.7173e-4 7.23515e-4 -0.03530603 -0.002556383 -8.27413e-4 -0.03450179 9.84762e-5 7.06732e-4 -0.04117804 -0.004297673 -0.001037776 -0.04037261 -0.001233816 4.01487e-4 -0.0470916 -0.005987048 -0.001257479 -0.05738812 -0.01310527 -0.003359973 -0.05437254 -0.0126962 -0.003541767 -0.06041431 -0.01352304 -0.003152668 -0.05137413 -0.01200073 -0.003682434 -0.05436748 -0.01268893 -0.003530621 -0.04844069 -0.0112285 -0.003854215 -0.05435365 -0.01267266 -0.003501594 -0.0513603 -0.01202011 -0.003661096 -0.05132812 -0.01191031 -0.003569245 -0.04836624 -0.01108217 -0.00369656 -0.04840391 -0.0111984 -0.003806591 -0.04260396 -0.009180903 -0.004063427 -0.02823835 -0.003478944 -0.004254341 -0.03105843 -0.004635393 -0.004240274 -0.04255175 -0.009055435 -0.003911674 -0.03680288 -0.006842315 -0.004088819 -0.02538573 -0.002557098 -0.004052281 -0.01933246 -0.001421868 -0.002458214 -0.02226215 -0.001714885 -0.003059089 -0.01639664 -0.001274883 -0.00181061 -0.0136618 -0.001724302 -0.001816332 -0.01365607 -0.001713395 -0.001805126 -0.01341503 -0.001255571 -0.001333713 -0.1060857 -0.011671 -8.80268e-4 -0.106086 -0.01167249 -8.82682e-4 -0.1060861 -0.01167327 -8.84006e-4 -0.1004005 -0.01234281 -0.001064419 -0.1060834 -0.0116589 -8.70684e-4 -0.1060845 -0.0116648 -8.75389e-4 -0.1060724 -0.01159524 -8.41852e-4 -0.1060786 -0.0116313 -8.58189e-4 -0.1060814 -0.01164716 -8.65379e-4 -0.0832768 -0.01350802 -0.001787781 -0.09470146 -0.01282733 -0.001286268 -0.09755873 -0.01265078 -0.001181185 -0.09469693 -0.01280909 -0.001264035 -0.0947014 -0.01283228 -0.001280367 -0.08327674 -0.01351344 -0.001781165 -0.09467869 -0.0127089 -0.001220941 -0.07756274 -0.01377403 -0.002084612 -0.07184708 -0.01390743 -0.00240314 -0.0718472 -0.0138992 -0.002407491 -0.06612724 -0.01385712 -0.002766788 -0.06612652 -0.01386564 -0.002763152 -0.06041288 -0.01353114 -0.003149986 -0.0832718 -0.01348966 -0.001761972 -0.07184165 -0.01388394 -0.002381205 -0.0661208 -0.0138427 -0.002740263 -0.06040674 -0.01350921 -0.00312674 -0.08325147 -0.01338553 -0.001711547 -0.05432558 -0.01256871 -0.003424465 -0.057343 -0.01306307 -0.003258347 -0.06038147 -0.01340955 -0.003063976 -0.06609696 -0.01373976 -0.002679407 -0.07181912 -0.0137794 -0.002323329 -0.09460282 -0.01227772 -0.001090884 -0.08316594 -0.01293522 -0.001559913 -0.07172369 -0.01332348 -0.00214827 -0.06599634 -0.01328873 -0.002493798 -0.06027537 -0.01297086 -0.002870082 -0.05723792 -0.01262789 -0.003053426 -0.0542171 -0.01213079 -0.003196597 -0.0512126 -0.0114668 -0.003309071 -0.04824066 -0.01063334 -0.003397226 -0.04239749 -0.008606851 -0.003523349 -0.03661513 -0.00641632 -0.003614962 -0.03083491 -0.004258394 -0.00370872 -0.02800762 -0.003137052 -0.003710091 -0.02516967 -0.002241134 -0.003506898 -0.01458579 0.002502799 0.001204371 -0.01352816 0.002493917 0.001253962 -0.01171034 0.002353072 0.001253902 -0.04535174 -0.002363801 1.42601e-4 -0.04628598 -0.002526342 1.08692e-4 -0.05007845 -0.006699085 -0.001329481 -0.05224007 -0.003562033 -1.07422e-4 -0.05308347 -0.007267534 -0.001356184 -0.05247694 -0.003603219 -1.16017e-4 -0.05609017 -0.007683277 -0.001322925 -0.05522578 -0.003810644 -7.73808e-5 -0.05819535 -0.004034638 -3.56431e-5 -0.01879829 -4.0113e-4 -0.001293241 -0.0216971 -6.57309e-4 -0.001779794 -0.02456611 -0.001123785 -0.002156555 -0.02737337 -0.001916944 -0.002336859 -0.03021186 -0.002911329 -0.002346456 -0.03605186 -0.004863977 -0.002352654 -0.04189217 -0.006904065 -0.002429544 -0.04778313 -0.00883466 -0.002488136 -0.05076903 -0.009639084 -0.002483665 -0.05378043 -0.01028162 -0.002442181 -0.05680042 -0.01075839 -0.002352774 -0.05982685 -0.01107418 -0.002200782 -0.1286989 -0.00490117 -1.12772e-4 -0.1260732 -0.006284773 -2.19258e-4 -0.1273871 -0.005592465 -1.65975e-4 -0.1119046 -0.01033234 -6.70665e-4 -0.1090006 -0.01109749 -7.94702e-4 -0.1247598 -0.006976842 -2.72525e-4 -0.1234663 -0.00753057 -3.08566e-4 -0.1191716 -0.008935272 -4.62362e-4 -0.1177201 -0.009248971 -5.09794e-4 -0.1191151 -0.008953213 -4.64213e-4 -0.1226651 -0.006201922 -1.6073e-4 -0.1241767 -0.001613259 2.86692e-4 -0.1211571 -0.006418824 -1.67396e-4 -0.1224576 -0.001222729 3.75255e-4 -0.11806 -0.006821274 -1.81989e-4 -0.1257838 -0.001978337 2.03902e-4 -0.1241171 -0.005972445 -1.55646e-4 -0.1270361 -0.002688527 9.0295e-5 -0.1254581 -0.005748927 -1.58082e-4 -0.1177293 -0.00923711 -5.03647e-4 -0.1178051 -0.008684873 -4.24234e-4 -0.1207416 -0.008052647 -3.4725e-4 -0.1235924 -0.00722903 -2.76372e-4 -0.1262465 -0.006174504 -2.11775e-4 -0.1241042 -0.007322371 -2.99115e-4 -0.1238963 -0.007431864 -3.07544e-4 -0.1234148 -0.007585108 -3.23324e-4 -0.1220005 -0.008035123 -3.69665e-4 -0.1206418 -0.008444607 -3.94406e-4 -0.1205851 -0.008485496 -4.16045e-4 -0.1277077 -0.005236268 -1.53476e-4 -0.1266336 -0.005516707 -1.62642e-4 -0.1118016 -0.007558465 -2.41931e-4 -0.1118847 -0.009795784 -5.83392e-4 -0.1074893 -0.01141786 -8.44081e-4 -0.1119094 -0.01045864 -6.93689e-4 -0.1119071 -0.01048129 -6.99731e-4 -0.1148136 -0.009865105 -6.04762e-4 -0.1177438 -0.009131848 -4.86835e-4 -0.128466 -0.004327535 -1.16847e-4 -0.1283736 -0.004206836 -1.02085e-4 -0.1278085 -0.003468573 -1.17528e-5 -0.1273457 -0.002864062 6.221e-5 -0.1167513 -7.61691e-4 6.4156e-4 -0.1188661 -9.32559e-4 5.42866e-4 -0.1044356 -0.001772344 0.001074373 -0.1041673 -1.56303e-4 0.001352608 -0.1115396 -4.90195e-4 0.001101672 -0.1119095 -0.01046103 -6.76881e-4 -0.1188446 0.007750272 0.001846075 -0.1200129 0.007448732 0.001726806 -0.1200129 0.007427334 0.001745343 -0.1111926 0.008871912 0.002418935 -0.1112759 0.00662291 0.002146959 -0.1028103 0.008036911 0.002649247 -0.1030443 0.006619513 0.002455294 -0.1289623 -0.004054427 -8.75536e-5 -0.1285909 -0.004566311 -1.00075e-4 -0.129461 0.00120455 4.62035e-4 -0.1295183 0.001056551 4.41157e-4 -0.1295217 6.55644e-4 3.894e-4 -0.1262477 -0.006176769 -1.8628e-4 -0.1206424 -0.008447408 -3.68077e-4 -0.1022495 0.0114445 0.003060638 -0.1022489 0.01144897 0.003057837 -0.1111598 0.009562075 0.002441942 -0.1022487 0.01145046 0.003056883 -0.1177296 -0.009238839 -4.89542e-4 -0.1234667 -0.007532477 -2.87308e-4 -0.1235932 -0.007233321 -2.30786e-4 -0.1180629 -0.00683844 -4.54313e-5 -0.12116 -0.006432116 -4.50774e-5 -0.120743 -0.008058667 -2.90791e-4 -0.1290954 -0.001345098 2.24064e-4 -0.1283877 -0.004199326 -5.51534e-5 -0.1278664 -0.003435671 8.13901e-5 -0.1277083 -0.005237877 -1.25119e-4 -0.1266358 -0.005521714 -1.074e-4 -0.1220061 0.006934344 0.001523375 -0.1222049 0.006838917 0.001513719 -0.1199988 0.007319033 0.001749038 -0.1221861 0.006736755 0.001518368 -0.1199381 0.006866276 0.001725196 -0.1243154 0.005979537 0.001280307 -0.1243303 0.00606364 0.001263618 -0.1222057 0.00685954 0.001501023 -0.1221055 0.006309211 0.001500308 -0.124216 0.005583107 0.00126785 -0.1263254 0.004948258 0.001052677 -0.1262099 0.004591941 0.001044869 -0.1272933 0.004411339 9.25828e-4 -0.1272928 0.004410684 9.25799e-4 -0.126324 0.004999995 0.001036882 -0.1253539 0.005589187 0.001148104 -0.1249632 0.005826532 0.001192927 -0.1196841 0.004994153 0.001541256 -0.1217687 0.004540562 0.001344501 -0.1238012 0.003942489 0.001140296 -0.1257285 0.003116846 9.42979e-4 -0.1274532 0.00199747 7.44642e-4 -0.1290667 -0.003159224 -8.86293e-6 -0.1254606 -0.005756676 -7.8171e-5 -0.1270718 -0.002649128 2.44687e-4 -0.1275207 -0.003040432 1.62117e-4 -0.1286813 4.65471e-4 5.00848e-4 -0.1289733 -4.3053e-4 3.60671e-4 -0.1291874 0.001449286 5.5342e-4 -0.1294299 3.93893e-4 3.99275e-4 -0.1281035 0.003563702 8.27289e-4 -0.128077 0.003598809 8.05276e-4 -0.128846 0.00275737 6.93736e-4 -0.1288515 0.002777576 6.83991e-4 -0.1288532 0.002773404 6.8942e-4 -0.1288445 0.002795755 6.86556e-4 -0.1284691 0.00318849 7.44617e-4 -0.1288162 0.002692103 6.99344e-4 -0.1286897 0.002418875 6.96911e-4 -0.1281625 0.001287639 6.30826e-4 -0.1264865 -0.002293765 3.2028e-4 -0.1241189 -0.005981922 -5.68782e-5 -0.1290535 0.002256393 6.10448e-4 -0.122667 -0.006213188 -4.85354e-5 -0.1292804 -0.002831041 -4.2594e-6 -0.1290794 -0.003893077 -8.86936e-5 -0.1295311 -4.75977e-4 2.43321e-4 -0.1295382 -0.001336753 1.32202e-4 -0.1294818 -6.84803e-4 2.49567e-4 -0.1294937 -0.001601397 1.0824e-4 -0.1293054 -0.002721607 6.80983e-6 -0.1291075 -0.003854274 -9.11234e-5 -0.1292111 -0.003282487 -4.39733e-5 -0.1291142 -0.003845095 -9.26885e-5 -0.1291179 -0.00383687 -9.41711e-5 -0.1292578 0.001728951 5.36035e-4 -0.1295264 9.01762e-5 3.16405e-4 -0.1273103 0.004401028 9.23881e-4 -0.1279777 0.003258943 8.23147e-4 -0.1022529 0.01142275 0.003066658 -0.1022506 0.01143687 0.003065407 -0.1022502 0.01143997 0.003063499 -0.1111676 0.009546637 0.002458691 -0.1111724 0.009416222 0.002460122 -0.1022803 0.01125282 0.003067016 -0.1022672 0.01133304 0.003071367 -0.1022636 0.01135498 0.003072559 -0.102256 0.01140296 0.003068387 -0.102383 0.01062673 0.003003597 -0.1023276 0.01096218 0.003049552 -0.1023198 0.01100933 0.003053724 -0.1125435 0.009268343 0.002346754 -0.1257866 -0.001996517 3.85093e-4 -0.1241983 -0.001553297 4.94031e-4 -0.1224816 -0.001250863 5.98644e-4 -0.1206958 -0.001056849 7.04702e-4 -0.1188746 -9.2994e-4 8.0489e-4 -0.1119049 -0.01033729 -6.35637e-4 -0.1118852 -0.009806513 -5.08287e-4 -0.1178065 -0.008692622 -3.61199e-4 -0.1177445 -0.009135425 -4.57438e-4 -0.1118026 -0.007582068 -7.92374e-5 -0.1291159 -0.003841936 -9.42596e-5 -0.1289076 -0.004371106 -1.03509e-4 -0.009411633 -0.002348542 -0.001899242 -0.0088045 -0.002489686 -0.001830756 -0.008783578 -0.00248599 -0.00173068 -0.005561411 0.001264333 8.31623e-4 -0.005533814 0.001339375 8.52116e-4 -0.006877958 0.001623153 9.63154e-4 -0.002890884 0.005857229 7.15594e-4 -0.005083322 0.006615757 0.001328229 -0.005085229 0.006556689 0.001431643 -7.09951e-4 0.00509876 1.30846e-4 -6.98924e-4 0.00509876 1.03028e-4 -8.21963e-4 0.005095541 2.40158e-4 -0.005102992 0.006457567 0.001524209 -9.72882e-4 0.00509119 3.87446e-4 -0.003020226 0.004526615 0.001197338 -0.005190849 0.006130337 0.001666784 -0.003295004 0.004346191 0.001235604 -0.005583286 0.004965901 0.0017277 -0.003843843 0.003985762 0.001312077 -0.002459585 0.004778206 0.001053094 -0.001578807 0.005020737 7.21868e-4 -9.74134e-4 0.00509119 3.8867e-4 -0.006198883 0.003325998 0.001461684 -0.005161106 0.002354264 0.001129209 -0.00474435 0.002988755 0.001239895 -0.004540026 0.003299772 0.001294136 -0.005698919 9.88087e-5 4.44104e-4 -0.007565736 -1.60802e-5 2.92928e-4 -0.00568217 -3.13424e-4 2.97395e-4 -0.00820899 -0.001454234 -5.17518e-4 -0.00549364 -0.00126326 -4.84064e-5 -0.005664467 -4.02573e-4 2.64939e-4 -0.005787551 -0.001951754 -3.98071e-4 -0.005165398 -0.002088904 -3.44906e-4 -0.005462408 -0.001420617 -1.05701e-4 -0.005018711 -0.002418935 -4.6302e-4 -0.006188571 -0.002833783 -0.001066505 -0.004359483 -0.003306806 -7.7499e-4 -0.004349529 -0.003316521 -7.79745e-4 -0.00628972 -0.003010869 -0.001353025 -0.00403434 -0.003625094 -9.30345e-4 -0.003922164 -0.003723561 -0.001142859 -0.003921449 -0.003726541 -0.001108467 -0.005310356 -0.003301799 -0.001436531 -0.006315767 -0.003036737 -0.001478612 -0.006339967 -0.003062486 -0.0015527 -0.003942847 -0.003705978 -0.001017093 -0.003933846 -0.003713607 -0.001038551 -0.003919363 -0.003725886 -0.001073122 -0.008545577 0.003795921 0.001782298 -0.01111656 0.003746986 0.001880049 -0.009271204 0.002044558 0.001146733 -0.0114175 0.003033757 0.001576364 -0.00971347 0.007414162 0.002608716 -0.00745958 0.006719052 0.002180635 -0.009694755 0.007469296 0.002605915 -0.007362306 0.00707066 0.002051889 -0.009656965 0.00761795 0.002525389 -0.009628593 0.007729411 0.002465009 -0.009770631 0.007245719 0.002617418 -0.01001369 0.006529271 0.002654254 -0.007884681 0.005496025 0.002169013 -0.01023471 0.005971729 0.002499163 -0.01051437 0.005266249 0.002302825 -0.01094269 0.004185616 0.00200212 -0.009626984 0.007742822 0.002447426 -0.007341563 0.007180273 0.001960933 -0.009625017 0.007759094 0.002426147 -0.007350206 0.007219612 0.001834928 -0.009617209 0.007823526 0.002341628 -0.008643448 -0.002311587 -0.001285433 -0.008754372 -0.002470254 -0.00159794 -0.01129847 -0.002119362 -0.002136766 -0.01128619 -0.002087593 -0.001956045 -0.01125681 -0.002079486 -0.001815378 -0.01114207 -0.001933097 -0.001476109 -0.01068526 -0.00108391 -6.11996e-4 -0.01000344 3.70617e-4 3.34635e-4 -0.0112946 -0.00198847 -0.002182006 -0.005096375 0.006638109 0.001212 -0.004781246 -0.002788662 -0.001824021 -0.004542589 -0.003071427 -0.001678884 -0.00622195 -0.002588748 -0.001951992 -0.006323933 -0.002976953 -0.001694798 -0.001766502 0.004983365 -3.26844e-4 -0.002828717 0.004615128 -5.62299e-4 -0.003402411 0.004836559 -4.43314e-4 -0.004671812 0.00313431 -0.00121212 -0.00527209 0.002120077 -0.001551866 -0.007001936 0.002528905 -0.001481831 -0.005309879 0.002003967 -0.001582324 -0.007681012 8.26106e-4 -0.001980364 -0.005589723 0.00114417 -0.001807987 -0.005684077 2.40792e-4 -0.001971125 -0.004310846 0.00350517 -0.001062035 -0.006314158 0.004168212 -8.11608e-4 -0.003840923 0.003988027 -8.66697e-4 -0.005670964 0.005606353 -1.16089e-6 -0.003723144 0.00406295 -8.30708e-4 -0.002887845 0.004594624 -5.75407e-4 -9.77576e-4 0.005090951 -1.5241e-4 -0.001330852 0.005042791 -2.30521e-4 -0.003001391 0.005718529 2.25147e-4 -0.002900242 0.005895674 5.11676e-4 -8.39636e-4 0.005095541 -8.7847e-5 -0.002874195 0.005921542 6.3727e-4 -7.00131e-4 0.005101978 5.76489e-5 -7.50139e-4 0.005098521 -4.5964e-5 -7.15032e-4 0.0050987 -3.08175e-6 -7.03722e-4 0.00509876 1.074e-5 -0.003971695 -0.003681182 -0.001243114 -0.003995895 -0.003658652 -0.001266002 -0.006306171 -0.002889811 -0.001790761 -0.00414294 -0.003521919 -0.001405179 -0.004233539 -0.003437638 -0.00149095 -0.005612373 -8.13575e-4 -0.002073228 -0.005608737 -8.51456e-4 -0.002076447 -0.005851626 -0.001481175 -0.002098977 -0.005365431 -0.001626133 -0.002040326 -0.005271971 -0.001923799 -0.002026438 -0.01127386 -0.001878857 -0.002272903 -0.01117658 -0.001527249 -0.002401709 -0.01075148 -3.04271e-4 -0.002390027 -0.01009058 0.001395821 -0.002003312 -0.008794724 -0.00240457 -0.001950323 -0.008776903 -0.002305448 -0.002042889 -0.008689105 -0.001978218 -0.002185463 -0.008296668 -8.1377e-4 -0.002246379 -0.005698919 9.88087e-5 -0.001996755 -0.005125582 0.006622374 0.001079261 -0.005236506 0.006463766 7.66811e-4 -0.009668409 0.007840514 0.002011835 -0.009637951 0.007867217 0.002133846 -0.009630143 0.007850706 0.002212285 -0.009627103 0.007844328 0.002242624 -0.009364962 0.003147184 -0.001367747 -0.01199686 0.00298959 -0.001680135 -0.1039033 0.001488387 0.001294136 -0.01395839 0.003983736 0.001989483 -0.03380089 0.002591669 0.001807987 -0.02903211 0.003322899 0.002006173 -0.02794867 0.003449738 0.002000212 -0.02509826 0.003783524 0.001984596 -0.02245837 0.004092633 0.001970171 -0.02235156 0.004092693 0.001971244 -0.01957464 0.004094183 0.00199896 -0.05682194 -2.8556e-4 0.001013875 -0.05143415 9.27048e-5 0.001054108 -0.0489481 2.67241e-4 0.001072704 -0.04554396 7.89887e-4 0.001252412 -0.03951829 0.001715004 0.001570463 -0.09249883 -7.01994e-5 0.001385211 -0.09835046 -1.1338e-4 0.00136888 -0.06317657 -2.84036e-4 0.001149892 -0.06540071 -2.83501e-4 0.001197516 -0.0690453 -2.39675e-4 0.001232385 -0.08669829 -2.73958e-5 0.001401424 -0.08077788 -9.85889e-5 0.00134474 -0.01531147 0.004096448 0.002041578 -0.01677095 0.004095673 0.002026975 -0.05731362 -2.85443e-4 0.001024425 -0.100938 0.01118999 0.003128468 -0.09637081 0.01172518 0.003302633 -0.09631752 0.01220542 0.003361642 -0.0261594 0.01060533 0.004602015 -0.02616775 0.01064938 0.004558861 -0.03177863 0.01117891 0.004760742 -0.02063971 0.01003241 0.003761529 -0.04859942 0.01276719 0.004423737 -0.03739756 0.01177841 0.004603385 -0.03739553 0.01176851 0.004620671 -0.03179711 0.0112729 0.004634261 -0.05423057 0.01309937 0.004371106 -0.05422097 0.01314491 0.004367351 -0.06624138 0.01359212 0.00409305 -0.0782786 0.01349365 0.003778457 -0.07828313 0.01346635 0.003786563 -0.09928011 0.01193672 0.003217697 -0.09630239 0.01230192 0.00335735 -0.09031009 0.01287525 0.003533124 -0.04859954 0.01276439 0.004434704 -0.05421459 0.01317799 0.004356145 -0.05421537 0.01317346 0.004358947 -0.05421769 0.0131613 0.004363715 -0.05424422 0.01303619 0.004370093 -0.06626272 0.01348179 0.004099011 -0.07830184 0.0133596 0.003792405 -0.09032618 0.01277446 0.003537714 -0.04019653 0.01199018 0.004585027 -0.0430004 0.01222282 0.004533886 -0.04300355 0.01219922 0.004540681 -0.04860991 0.01270103 0.004455149 -0.04019594 0.01200658 0.004573166 -0.04019612 0.01201939 0.004560053 -0.04299807 0.01224261 0.004525899 -0.04299664 0.01225858 0.004516661 -0.0458005 0.01249557 0.004483401 -0.02060341 0.01001584 0.0039047 -0.01506888 0.009067773 0.003109037 -0.01509594 0.009069383 0.002965033 -0.02619385 0.01070892 0.004455089 -0.02623265 0.01072901 0.004328072 -0.03179204 0.0112645 0.004658758 -0.03180295 0.01127839 0.004608511 -0.03740042 0.01178497 0.004584848 -0.04019713 0.01202863 0.004545688 -0.04299604 0.01227086 0.00450623 -0.04579859 0.01251083 0.004476249 -0.04860079 0.01275455 0.004441618 -0.04860293 0.01274079 0.00444734 -0.04860597 0.0127229 0.004451811 -0.04299724 0.01228439 0.004481911 -0.04299622 0.01227945 0.004494667 -0.04020154 0.0120368 0.004513561 -0.04019898 0.01203441 0.004530251 -0.04579758 0.01253217 0.00445342 -0.0457974 0.01252979 0.004458546 -0.04439693 0.01240801 0.004469931 -0.04579758 0.01252222 0.004467964 -0.04439651 0.01240175 0.004480957 -0.04859912 0.01277035 0.004426717 -0.0542109 0.01317971 0.004350066 -0.04299807 0.01228553 0.004475116 -0.04299908 0.01228576 0.004468023 -0.045798 0.0125336 0.004447996 -0.04579865 0.01253414 0.004442274 -0.04300028 0.01228511 0.004460692 -0.031825 0.01127731 0.004523515 -0.03740841 0.01178818 0.004544198 -0.0318095 0.01128095 0.004581451 -0.037404 0.01178818 0.004565119 -0.03183394 0.01127117 0.00449264 -0.03741359 0.01178497 0.004522144 -0.05177789 0.01244139 0.004359483 -0.04306238 0.01185464 0.004581034 -0.04302489 0.012066 0.004555046 -0.03740006 0.0116387 0.004698157 -0.04020339 0.01191949 0.00461322 -0.03178167 0.01122182 0.004724025 -0.03458827 0.01146435 0.004721581 -0.03739529 0.0116955 0.004677474 -0.03534042 0.01133471 0.004777312 -0.03178477 0.01103675 0.004739701 -0.03177875 0.01112461 0.004791975 -0.02699416 0.01063525 0.004689037 -0.03742009 0.01147472 0.004724442 -0.02616024 0.01053053 0.004605889 -0.02058023 0.00996685 0.004024207 -0.02058404 0.009830176 0.004049956 -0.01818257 0.009528577 0.003810524 -0.01505434 0.009037911 0.003232777 -0.01507592 0.008910179 0.003277778 -0.02617919 0.01068401 0.004509925 -0.03178781 0.01125317 0.004681825 -0.03459054 0.01150101 0.004687368 -0.0373938 0.01173877 0.004651606 -0.09201705 0.01223534 0.003468632 -0.04719907 0.01264005 0.004455089 -0.04719829 0.01264882 0.004447042 -0.04859924 0.01276785 0.00443089 -0.05421274 0.01317876 0.004353106 -0.03739422 0.01175534 0.004636764 -0.04019796 0.01197022 0.004595696 -0.04301244 0.01214045 0.004550457 -0.05428415 0.01285511 0.004352927 -0.05434364 0.01254844 0.004306852 -0.0903927 0.01232504 0.003502845 -0.0811904 0.01283329 0.003696382 -0.07838004 0.01286858 0.003764986 -0.06635159 0.01301956 0.00405848 -0.06579911 0.01302653 0.00407195 -0.01276689 0.006996631 0.003091394 -0.09714788 0.007158339 0.002663016 -0.01330214 0.005606949 0.002698779 -0.04974621 0.007494091 0.003241062 -0.04396307 0.007634997 0.003512203 -0.04338008 0.01030653 0.004251718 -0.07873171 0.01100277 0.003477692 -0.07931429 0.007836341 0.002918303 -0.066747 0.01107031 0.003726303 -0.06740182 0.007837831 0.003070652 -0.05477702 0.01068663 0.003913462 -0.05549925 0.007545232 0.003140807 -0.04908901 0.01046007 0.004030466 -0.09121346 0.007520914 0.002777338 -0.04318529 0.01123762 0.00445646 -0.05451983 0.01181215 0.004163503 -0.0150609 0.008895158 0.003425717 -0.02057284 0.009770035 0.004195988 -0.01508331 0.008776843 0.003496944 -0.01517045 0.008440554 0.003577232 -0.02067178 0.009188652 0.004268586 -0.0205903 0.009615123 0.004247426 -0.02625131 0.009679675 0.004694163 -0.02617084 0.0102114 0.004725754 -0.03195565 0.009992003 0.004768729 -0.03183579 0.01063996 0.004853785 -0.03766727 0.01017922 0.004549086 -0.03750938 0.01096481 0.004695713 -0.02615499 0.010405 0.00469619 -0.03180098 0.0108776 0.00484997 -0.03817945 0.007867872 0.00389111 -0.03239601 0.008040845 0.004208683 -0.02661526 0.008056879 0.004235506 -0.02103108 0.007876336 0.00394237 -0.01552283 0.007367312 0.003445506 -0.05057305 0.003803551 0.002169549 -0.04472428 0.004248917 0.002434909 -0.03888773 0.00486803 0.00282979 -0.03305357 0.005449354 0.003186345 -0.02721619 0.005865752 0.003281354 -0.02162361 0.00608313 0.003130555 -0.01608651 0.005857348 0.002905368 -0.05639559 0.003665268 0.002117455 + + + + + + + + + + 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.9965841 -0.08258438 0 -0.9965841 0.08258438 0 -0.9965841 0.08258438 0 -0.9458234 0.3246817 0 -0.9458234 0.3246817 0 -0.7891305 0.6142256 0 -0.7891305 0.6142256 0 -0.546954 0.8371627 0 -0.546954 0.8371627 0 -0.2454884 0.9693995 0 -0.2454884 0.9693995 0 0.08258092 0.9965845 0 0.08258092 0.9965845 0 0.4016861 0.9157774 0 0.4016861 0.9157774 0 0.6772947 0.7357119 0 0.6772947 0.7357119 0 0.8794687 0.4759566 0 0.8794687 0.4759566 0 0.9863623 0.1645883 0 0.9863623 0.1645883 0 0.9863623 -0.1645883 0 0.9863623 -0.1645883 0 0.8794683 -0.4759573 0 0.8794683 -0.4759573 0 0.6772947 -0.7357119 0 0.6772947 -0.7357119 0 0.4016878 -0.9157767 0 0.4016878 -0.9157767 0 0.08258092 -0.9965845 0 0.08258092 -0.9965845 0 -0.2454884 -0.9693995 0 -0.2454884 -0.9693995 0 -0.546954 -0.8371627 0 -0.546954 -0.8371627 0 -0.7891312 -0.6142247 0 -0.7891312 -0.6142247 0 -0.9458231 -0.3246823 0 -0.9458231 -0.3246823 0 -0.9965841 -0.08258438 0 0.9989943 -0.04483824 0 0.9989943 0.04483824 0 0.9989943 0.04483824 0 0.9839274 0.1785689 0 0.9839274 0.1785689 0 0.9362366 0.3513705 0 0.9362366 0.3513705 0 0.8584481 0.5129004 0 0.8584481 0.5129004 0 0.753071 0.6579392 0 0.753071 0.6579392 0 0.6234884 0.7818326 0 0.6234884 0.7818326 0 0.4738689 0.8805955 0 0.4738689 0.8805955 0 0.3090192 0.9510558 0 0.3090192 0.9510558 0 0.1342313 0.9909501 0 0.1342313 0.9909501 0 -0.0448628 0.9989932 0 -0.0448628 0.9989932 0 -0.2225205 0.974928 0 -0.2225205 0.974928 0 -0.3930248 0.9195279 0 -0.3930248 0.9195279 0 -0.5509014 0.8345704 0 -0.5509014 0.8345704 0 -0.6910575 0.7227998 0 -0.6910575 0.7227998 0 -0.8090196 0.5877817 0 -0.8090196 0.5877817 0 -0.9009664 0.4338888 0 -0.9009664 0.4338888 0 -0.9639638 0.2660337 0 -0.9639638 0.2660337 0 -0.9959741 0.08964198 0 -0.9959741 0.08964198 0 -0.9959741 -0.08964198 0 -0.9959741 -0.08964198 0 -0.9639637 -0.266034 0 -0.9639637 -0.266034 0 -0.9009668 -0.433888 0 -0.9009668 -0.433888 0 -0.8090192 -0.5877822 0 -0.8090192 -0.5877822 0 -0.6910575 -0.7227998 0 -0.6910575 -0.7227998 0 -0.5509014 -0.8345704 0 -0.5509014 -0.8345704 0 -0.3930248 -0.9195279 0 -0.3930248 -0.9195279 0 -0.2225195 -0.9749282 0 -0.2225195 -0.9749282 0 -0.04486489 -0.9989931 0 -0.04486489 -0.9989931 0 0.1342323 -0.9909499 0 0.1342323 -0.9909499 0 0.3090201 -0.9510555 0 0.3090201 -0.9510555 0 0.4738689 -0.8805955 0 0.4738689 -0.8805955 0 0.6234877 -0.7818331 0 0.6234877 -0.7818331 0 0.753071 -0.6579392 0 0.753071 -0.6579392 0 0.8584481 -0.5129004 0 0.8584481 -0.5129004 0 0.9362366 -0.3513705 0 0.9362366 -0.3513705 0 0.9839274 -0.1785689 0 0.9839274 -0.1785689 0 0.9989943 -0.04483824 0 -0.4999995 -0.8660258 0 -0.4999995 -0.8660258 0 0.4999995 -0.8660258 0 0.4999995 -0.8660258 0 1 0 0 1 0 0 0.4999997 0.8660256 0 0.4999997 0.8660256 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -1 0 0 -1 0 0 -0.8315983 0 -0.5553776 -0.9807735 0 -0.1951498 -0.9807735 0 -0.1951498 -0.8968206 -0.001491665 -0.442392 -0.7074394 9.97705e-4 -0.7067734 -0.5550361 9.7822e-4 -0.8318256 -0.7068079 -0.001220107 -0.7074044 -0.2590129 7.38622e-4 -0.9658735 -0.2592328 7.38624e-4 -0.9658146 -0.1951038 0 -0.9807826 -0.4895182 -0.8498637 -0.1952022 -0.4508891 -0.7749888 -0.442822 -0.490391 -0.8493832 -0.1951017 -0.4484265 -0.776697 -0.4423295 -0.353557 -0.6123784 -0.7070999 -0.3535583 -0.6123806 -0.7070973 -0.3535615 -0.6123862 -0.7070908 -0.3535633 -0.612389 -0.7070875 -0.1293887 -0.2241076 -0.965937 -0.1293556 -0.2240509 -0.9659546 -0.1294133 -0.2241508 -0.9659236 -0.129415 -0.2241538 -0.9659228 0.490391 -0.8493832 -0.1951017 0.4153774 -0.7204593 -0.5553378 0.4484257 -0.7766973 -0.4423297 0.4903917 -0.8493847 -0.1950936 0.1260669 -0.2242044 -0.9663538 0.3545689 -0.6121364 -0.7068025 0.3545644 -0.6121287 -0.7068116 0.2782167 -0.4804821 -0.8317044 0.09798151 -0.1682361 -0.980865 0.1294134 -0.2241508 -0.9659237 0.9807735 0 -0.1951498 0.9807735 0 -0.1951498 0.8315983 0 -0.5553776 0.8315984 0 -0.5553777 0.5554269 0 -0.8315653 0.5554269 0 -0.8315654 0.1951038 0 -0.9807825 0.1951038 0 -0.9807826 0.490392 0.8493847 -0.1950935 0.490389 0.84938 -0.1951211 0.4157315 0.7200692 -0.5555786 0.4157686 0.7201306 -0.5554713 0.2777905 0.481146 -0.8314631 0.2777487 0.4810758 -0.8315177 0.09754443 0.1689523 -0.9807855 0.09754836 0.168959 -0.9807841 -0.4999997 0.8660256 0 -0.4999997 0.8660256 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.4903892 0.8493798 -0.1951216 -0.4903916 0.8493846 -0.1950947 -0.4157676 0.7201317 -0.5554708 -0.4157332 0.7200692 -0.5555775 -0.2777497 0.4810753 -0.8315178 -0.2777892 0.481146 -0.8314636 -0.09754818 0.1689587 -0.980784 -0.09754455 0.1689523 -0.9807855 0.9380454 0.3430646 -0.04875952 0.9409648 0.3349634 -0.04883366 0.9403008 0.3368203 -0.04885131 0.93853 0.3417016 -0.04900509 0.9422903 0.3312187 -0.04881608 0.9415481 0.3333531 -0.04861205 0.9380727 0.3429123 -0.04930436 0.9428136 0.3297684 -0.04853159 0.9527161 0.3005969 -0.04442471 0.9373074 0.3449735 -0.04947817 0.9336611 0.3545888 -0.05043691 0.947466 0.3161603 -0.04848611 0.9450699 0.3232786 -0.04831117 0.9403218 0.3367503 -0.0489304 0.9392864 0.3396136 -0.04902738 0.942059 0.3319129 -0.04856538 0.9350586 0.3509337 -0.05010902 0.9414962 0.3334573 -0.04889941 0.9788835 0.2017417 -0.03297644 0.9217047 0.3840562 -0.05441743 0.9535511 0.297795 -0.04537087 -0.1311252 -0.5000443 -0.8560151 -0.0688709 -0.4042395 -0.9120566 -0.001876413 -0.4185613 -0.9081866 0.1162558 -0.4212833 -0.899447 -1.02014e-4 -0.296878 -0.9549154 -1.02205e-4 -0.296878 -0.9549154 -0.08186966 -0.1619176 -0.9834023 -0.08583837 -0.1467799 -0.9854376 -0.08583825 -0.1467751 -0.9854384 -0.02561122 -0.1715323 -0.9848455 0.01218891 -0.4196318 -0.9076126 0.01218926 -0.4196316 -0.9076127 0.01218873 -0.4196316 -0.9076128 8.01087e-4 -0.4764463 -0.8792032 0.006049335 -0.4578118 -0.8890287 0.006049931 -0.4578116 -0.8890287 0.02466833 -0.5837358 -0.8115689 0.02466678 -0.5837358 -0.8115689 0.001665353 -0.4781582 -0.8782721 0.001665651 -0.4781582 -0.8782721 0.001665294 -0.4781582 -0.8782722 0.02466726 -0.5837368 -0.8115682 0.0400893 -0.3973282 -0.9168006 0.07103389 -0.5656813 -0.8215587 0.1164069 -0.06388795 -0.9911447 0.07103347 -0.5656828 -0.8215578 0.0710566 -0.5656813 -0.8215568 0.1349163 -0.4309611 -0.8922276 0.12598 -0.4229915 -0.8973335 0.1340265 -0.3818452 -0.9144567 0.1340258 -0.381847 -0.914456 0.1372376 -0.4377768 -0.8885479 0.1372385 -0.4377768 -0.8885477 0.1356312 -0.4348004 -0.8902543 0.1368671 -0.4303781 -0.8922119 0.1349198 -0.4309611 -0.8922272 -0.001875996 -0.4185613 -0.9081866 0.07891064 -0.6325629 -0.7704785 0.06039518 -0.585294 -0.8085687 0.07915318 -0.5024366 -0.8609832 0.07915198 -0.5024381 -0.8609826 -0.04691398 -0.405321 -0.9129699 -0.07657581 -0.4869766 -0.8700518 -0.07657372 -0.4869746 -0.870053 -0.1328992 -0.4993215 -0.8561635 -0.1328994 -0.4993232 -0.8561624 -0.06886994 -0.4042388 -0.9120571 -0.09809774 -0.4371743 -0.8940109 -0.1128863 -0.4122359 -0.9040566 -0.1223078 -0.4116028 -0.903119 -0.1155956 -0.4313455 -0.8947506 -0.1109182 -0.4315911 -0.8952242 -0.1151349 -0.4280922 -0.8963711 -0.1196589 -0.8030235 -0.5838108 -0.1225029 -0.6281058 -0.7684245 -0.08677548 -0.8125397 -0.5764107 -0.1331525 -0.892162 -0.4316451 -0.1304385 -0.8925052 -0.431764 -0.1169155 -0.8903505 -0.4400076 -0.06644421 -0.9154826 -0.3968335 -0.1095567 -0.9116168 -0.3961718 -0.1016619 -0.9234326 -0.3700502 -0.115778 -0.9226696 -0.3677991 -0.1157803 -0.9226694 -0.3677991 -0.09175717 -0.9475699 -0.3060912 -0.0917533 -0.9475714 -0.3060875 -0.05960422 -0.8811451 -0.4690744 -0.05960422 -0.881145 -0.4690744 -0.06087249 -0.870874 -0.4877222 -0.05529886 -0.731957 -0.6791031 -0.05529886 -0.7319569 -0.6791032 -0.05589699 -0.8643876 -0.4997096 -0.07867997 -0.915652 -0.3941967 -0.05960458 -0.8811451 -0.4690744 -0.05529826 -0.731957 -0.679103 -0.05101662 -0.7108609 -0.7014799 -0.06018793 -0.6089349 -0.7909334 -0.06018805 -0.6089349 -0.7909334 -0.02208614 -0.4258161 -0.9045401 -0.03985726 -0.3742344 -0.9264772 0.01082181 -0.1712258 -0.9851723 -0.03886187 -0.3737384 -0.9267197 -0.03985929 -0.3742344 -0.9264771 0.01868367 0.02934634 -0.9993947 -0.01746702 -0.09026008 -0.995765 -0.01746672 -0.09026008 -0.995765 -0.01670682 0.110915 -0.9936895 -0.01670676 0.110915 -0.9936895 -0.003880858 0.08398526 -0.9964594 -0.02423828 0.07883024 -0.9965934 -0.03069788 0.06903153 -0.9971421 -0.02734607 0.1471633 -0.9887341 -0.02686202 0.1463497 -0.9888682 -0.02734661 0.1471646 -0.9887339 -0.02379977 0.1082229 -0.9938417 -0.01972085 0.05536258 -0.9982716 -0.03639823 0.1434888 -0.9889824 -0.03639757 0.1434888 -0.9889824 -0.03639972 0.1434916 -0.9889819 -0.06759685 0.07744729 -0.9947023 -0.05830138 0.1464604 -0.9874969 -0.04939919 0.1464515 -0.9879836 -0.05358636 0.1079321 -0.992713 -0.05358642 0.1079319 -0.992713 -0.07574576 -0.8082292 -0.583976 -0.1353151 -0.7981218 -0.5871042 -0.1325113 -0.7735462 -0.6197314 -0.1195143 -0.7750259 -0.6205251 -0.1182417 -0.7722589 -0.6242076 -0.09042978 -0.7749918 -0.625468 -0.05064237 -0.7521716 -0.6570184 0.003038644 -0.754163 -0.6566804 0.01748538 -0.7899345 -0.6129419 0.066549 -0.6823608 -0.7279801 0.08416944 -0.6817949 -0.7266852 -0.1400623 -0.9073861 -0.396274 -0.1436218 -0.8523633 -0.5028416 -0.1060163 -0.8569001 -0.5044628 -0.07586771 -0.796727 -0.5995584 -0.06966233 -0.8101553 -0.5820615 0.01641279 -0.8133866 -0.581492 -0.1007203 -0.8947705 -0.4350185 -0.09987878 -0.9052579 -0.4129555 -0.0240429 -0.9102374 -0.4133882 -0.02176392 -0.7776618 -0.628306 0.04125481 -0.7780388 -0.6268602 -0.104348 -0.9018427 -0.4192748 -0.1222233 -0.8581126 -0.4987025 -0.002711057 -0.8660871 -0.4998857 0.001810729 -0.7310308 -0.6823421 0.04488533 -0.7310075 -0.6808915 0.07587075 -0.6001139 -0.7963083 0.05062854 -0.6006283 -0.7979238 0.08964669 -0.4943887 -0.8646059 -0.02424007 0.07883024 -0.9965933 -0.02422416 0.07882833 -0.9965938 -0.005174994 -0.01957845 -0.9997949 0.01723879 -0.01956796 -0.99966 0.04359602 -0.1678888 -0.9848414 0.01096385 -0.1680603 -0.9857157 0.04472452 -0.3775762 -0.9248979 -0.0197913 -0.3777983 -0.9256764 0.0175327 -0.5815984 -0.8132871 -0.04701298 -0.5807902 -0.8126947 -0.002527117 -0.7520821 -0.6590647 -0.03023898 -0.7515741 -0.6589552 -0.009804546 -0.8629055 -0.5052705 -0.06110936 -0.8609207 -0.5050558 -0.0301119 -0.2285598 -0.9730641 -0.03242826 -0.2379524 -0.9707352 0.001413762 -0.2387192 -0.9710876 -0.00210911 -0.2524928 -0.9675965 0.07250469 -0.2531747 -0.9646998 0.06045323 -0.2965191 -0.9531117 0.1053479 -0.2962033 -0.9492973 0.07772636 -0.3856083 -0.9193828 0.06822878 -0.3857122 -0.9200929 -0.03257793 -0.1176062 -0.9925258 -0.03239113 -0.1168122 -0.9926257 -9.95556e-4 -0.117223 -0.9931051 -0.006886899 -0.1419777 -0.9898459 0.06465864 -0.142371 -0.9876993 0.04169571 -0.2340631 -0.9713269 0.08592301 -0.2338195 -0.9684759 0.04456734 -0.3803453 -0.9237701 0.0685817 -0.3800679 -0.9224125 0.02113944 -0.5291374 -0.8482728 0.05569148 -0.5288138 -0.8469088 0.002515017 -0.6749839 -0.7378281 0.0286017 -0.675015 -0.7372493 -0.007751584 -0.8225014 -0.5687102 -0.04882901 -0.8211048 -0.568685 -0.04838275 -0.8819656 -0.4688239 -0.09175282 -0.9475703 -0.3060913 -0.06032317 -0.1321178 -0.9893968 -0.06592416 -0.1529336 -0.9860352 -0.1116858 -0.1514757 -0.9821311 -0.1244434 -0.1756855 -0.9765492 -0.07263606 -0.1775785 -0.9814224 -0.06793016 -0.1658967 -0.9838007 -0.05721205 -0.1662046 -0.9844301 -0.05423992 -0.001174747 -0.9985273 -0.05769979 -0.01363468 -0.998241 -0.07088923 -0.01345336 -0.9973935 -0.1095229 -0.07365304 -0.9912517 -0.03844475 -0.1003425 -0.9942098 -0.03844439 -0.1003425 -0.99421 -0.02285265 -0.4384536 -0.8984633 -0.01110947 -0.3320993 -0.943179 -0.01232504 -0.3859761 -0.9224264 0.01523506 -0.3866919 -0.922083 -0.02561122 -0.1715323 -0.9848456 -0.05729997 -0.1715476 -0.983508 -0.04463446 -0.1719042 -0.9841019 -0.06824851 -0.1828023 -0.9807779 -0.0748561 -0.1825842 -0.9803365 -0.1253906 -0.2297077 -0.9651485 -0.06548309 -0.232334 -0.9704292 -0.06714779 -0.2384826 -0.9688226 -0.01278388 -0.240171 -0.9706465 -0.0120272 -0.1331825 -0.9910185 -0.01710569 -0.1713117 -0.9850683 -0.0154547 -0.001627206 -0.9998793 -0.02323275 -0.0590372 -0.9979854 -0.02026629 0.118122 -0.9927922 -0.0311501 0.05541044 -0.9979777 -0.03073811 0.07164406 -0.9969566 -0.02686172 0.1463497 -0.9888681 -0.006346523 -0.1780343 -0.9840039 -0.04517441 -0.1976134 -0.9792385 -0.03993606 -0.1977658 -0.9794354 -0.07642227 -0.2644421 -0.9613688 -0.04260909 -0.2657607 -0.963097 -0.04342579 -0.3215308 -0.9459028 -0.008475244 -0.3226774 -0.9464711 -0.008122444 -0.2780221 -0.9605403 -0.00949347 -0.2779872 -0.9605379 -0.009209036 -0.171472 -0.9851459 -0.0165829 -0.228893 -0.9733104 -0.01583713 -0.05913531 -0.9981243 -0.02320671 -0.1177538 -0.9927716 -0.0213418 0.06362217 -0.9977458 -0.02445626 0.06361973 -0.9976745 -0.04845893 -0.5301549 -0.8465148 -0.04545497 -0.5256147 -0.8495075 -0.1007234 -0.5221536 -0.8468828 -0.09296977 -0.5106179 -0.8547666 -0.1284492 -0.5078989 -0.851786 -0.1240711 -0.5015995 -0.8561567 -0.132039 -0.5009838 -0.8553251 -0.1311249 -0.5000397 -0.8560178 0.002507209 -0.439309 -0.8983325 0.002090334 -0.4406009 -0.8977007 0.05757206 -0.4414934 -0.8954156 0.06778573 -0.4123452 -0.9085024 0.1063402 -0.4120686 -0.9049261 0.1092366 -0.4040786 -0.9081783 0.1271749 -0.4037289 -0.9059964 0.1112837 -0.4768969 -0.871886 0.1338776 -0.4762215 -0.8690741 0.1190496 -0.5180151 -0.8470464 0.06191956 -0.5190708 -0.8524855 0.09910082 -0.4022516 -0.9101498 0.01842349 -0.5324613 -0.8462539 0.1162564 -0.4212833 -0.899447 0.09140008 -0.4177559 -0.9039503 0.1030432 -0.4616239 -0.8810706 0.03818398 -0.4616364 -0.886247 0.05443936 -0.5143285 -0.8558636 -0.007098555 -0.5130882 -0.8583065 0.00204432 -0.5151891 -0.8570742 -0.01298576 -0.5488218 -0.8358386 -0.01359635 -0.4079802 -0.9128895 0.001430451 -0.4084483 -0.9127804 -0.1225029 -0.6281057 -0.7684246 -0.1171903 -0.6238232 -0.7727296 -0.1148021 -0.6240411 -0.7729122 -0.1315574 -0.6454012 -0.7524294 -0.0895912 -0.6492995 -0.7552374 -0.09658443 -0.6584424 -0.7464081 -0.05008375 -0.6617404 -0.7480583 -0.04705774 -0.6577203 -0.7517909 0.005111336 -0.6596504 -0.7515552 0.01652228 -0.644231 -0.7646526 0.06846654 -0.6440308 -0.7619296 0.09292185 -0.6101011 -0.7868559 0.08934247 -0.6102164 -0.7871811 0.1182146 -0.5334475 -0.8375315 0.08645761 -0.5344466 -0.8407686 0.116984 -0.3935669 -0.9118223 0.09957832 -0.3939061 -0.9137406 0.1122337 -0.3562548 -0.9276239 0.06909608 -0.3566194 -0.9316912 0.07005381 -0.3535532 -0.9327876 8.06863e-4 -0.3527192 -0.9357289 0.002531766 -0.3466466 -0.9379925 -0.02922338 -0.3457061 -0.9378877 -0.02389836 -0.325904 -0.9451007 -0.003136277 -0.3265077 -0.9451894 -0.003335177 -0.3744457 -0.9272429 -0.001819252 -0.3744878 -0.9272301 -0.002938985 -0.4575482 -0.8891801 0.005989074 -0.4119517 -0.911186 0.005249261 -0.1589227 -0.9872771 0.1713078 -0.3413809 -0.9241822 -0.1806587 0.4271861 -0.8859314 0.1551823 -0.2786565 -0.9477706 0.1743429 -0.2816169 -0.9435552 0.103515 -0.2768854 -0.9553111 0.05153852 -0.2313669 -0.9715005 0.004853844 -0.1643218 -0.9863948 0.01313954 -0.1656469 -0.9860976 0.07433468 -0.2515988 -0.9649727 0.04447025 -0.2348407 -0.9710161 0.04456681 -0.2230411 -0.9737898 0.05269891 -0.1917768 -0.9800227 0.03101176 -0.2044363 -0.9783885 0.02447783 -0.2033103 -0.9788084 0.01313954 -0.1656469 -0.9860976 0.006638646 -0.1748253 -0.9845771 0.01193201 -0.1756718 -0.9843765 0.01769137 -0.1745591 -0.9844878 0.03198641 -0.1892422 -0.9814093 0.03198641 -0.1892421 -0.9814093 0.1071584 -0.2802643 -0.9539231 0.1065084 -0.3084192 -0.9452691 0.1104816 -0.3092198 -0.9445512 0.136972 -0.2383518 -0.9614713 0.1503064 -0.2944689 -0.9437669 0.1336659 -0.2911129 -0.947305 0.1335875 -0.2906152 -0.9474689 0.102607 -0.2853215 -0.9529236 0.1019505 -0.2775055 -0.9552993 -0.2109562 0.5383392 -0.8158974 -0.2253972 0.4548352 -0.8615806 -0.2253986 0.4548351 -0.8615802 -0.2203192 0.5568488 -0.8008614 -0.2137507 0.5573391 -0.802299 -0.2118314 0.6583672 -0.7222741 -0.2194362 0.6194701 -0.7537271 -0.2194361 0.6194701 -0.7537271 -0.212511 0.5271258 -0.8227864 -0.2125061 0.5271265 -0.8227871 -0.1795245 0.4309205 -0.884352 -0.1868844 0.4301338 -0.8832095 -0.1441177 0.412985 -0.8992628 -0.1806662 0.4271367 -0.8859537 -0.1950497 0.3633117 -0.9110216 -0.2258724 0.3686948 -0.9016905 -0.2422187 0.2800385 -0.9289287 -0.2113133 0.2741737 -0.9381767 -0.2218448 0.1771885 -0.9588479 -0.1536583 0.1634902 -0.9745051 -0.1538971 0.06859683 -0.9857029 -0.04929339 0.04894638 -0.9975843 -0.03867596 -0.02519959 -0.9989341 0.05808264 -0.04008138 -0.9975069 0.06843149 -0.0874325 -0.9938173 0.1135398 -0.09403204 -0.9890736 0.1350755 -0.1796137 -0.9744195 0.1586702 -0.1833881 -0.9701509 0.1702793 -0.245686 -0.9542763 0.1709277 -0.2457867 -0.9541345 0.09921211 -0.03683811 -0.9943842 0.08190357 -0.03425896 -0.9960512 0.01468235 0.1268725 -0.9918103 -0.01978337 0.1297596 -0.9913482 -0.05818837 0.2098007 -0.9760112 -0.1098756 0.2125083 -0.9709622 -0.1466751 0.3169896 -0.9370187 -0.1855828 0.3189758 -0.9294157 -0.2025965 0.4302205 -0.879696 -0.2221053 0.4309979 -0.8745915 -0.2228091 0.5305508 -0.8178459 -0.2197698 0.5304881 -0.8187084 -0.2117864 0.6127168 -0.7613965 0.1472211 -0.20647 -0.9673138 0.1304727 -0.129175 -0.9830008 0.1196265 -0.1266359 -0.9847095 0.05973583 0.08651673 -0.9944579 -0.01621317 0.1616851 -0.9867092 0.001874566 0.1595896 -0.9871817 -0.2721973 0.7591984 -0.5912075 -0.272198 0.7591984 -0.5912073 -0.2254248 -4.65875e-4 -0.9742605 -0.2254245 -4.63141e-4 -0.9742605 -0.2254316 -4.8393e-4 -0.9742588 -0.2137086 0.0294581 -0.9764533 -0.2112612 0.02859097 -0.9770114 -0.2392392 -0.04388636 -0.9699683 -0.1702244 -0.068237 -0.9830398 -0.1943068 -0.1338438 -0.9717668 -0.08125901 -0.1704745 -0.9820058 -0.09802973 -0.2204393 -0.9704622 0.05433428 -0.2606481 -0.9639037 0.04771035 -0.2842652 -0.9575579 0.1616045 -0.3060481 -0.9381996 0.1603514 -0.3103001 -0.9370173 0.1906663 -0.3150279 -0.929733 0.1902542 -0.3220362 -0.9274137 0.2013624 -0.3236865 -0.9244892 0.2014201 -0.3233295 -0.9246015 0.1864913 -0.3211691 -0.928478 0.1879719 -0.3159272 -0.9299767 0.1450846 -0.3094143 -0.9397942 0.1560709 -0.2834333 -0.9462069 0.140791 -0.3859225 -0.9117245 0.140792 -0.3859226 -0.9117243 0.1996271 -0.4143944 -0.8879337 0.1733824 -0.4462011 -0.8779767 0.2058569 -0.4505137 -0.8687119 0.1783043 -0.5029844 -0.8457034 0.2002874 -0.5060184 -0.8389459 0.1799775 -0.5240288 -0.8324674 -0.1232838 -0.4174719 -0.9002879 -0.1407303 -0.4221088 -0.8955551 -0.1782436 -0.4069268 -0.8959017 0.1275022 -0.5496439 -0.8256118 0.1275029 -0.5496441 -0.8256115 0.1106559 -0.5313091 -0.8399202 -0.03407436 -0.4953835 -0.8680058 -0.02472221 -0.4980958 -0.8667696 -0.03412371 -0.5066555 -0.8614731 -0.03412359 -0.5066555 -0.861473 -0.1276484 -0.2635011 -0.9561764 0.03313148 -0.227968 -0.9731047 0.0336917 -0.2097631 -0.9771716 0.01793354 -0.2180761 -0.975767 -0.001448631 -0.1630975 -0.9866089 -0.00144875 -0.1630975 -0.9866089 0.01775789 -0.1728991 -0.9847795 0.01300132 -0.1740866 -0.9846446 0.02556085 -0.1761317 -0.9840347 0.01294523 -0.191918 -0.9813256 0.01294529 -0.191918 -0.9813256 -0.09429967 0.7683993 -0.6329851 -0.06235629 0.9185007 -0.3904715 -0.1220315 0.7676753 -0.6291129 -0.1585274 0.611826 -0.7749439 -0.1129512 0.7679843 -0.6304301 -0.1878217 0.4282394 -0.8839309 0.1071542 -0.2802634 -0.9539237 0.07477629 -0.2672275 -0.9607279 0.07551223 -0.2715715 -0.9594514 0.06792026 -0.2504016 -0.9657567 0.05637794 -0.2686865 -0.9615764 -0.1478201 -0.3748794 -0.9152129 -0.1862615 -0.238717 -0.9530587 -0.1862612 -0.2387132 -0.9530597 -0.138624 -0.03327184 -0.9897861 -0.2016395 -0.1956439 -0.9597213 -0.1756435 -0.2064744 -0.9625579 -0.2114503 -0.2603262 -0.9420823 -0.1262971 -0.2940738 -0.9474015 -0.1552389 -0.3351153 -0.9293 -0.03427278 -0.3766916 -0.9257045 -0.05127149 -0.3999599 -0.9150974 0.09618228 -0.4388877 -0.8933792 0.09663873 -0.4382542 -0.893641 0.1897471 -0.4551512 -0.8699618 0.2019135 -0.4394042 -0.8753027 0.204022 -0.4397036 -0.8746632 0.2145075 -0.4076069 -0.8876052 0.198351 -0.4053899 -0.8923653 0.212405 -0.3727276 -0.9033041 0.1741288 -0.3673689 -0.9136297 0.1896438 -0.3387524 -0.9215651 0.1306232 -0.3297729 -0.9349799 0.1449594 -0.3082438 -0.9401981 0.07770311 -0.2965819 -0.951841 0.01752454 -0.2629478 -0.9646509 0.07171607 -0.2693796 -0.9603601 0.07700294 -0.2704169 -0.959659 0.07175666 -0.2768362 -0.9582342 0.1282107 -0.286891 -0.9493448 0.07192379 -0.3594455 -0.9303902 0.1384292 -0.3364484 -0.931472 0.0177741 -0.2361293 -0.971559 0.03739273 -0.2399765 -0.9700583 0.05639231 -0.2693367 -0.9613935 0.09282809 -0.2764587 -0.956532 0.09374022 -0.2928358 -0.9515566 0.1367661 -0.3002367 -0.944009 0.1347706 -0.285632 -0.9488157 0.1535634 -0.2886505 -0.9450393 0.1500012 -0.271753 -0.9506051 0.1446703 -0.2706013 -0.9517591 -0.02748084 0.9737832 -0.2258123 0.08057141 0.9263958 0.36783 -0.190285 0.5952562 -0.7806802 0.05951899 0.9778378 0.2007261 -0.3633603 0.9315009 -0.01659464 -0.360602 0.9325879 -0.01568603 -0.2361642 0.8623613 0.4478386 -0.122901 0.5444264 -0.8297562 0.07359427 -0.07085251 -0.9947682 0.004723668 -0.2377229 -0.9713216 -0.002138316 -0.2893069 -0.957234 -0.01800447 -0.4070066 -0.9132478 -0.07193559 -0.7718223 -0.6317561 -0.01799517 -0.4069343 -0.9132801 -0.002158939 -0.2894448 -0.9571923 -0.002187371 -0.2896587 -0.9571275 0.01157206 -0.4575403 -0.8891136 0.01157277 -0.4575308 -0.8891185 0.00699687 -0.5136919 -0.8579462 0.00685507 -0.5136688 -0.8579612 0.04507207 0.09107285 -0.9948236 0.01250183 -0.454811 -0.8905003 0.005950629 -0.5257813 -0.8505989 -0.006407618 -0.5237161 -0.8518687 0.003013908 -0.436806 -0.8995506 -0.02250444 -0.4323514 -0.9014243 0.004726231 -0.2377009 -0.971327 0.06296092 -0.1737681 -0.9827719 0.04010784 -0.4805353 -0.8760576 0.04010802 -0.4805353 -0.8760577 0.1010716 -0.2715135 -0.9571129 0.09167397 -0.1909227 -0.9773148 -0.1641982 0.5619711 -0.8106955 -0.1521459 0.5631996 -0.8121932 -0.04802304 0.3031606 -0.9517287 -0.03497928 0.3023804 -0.9525453 0.03481352 0.08780914 -0.9955288 0.02865499 0.1089559 -0.9936336 -0.08557564 0.4221835 -0.9024621 -0.09588819 0.4221783 -0.9014272 -0.01544606 0.2379826 -0.9711467 -0.06987196 0.4055483 -0.9113993 -0.08142018 0.4056712 -0.9103855 -0.1393586 0.5661499 -0.8124368 -0.1546891 0.5647402 -0.8106417 -0.2015532 0.6774619 -0.7074049 -0.2152798 0.6748235 -0.7058809 -0.2445905 0.7394838 -0.6271676 -0.2490219 0.7382909 -0.6268292 0.063488 0.01004391 -0.997932 0.0635038 0.00993365 -0.9979321 -0.2337284 0.8421232 0.4860037 -0.2351374 0.8546471 0.4629133 -0.1705195 0.840239 -0.5147053 -0.1869013 0.7200522 -0.6682759 -0.2031003 0.716915 -0.6669207 -0.2758538 0.8834525 -0.3787037 -0.2968365 0.8762072 -0.3796697 -0.3387915 0.9400762 -0.03843367 -0.2229451 0.8087235 -0.5442994 -0.2403393 0.8041153 -0.5437239 -0.3047416 0.9344242 -0.1843471 -0.3264524 0.9263468 -0.1879107 -0.3445532 0.9315909 0.1158521 -0.236165 0.8623611 0.4478384 -0.2358154 0.8597651 0.4529846 -0.2358238 0.8597765 0.4529587 -0.1327971 0.9788153 -0.1558384 -0.1122726 0.9307117 0.3480957 -0.2625882 0.9029895 -0.3400843 -0.2625864 0.9029901 -0.3400839 -0.2619487 0.8833761 0.388625 -0.366628 0.9092555 -0.1970744 -0.376205 0.9046672 -0.2001171 0.06614339 0.9771131 0.2021757 0.0307604 0.9979269 0.05653119 -0.02888089 0.9985597 0.04521685 -0.04948598 0.9984836 -0.02411526 -0.09884929 0.9945439 -0.0333386 -0.1146385 0.9889788 -0.0936957 -0.1905049 0.9756655 -0.1085582 -0.1998463 0.9662845 -0.1623439 -0.31277 0.9311745 -0.1873206 -0.3141399 0.9218161 -0.2270925 -0.371665 0.8963307 -0.2417778 -0.3709644 0.893948 -0.2514804 -0.3441089 0.9064256 -0.2449116 -0.3475441 0.9126436 -0.2151622 -0.3423848 0.9148324 -0.2141363 -0.3304105 0.8925706 -0.3068332 -0.3254703 0.8945752 -0.3062747 -0.3093305 0.8638948 -0.3974925 -0.2923954 0.8700435 -0.3968996 -0.3721666 0.9267867 0.05058056 -0.364948 0.9283593 0.07044142 -0.3664029 0.9278302 0.06985825 -0.3629081 0.9103789 0.1987665 -0.3629091 0.9103782 0.1987674 -0.2494956 0.8284264 -0.5014595 -0.2692732 0.8225071 -0.5009732 -0.3222597 0.9221277 -0.2140774 -0.3388735 0.9155553 -0.2166175 -0.3560732 0.9334677 -0.04301291 -0.3621553 0.9289643 0.07660859 -0.3624384 0.9255416 0.1095954 -0.3607096 0.9323253 0.02565407 -0.1718832 0.3516023 0.9202347 0.0955584 -0.0582779 -0.9937164 0.09555804 -0.0582779 -0.9937165 -0.05873996 0.3286855 -0.942611 0.1123422 -0.1595012 -0.9807847 0.0863232 -0.07797271 -0.9932112 0.1228757 -0.2693179 -0.9551803 0.11785 -0.1598879 -0.9800751 0.0981726 -0.2372085 -0.9664856 0.1097055 -0.2391793 -0.964758 0.1005748 -0.1924103 -0.976147 0.01169997 0.1797295 -0.9836465 0.01171582 0.1796652 -0.983658 0.01171654 0.1796637 -0.9836583 0.01171445 0.1796657 -0.983658 0.03808182 0.1682919 -0.9850013 0.06348758 0.01004689 -0.997932 -0.1787852 0.5971062 -0.7819846 -0.1138643 0.4366634 -0.8923901 -0.1036788 0.4369677 -0.8934819 -0.02725183 0.2376846 -0.97096 -0.01917141 0.2370132 -0.9713172 0.0678786 0.00986433 -0.9976448 0.09891432 -0.09669971 -0.9903863 0.09640032 -0.09629607 -0.9906736 0.09989738 -0.1114557 -0.9887356 0.09545701 -0.08175045 -0.992071 -0.04682123 0.2369161 -0.9704013 -0.04681658 0.2369161 -0.9704015 0.1400937 -0.2217401 -0.9649897 0.1030022 -0.1004186 -0.9895992 0.1030018 -0.1004186 -0.9895992 0.1117981 -0.1235619 -0.9860191 0.03941386 0.1156626 -0.9925063 0.02328771 0.1176757 -0.992779 0.006434798 0.1641437 -0.9864155 -0.116795 0.4523753 -0.8841467 -0.1262128 0.4518698 -0.8831105 -0.2149045 0.6512019 -0.7278407 -0.285433 0.8447529 -0.4526815 -0.2274654 0.7129287 -0.6633191 -0.285426 0.8447546 -0.4526826 -0.2532875 0.6608857 -0.7064527 -0.2463421 0.6627926 -0.7071219 0.001586675 0.9747444 -0.2233175 -0.1134955 0.8075388 -0.5787919 -0.1803175 0.9422334 -0.2822797 -0.1803175 0.9422334 -0.2822797 -0.1962372 0.8068009 -0.5572821 0.01137751 0.9867649 0.1617583 0.004857361 0.9868764 0.161404 0.05097675 0.946786 0.3178014 0.05097627 0.946786 0.3178014 0.1351757 -0.22291 -0.9654214 -0.2568745 0.6514168 -0.7139129 -0.2526389 0.641088 -0.7246929 -0.2962955 0.7391082 -0.6049198 -0.2625594 0.7512471 -0.6055497 -0.2555018 0.7359561 -0.6269668 -0.2461075 0.7386388 -0.6275697 -0.190759 0.6086225 -0.7701881 -0.1811422 0.6101183 -0.7713255 -0.09822201 0.404339 -0.9093198 -0.08289915 0.4042969 -0.9108632 0.002371966 0.1687154 -0.9856619 0.01422697 0.1674003 -0.9857864 0.07422804 -0.02795332 -0.9968494 0.07367265 -0.02786833 -0.996893 0.04097831 0.08699661 -0.9953654 -0.2511831 0.8765996 0.4104635 0.007790207 0.2359401 -0.9717364 0.006240189 -0.2036868 -0.9790162 0.00623387 -0.2037376 -0.9790056 0.009305417 -0.1811404 -0.9834132 0.03573274 -0.1292566 -0.9909671 0.04314148 -0.2726754 -0.9611384 0.05058276 -0.1037126 -0.9933203 0.01184594 -0.4545369 -0.8906491 0.01157432 -0.4575142 -0.889127 0.01157397 -0.4575141 -0.889127 0.03573256 -0.1292566 -0.9909672 0.03640651 -0.1227149 -0.9917739 0.03613388 -0.1226736 -0.9917891 0.02120351 -0.2077573 -0.9779505 0.01419109 -0.1568927 -0.9875138 0.01297348 -0.1567055 -0.9875602 0.01123547 -0.1814417 -0.9833375 -0.1327983 0.9788151 -0.1558386 -0.1098366 0.9913924 -0.07125425 -0.1155883 0.9906599 -0.0723356 0.03440344 0.9529741 0.3010928 -0.06400448 0.9620527 -0.2652506 -0.04056525 0.9656728 -0.2565749 0.04250609 0.9794852 0.1969826 0.06348836 0.01004314 -0.9979321 0.06349176 0.0100187 -0.9979321 0.1060345 -0.3366414 -0.9356437 0.1035798 -0.3359352 -0.9361723 0.07772034 -0.2082184 -0.9749895 0.07687181 -0.418085 -0.9051495 0.07687181 -0.418085 -0.9051495 -0.02997696 0.9736621 -0.2260164 -0.01507633 0.986286 -0.1643552 -0.080006 0.9819681 -0.1712825 -0.1019306 0.9634497 -0.2477391 -0.1409485 0.9576869 -0.2509368 -0.1588996 0.9316993 -0.3266304 -0.2118914 0.9198061 -0.3302406 -0.221631 0.8855321 -0.4083047 -0.3000879 0.8598104 -0.4131262 -0.2959113 0.8225008 -0.4857252 -0.3305718 0.8079862 -0.4877301 -0.3347461 0.8181954 -0.4674412 -0.3028046 0.8319358 -0.4649648 -0.3108344 0.8480697 -0.4291384 -0.3052136 0.8502514 -0.4288557 -0.2870093 0.8125517 -0.5073314 -0.2816833 0.814362 -0.5074142 -0.265416 0.7805708 -0.5659185 -0.2503627 0.7848827 -0.5668136 -0.2210576 0.7187479 -0.6591926 -0.2028539 0.7225832 -0.6608508 -0.1467351 0.5758056 -0.8043113 -0.1319879 0.5771814 -0.805879 -0.06887644 0.3921012 -0.91734 -0.03446412 0.3912883 -0.9196226 -0.07842433 0.5470057 -0.8334472 -0.1139095 0.6663984 -0.7368432 -0.165741 0.659696 -0.7330288 -0.2307209 0.8255993 -0.5149307 -0.2416273 0.6098766 0.7547627 -0.2979579 0.8305279 0.4705789 -0.1439022 0.2721803 0.9514252 -0.2400407 0.7834835 -0.573179 -0.1718844 0.3516021 0.9202345 0.05320155 -0.1735382 -0.9833891 0.05320155 -0.1735381 -0.9833891 0.06241887 -0.2588545 -0.9638975 0.07313925 -0.2120463 -0.9745188 0.07791918 -0.2128013 -0.9739837 0.07495123 -0.2735999 -0.9589189 0.09187871 -0.2698331 -0.9585136 0.1051189 -0.2628245 -0.9591003 0.1009629 -0.2621039 -0.9597437 0.0953924 -0.1821702 -0.9786288 0.0953918 -0.18217 -0.9786289 0.1106883 0.6840591 0.7209793 -0.03416138 0.2953475 0.954779 0.001726865 0.2160686 0.9763767 -0.002934396 0.2168056 0.9762104 0.1173499 0.9900606 0.07751685 0.05664753 0.5023909 0.862783 0.003668129 0.2157607 0.9764394 -0.006261408 0.1830678 0.9830804 -0.05189275 0.2715483 0.9610248 -0.01387429 0.2493786 0.9683067 -0.03477406 0.2532503 0.9667755 -5.58595e-4 0.1821541 0.9832699 -0.004706025 0.187691 0.9822168 -4.55708e-4 0.1870131 0.9823573 -0.01589393 0.2029332 0.9790636 -1.73138e-4 0.2003703 0.9797202 -0.02369946 0.2054463 0.9783814 -0.0146358 0.2171702 0.976024 -0.0146358 0.2171702 0.976024 -0.006912171 0.6310112 0.7757429 -0.02596259 0.6359813 0.7712675 0.05686956 0.5899608 0.8054268 0.04295754 0.5819875 0.8120624 -0.02826136 0.6537162 0.7562119 -0.0282613 0.6537162 0.756212 -0.1076158 0.6259253 0.7724224 -0.1235661 0.6338233 0.763544 -0.1819752 0.6426298 0.7442526 -0.1138045 0.5852578 0.8028213 -0.1138039 0.5852576 0.8028214 -0.1367828 0.5316621 0.8358384 -0.07256937 0.5153951 0.8538745 -0.1253858 0.5245776 0.8420788 -0.0521878 0.4358146 0.8985222 -0.09354251 0.4433627 0.891448 -0.0671882 0.8180081 -0.5712691 -0.06719404 0.8180075 -0.5712693 -0.1203908 0.5112428 0.8509624 -0.1204087 0.5114179 0.8508546 -0.1204127 0.5114552 0.8508316 -0.2184019 0.9474106 -0.2339096 -0.1345193 0.6652936 0.7343629 -0.1125875 0.953794 -0.2785699 0.01632839 0.3470485 -0.937705 -0.1719146 0.855529 -0.4883804 -0.1338991 0.7080954 -0.6933052 -0.1339005 0.7080947 -0.6933055 -0.2240537 0.9215766 -0.3170117 -0.2406538 0.9006083 0.361926 -0.1830052 0.6618102 0.7269913 -0.2161766 0.6629755 0.7167504 -0.3109142 0.8363183 0.4515572 -0.3308342 0.9377092 -0.1060669 -0.330832 0.9377101 -0.1060659 -0.3700447 0.8995828 0.2319865 -0.2294853 0.7072777 0.6686514 -0.2746269 0.7064391 0.6523219 -0.2934947 0.7839261 0.5471022 -0.3352712 0.7795239 0.5290894 -0.3376641 0.8437368 0.4172423 -0.3519797 0.8670954 0.3524998 -0.3432208 0.868895 0.3566802 -0.3614675 0.9035923 0.2299179 -0.3614658 0.9035927 0.2299188 -0.3546441 0.8869006 0.2960315 -0.3546454 0.8869004 0.2960309 -0.2986605 0.9480959 0.1091611 -0.1585565 0.870166 0.4665522 -0.1585581 0.870166 0.4665516 0.01170057 0.8750931 0.4838132 0.02444702 0.8628985 0.5047855 0.02444678 0.8628986 0.5047854 0.06076776 0.8780203 0.4747501 0.1249011 0.8187417 0.5604122 0.1249015 0.8187416 0.5604123 0.1432939 0.8778851 0.4569298 0.1108752 0.6839223 0.7210804 0.1108862 0.683992 0.7210128 0.08415251 0.8453643 0.5275202 0.08414447 0.8453196 0.5275931 0.084185 0.8455463 0.5272234 0.05567532 0.6718641 0.738579 0.04665982 0.6140646 0.7878753 0.04666042 0.6140688 0.7878721 0.01825141 0.4099986 0.9119036 0.01825463 0.4100214 0.9118933 0.01825869 0.4100506 0.9118799 0.07379454 0.7786639 -0.6230865 0.0737254 0.774368 -0.6284257 0.07374632 0.7702518 -0.6334616 0.07090139 0.7703946 -0.6336128 -0.001503109 0.5758407 0.8175605 -0.002930939 0.2168307 0.9762048 0.06430238 0.6997316 0.7115061 0.02575427 0.7054328 0.7083088 0.0737949 0.7786782 -0.6230685 0.07379549 0.7786782 -0.6230685 -0.03914719 0.2411808 0.9696903 0.07076752 0.7627708 -0.642785 0.07364946 0.7626294 -0.6426291 0.07369184 0.7699385 -0.6338487 0.06879401 0.7701868 -0.6340976 -0.05798298 -0.1169545 0.9914432 0.06093496 0.4775697 -0.8764783 -0.0626707 0.2327649 0.9705117 0.04406493 0.4103468 -0.9108643 0.04406493 0.4103468 -0.9108643 -0.0826295 0.3245416 0.9422553 0.01844871 0.3349464 -0.9420565 0.01844882 0.3349465 -0.9420566 0.06149888 0.3789626 -0.9233663 0.05997747 0.4775829 -0.8765372 0.06006348 0.467373 -0.8820175 0.05198919 0.4674592 -0.8824846 0.05481183 0.3953286 -0.916903 0.038944 0.3945211 -0.9180614 0.04534077 0.3200139 -0.9463274 0.01787984 0.3157959 -0.9486586 -0.1504732 0.8586736 0.4899361 -0.791997 0.6095243 0.03494173 -0.242087 0.9632242 0.1165883 0.003363728 0.6266527 0.7792914 -0.02056664 0.6295357 0.7766993 -0.01593369 0.6837949 0.7295004 -0.0506215 0.6872424 0.7246623 -0.04911267 0.711547 0.70092 -0.0888195 0.7145281 0.6939457 -0.08835488 0.7361363 0.6710414 -0.1443547 0.7385619 0.65855 -0.1496825 0.89144 0.427703 -0.2249505 0.8919659 0.3921657 -0.1143462 0.6974073 -0.7074943 -0.1389656 0.6866071 -0.7136241 -0.2663169 0.8946807 0.3586387 -0.2568532 0.8945264 0.3658536 -0.2402613 0.8967511 0.3716343 -0.03337895 0.4409663 0.8969027 -0.0126636 0.4379047 0.8989322 -0.01630973 0.3974782 0.9174667 1.36555e-4 0.3950075 0.9186779 0.01818472 0.5731891 0.8192214 0.03011673 0.6756603 0.7365977 -0.03523725 -0.008643388 0.9993416 -0.03524494 -0.00871998 0.9993407 0.06755906 0.4970599 -0.8650822 -0.172544 0.6166478 0.7680978 -0.1433736 0.6144762 0.7757984 -0.1495623 0.9207156 0.3604356 -0.1156243 0.5500046 0.8271191 -0.08822786 0.5466001 0.8327331 -0.08725345 0.5218696 0.848551 -0.05729603 0.5178847 0.8535295 -0.05742865 0.4931991 0.8680188 -0.02978724 0.4892463 0.8716368 0.001727461 0.2160732 0.9763756 0.006004095 0.2760552 0.9611231 -0.01351153 0.279111 0.9601638 -0.01349443 0.2909651 0.9566385 -0.02240163 0.2923546 0.9560475 -0.02151668 0.3227068 0.9462544 -0.03754311 0.3252846 0.9448705 -0.03720331 0.3650211 0.9302556 -0.05821585 0.3684809 0.9278107 -0.05985468 0.391219 0.9183492 -0.08212256 0.3948385 0.9150729 -0.08506709 0.4199946 0.903531 -0.1020882 0.4227606 0.9004729 -0.1075888 0.4447304 0.8891792 -0.1154409 0.4458888 0.8876129 -0.1267444 0.4824067 0.8667292 -0.1393245 0.4840409 0.8638826 -0.1566073 0.5296947 0.8336052 -0.173631 0.5314779 0.8290859 -0.1965137 0.5814686 0.7894787 -0.2190915 0.5830324 0.7823505 -0.262841 0.681568 0.6829201 -0.2689869 0.6815881 0.6805025 -0.3117557 0.7646936 0.5639611 -0.2951329 0.7657163 0.5714676 -0.3306612 0.829833 0.449489 -0.3294197 0.8299853 0.450119 -0.3515439 0.8525839 0.3866753 -0.2413488 0.86451 0.4408777 -0.2545941 0.8770822 0.4073189 -0.08562827 0.8764208 0.4738717 -0.1534893 0.9375151 0.3122603 0.01917928 0.8738226 0.4858665 0.04295742 0.5819875 0.8120623 0.08594262 0.5141741 0.8533691 0.04416364 0.5294512 0.84719 0.05662089 0.5185308 0.8531823 0.03936994 0.5085997 0.8601025 -0.03710353 0.3756486 0.9260191 -0.03128224 0.3733028 0.9271821 -0.06835919 0.3800591 0.9224327 -0.0263434 0.3470564 0.9374741 -0.05403739 0.3299165 0.9424623 -0.02198749 0.3237735 0.9458791 -0.05583012 0.3283667 0.9428989 -0.03698688 0.3134499 0.9488842 -0.06286513 0.3182701 0.9459134 -0.03569871 0.2952721 0.9547461 -0.03569781 0.2952719 0.9547461 0.1258444 0.4757183 0.870549 0.07176661 0.5956019 0.8000676 0.1157628 0.5798462 0.8064598 0.07403534 0.6379313 0.7665262 0.0721749 0.6385296 0.7662054 0.04430717 0.6709479 0.7401797 -0.01626896 0.686866 0.726602 -0.01922339 0.689722 0.7238191 -0.158129 0.7145764 0.6814514 -0.1243144 0.6880926 0.7148948 -0.2433053 0.7010205 0.6703527 -0.1868197 0.6598981 0.7277588 -0.2209846 0.6631911 0.7150829 -0.1499887 0.5784616 0.8018015 -0.1935374 0.5837599 0.7885224 -0.1150569 0.4922509 0.8628157 -0.1547197 0.4980129 0.8532555 -0.08413279 0.4124582 0.9070832 -0.1137685 0.4172948 0.9016218 -0.067941 0.3783778 0.9231545 -0.09437453 0.3829334 0.9189425 -0.05794918 0.3502389 0.9348661 -0.0835849 0.35484 0.9311832 -0.05586737 0.3286436 0.9428002 -0.08196318 0.3334629 0.9391936 -0.06256157 0.3141813 0.9472994 -0.07079428 0.3157601 0.9461944 -0.04931396 0.2773771 0.9594947 -0.03421586 0.2745223 0.9609718 0.1108866 0.6839891 0.7210154 0.11075 0.6843296 0.7207131 0.125507 0.6792201 0.7231237 0.08766734 0.728961 0.6789185 0.06470614 0.735657 0.6742565 0.04141539 0.7610019 0.6474263 -0.04487425 0.7795889 0.6246817 -0.04466831 0.7794046 0.6249266 -0.2112393 0.7973577 0.5653305 -0.1801313 0.7751849 0.6055088 -0.3086037 0.7773826 0.5481241 -0.258328 0.7433882 0.6169607 -0.2873727 0.7435243 0.6038116 -0.2206847 0.662297 0.7160034 -0.2627542 0.664331 0.6997318 -0.188501 0.5697703 0.7998932 -0.2155422 0.5722445 0.7912508 -0.1472823 0.4757404 0.8671671 -0.1594805 0.4773134 0.86414 -0.1178059 0.4323244 0.8939896 -0.1293078 0.4340243 0.891573 -0.09698158 0.3955149 0.913325 -0.1085774 0.3973881 0.9112046 -0.08537745 0.3671199 0.9262472 -0.09747403 0.3691937 0.9242266 -0.08330053 0.3490741 0.9333854 -0.08078432 0.3486173 0.9337772 -0.07097804 0.3226326 0.9438593 -0.05898648 0.320508 0.9454074 -0.05155211 0.2985092 0.9530134 -0.039011 0.2963092 0.954295 -0.03441172 0.2617173 0.964531 -0.02463507 0.260083 0.9652719 -0.02196758 0.2355806 0.9716066 -0.01702231 0.2347934 0.9718962 -0.01450634 0.2246825 0.974324 0.00282222 0.2219342 0.9750576 0.003668069 0.2157604 0.9764394 -0.01511693 -0.1049788 -0.9943595 -0.005286514 -0.1787887 -0.9838733 -0.05017513 -0.4019071 -0.9143047 -0.02684146 -0.1272469 -0.9915078 0.0324735 -8.66999e-4 -0.9994722 -0.01002687 -0.1003115 -0.9949056 -0.02612668 -0.1103003 -0.9935549 -0.009105443 -0.1061186 -0.9943118 -0.03189158 -0.1028053 -0.9941901 -0.01671469 -0.08943927 -0.9958521 -0.0819118 -0.508592 -0.8571025 -0.01229411 -0.1305489 -0.9913657 0.002647817 -0.1087519 -0.9940654 -0.01176619 -0.1123663 -0.9935972 -0.006045877 -0.1064914 -0.9942952 -0.01478272 -0.09815919 -0.9950609 -0.01905477 -0.1034952 -0.9944474 -0.01244693 -0.1007729 -0.9948316 -0.01143479 -0.09438419 -0.9954702 -0.027157 -0.1058672 -0.9940093 -0.02684551 -0.1272563 -0.9915065 0.02086985 -0.03729426 -0.9990864 -0.09918141 -0.3462207 -0.9328957 -0.07198107 -0.3233728 -0.94353 -0.1278915 -0.4768514 -0.8696302 -0.180674 -0.6443279 -0.7431005 0.04232364 0.003831088 -0.9990966 -0.01291662 -0.08204019 -0.9965454 -0.02100133 -0.0867573 -0.996008 -0.007523775 -0.1623207 -0.9867093 -8.75049e-4 -0.1508387 -0.988558 0.01977568 -0.06053149 -0.9979704 -0.04476803 -0.4026833 -0.9142439 -0.1196024 -0.7643703 -0.6335875 -0.009659767 -0.201183 -0.979506 -0.009649395 -0.201133 -0.9795164 -0.01672428 -0.2342773 -0.9720259 -0.02748084 -0.2851516 -0.9580883 0.0107693 -0.1025079 -0.9946739 -0.02595919 -0.2858368 -0.9579267 -0.02591025 -0.2855985 -0.9579991 -0.02359908 -0.2600986 -0.9652936 -0.02204883 -0.259964 -0.9653665 -0.01671719 -0.2342431 -0.9720343 -0.00528723 -0.1787921 -0.9838726 -0.005363523 -0.1791436 -0.9838083 -0.005474448 -0.1791394 -0.9838085 -0.04188895 -0.3454306 -0.9375088 -0.07949423 -0.5072428 -0.858129 0.02064353 -0.03800565 -0.9990643 -0.01163768 -0.1592683 -0.9871668 -0.001376569 -0.1579023 -0.9874537 -0.001918256 -0.1604734 -0.9870383 -0.002488553 -0.1604525 -0.9870405 -0.003125548 -0.1630345 -0.9866154 0.03819108 -0.008408725 -0.9992352 -0.0510419 -0.08270347 -0.9952662 -0.005407869 -0.05334872 -0.9985613 -0.0361697 -0.09404313 -0.9949108 -0.02070695 -0.0852642 -0.9961432 -0.03222328 -0.09704518 -0.9947583 -0.03439211 -0.09844821 -0.9945478 3.31883e-4 -0.1193615 -0.9928508 -0.009240806 -0.1217596 -0.9925166 -0.006768345 -0.1089684 -0.9940221 -0.02081161 -0.1147486 -0.9931765 -0.0069682 -0.07860243 -0.9968817 0.0279051 -0.02395558 -0.9993235 -0.02036297 -0.1547543 -0.9877431 -0.008438706 -0.1328735 -0.9910971 -0.03600436 -0.1269444 -0.9912562 -0.03600448 -0.1269444 -0.9912561 -0.1124479 -0.5824547 -0.8050479 -0.001347005 -0.1388716 -0.9903094 6.13926e-4 -0.138608 -0.9903472 0.002535045 -0.1285635 -0.991698 -0.008266389 -0.1505655 -0.9885655 -0.008531808 -0.1527908 -0.9882218 -0.007523775 -0.1623208 -0.9867093 0.02606695 0.1654223 0.9858782 0.137338 0.7479302 0.6494141 0.2389397 -0.6353443 0.7343333 0.03906983 0.1185597 0.992178 0.0371747 0.1294481 0.9908891 0.01283138 0.03375405 0.9993477 0.03142994 0.1277039 0.9913142 0.3919788 0.7812483 0.485802 0.2689847 0.8845757 0.3810158 0.1713337 -0.5401923 0.8239156 0.1715319 -0.5414012 0.8230805 0.1714293 -0.5407762 0.8235126 0.008293867 0.1281892 0.991715 0.008312106 0.1282748 0.9917039 0.1809879 0.9108878 0.3708461 -0.02087998 0.0372678 0.9990871 0.304243 0.7244952 0.6185006 0.1116159 0.285081 0.9519826 0.07847249 0.2169924 0.9730141 0.2253768 0.5985932 0.7686947 0.02014392 0.1543857 0.9878053 0.02420532 0.1553893 0.9875567 0.03860998 0.2044484 0.9781156 0.03697538 0.2005733 0.9789807 0.2436903 0.8006139 0.5473869 0.1920456 0.6767207 0.7107514 0.08608311 0.1181181 0.9892613 0.08246386 0.1205905 0.9892713 0.02044814 0.09664016 0.9951093 0.0566312 0.1523866 0.9866971 0.04757189 0.1178306 0.9918936 0.2389421 -0.6353444 0.7343326 0.1696067 -0.2573275 0.9513233 0.1102927 -0.0196731 0.9937044 0.111353 -0.02465778 0.993475 0.08777654 0.06413972 0.994073 0.1667194 -0.1631214 0.9724175 0.1247733 -0.02211064 0.9919389 0.2773767 -0.4947493 0.8235808 0.2773414 -0.4947555 0.8235889 0.08812677 0.05856412 0.9943863 0.09018737 0.05894345 0.994179 0.09095156 0.05396264 0.9943922 0.08565396 0.05265229 0.9949328 0.08653247 0.04975783 0.9950057 0.05828583 0.09166735 0.9940824 0.279539 -0.2867047 0.9163287 0.2791922 -0.2867251 0.9164282 0.1626394 -0.1003501 0.9815693 0.1459813 -0.05391609 0.9878171 0.1695098 -0.1625503 0.9720308 0.07032859 0.1069763 0.9917711 0.07670485 0.1019667 0.9918262 0.07008039 0.1007589 0.9924396 0.07612639 0.09642487 0.9924248 0.06193172 0.09293872 0.9937438 0.06623703 0.09029388 0.9937101 0.05756562 0.08751821 0.9944983 0.1031371 0.09903663 0.9897245 0.06359255 0.1356916 0.9887081 0.07659858 0.1209787 0.9896953 0.08998882 0.1252511 0.9880356 0.1208713 0.1148691 0.9859996 0.1247856 0.1152603 0.9854661 0.7394894 -0.6556726 0.1524757 0.9326366 -0.360628 0.01167553 0.4216971 -0.2753003 0.8639337 0.140679 0.07390028 0.9872933 0.09115934 0.09984147 0.9908187 0.09001791 0.09984695 0.9909225 0.06549298 0.1153606 0.9911623 0.0590865 0.1136447 0.9917629 0.04977035 0.1287046 0.9904333 0.03670656 0.1249554 0.9914831 0.9329603 -0.3598125 0.01095533 0.4512249 -0.03865724 0.8915726 0.2788701 -0.1315288 0.9512789 0.3375982 -0.1862471 0.9226806 0.02464973 0.1540846 0.9877502 0.02953261 0.1497461 0.9882833 0.04566997 0.1562977 0.9866535 0.04423356 0.1704739 0.9843688 0.05480462 0.1513359 0.9869619 0.04970663 0.1253514 0.9908665 0.07671529 0.1346626 0.9879174 0.08849185 0.124436 0.9882737 0.1107569 0.1323322 0.984998 0.1463364 0.1269901 0.98105 0.1362006 0.1025104 0.9853633 0.1583418 0.1080026 0.9814597 0.08833664 0.05709493 0.994453 0.5425376 0.1031288 0.8336771 0.3281381 0.1397787 0.9342309 0.3282244 0.139773 0.9342015 0.2541254 0.1243604 0.9591427 0.2395023 0.1134294 0.9642471 0.1822216 0.1323227 0.974313 0.1257255 0.1281387 0.9837549 -0.2653799 0.03694981 0.9634357 0.5230605 0.1636738 0.8364321 0.4138423 0.1489818 0.8980752 0.6953345 0.1799121 0.6958028 0.3101219 0.01897132 0.9505075 0.303028 0.01704168 0.9528293 0.2471009 0.08421778 0.965323 0.3446699 0.08560049 0.934813 0.418697 0.1128327 0.9010891 0.05825769 0.09164428 0.9940862 0.0586732 0.09089857 0.9941302 0.1044284 0.04660421 0.9934398 0.594802 -0.6992968 0.3964774 0.08721262 0.04997676 0.9949353 0.08740532 0.04962205 0.9949362 0.05945706 0.08660817 0.9944667 0.09062993 -0.1012052 0.9907289 0.1714718 -0.5410384 0.8233316 0.1714569 -0.5409468 0.823395 0.07085728 -0.01347982 0.9973953 0.05966204 0.04477059 0.9972141 0.05966269 0.04476761 0.9972143 0.08883464 -0.1010071 0.9909117 0.04006946 0.1289635 0.9908396 0.04006916 0.1289651 0.9908393 0.05355572 0.07328623 0.9958719 0.05243211 0.07955378 0.9954508 0.05878585 0.04492157 0.9972593 0.204388 -0.764908 0.6108528 0.2011746 -0.7647095 0.6121668 0.09066396 -0.1013751 0.9907084 0.05129283 0.1045336 0.9931977 0.05159771 0.1180338 0.9916681 0.06497901 0.06118613 0.9960091 0.06286317 0.07290273 0.9953559 0.08570086 -0.02297514 0.996056 0.08369642 -0.01394426 0.9963937 0.04399406 0.1488917 0.9878744 0.09062433 -0.04805356 0.9947252 0.04421442 0.1078567 0.9931827 0.03801268 0.1079539 0.993429 0.0532518 0.1128277 0.9921866 0.04044038 0.1138113 0.992679 0.06434053 0.1196807 0.9907253 0.04562371 0.1220806 0.991471 0.06604951 0.1258107 0.9898531 0.04547387 0.129348 0.9905561 0.04627209 0.1294509 0.9905056 0.03137779 0.1441775 0.9890542 0.03710579 0.1439411 0.9888904 0.0265311 0.1562845 0.9873557 0.177003 0.9810315 0.07903766 -0.0109359 0.101733 0.9947517 0.1488083 0.8352794 0.5293058 0.1487922 0.8352147 0.5294123 0.003137648 0.1667699 0.9859908 0.1540318 0.8340891 0.5296882 0.09931498 0.6057632 0.7894222 0.09928381 0.605626 0.7895316 0.1322019 0.7481916 0.6501784 0.05281007 0.4045686 0.9129816 0.05279433 0.4044965 0.9130144 0.052796 0.4045043 0.9130108 0.01400083 0.2141144 0.9767082 0.03364884 0.3149492 0.948512 0.01003569 0.2147321 0.9766215 0.01436293 0.2327718 0.9724254 0.01172393 0.2144633 0.9766617 0.01172161 0.214452 0.9766641 0.01959502 0.2325672 0.9723829 0.01429319 0.2142587 0.9766724 0.0358572 0.3148511 0.9484636 0.03244841 0.3006284 0.9531891 0.1562337 0.8268196 0.5403337 0.1809869 0.9108877 0.370847 0.2196333 0.8746515 0.4321412 0.04228705 0.3018041 0.9524316 0.01708608 0.199217 0.9798064 0.02309495 0.2153999 0.9762528 0.01299113 0.1696173 0.9854243 0.007282018 0.1688597 0.9856132 0.01711785 0.1887495 0.981876 0.005291879 0.1891977 0.9819248 0.01932984 0.213222 0.9768126 0.01932996 0.2132223 0.9768124 0.01437985 0.1797313 0.9836106 0.01437997 0.179732 0.9836105 0.9065937 0.3586048 0.2224645 0.9067527 0.3607462 0.2183157 0.4825158 0.207083 0.8510553 0.6638891 0.2735415 0.6960073 0.4186856 0.1128376 0.9010938 0.5081868 0.09435093 0.8560631 0.1549227 0.128489 0.9795354 0.1544601 0.1282225 0.9796433 0.1294803 0.1282901 0.9832479 0.06419873 0.08615964 0.9942108 0.04531341 0.09662634 0.9942887 3.82549e-4 0.03776699 0.9992865 0.6762845 -0.1605666 0.718928 0.2686622 0.03999823 0.9624036 0.179656 -0.002491116 0.9837264 0.1068872 0.0583074 0.99256 0.107607 0.05793255 0.9925042 0.06945705 0.09041273 0.9934793 0.06888723 0.09046953 0.9935139 0.04982244 0.1093951 0.9927489 0.04586356 0.1085315 0.9930344 0.03830176 0.1259602 0.9912956 0.03342682 0.1239677 0.991723 0.0254296 0.1238556 0.9919744 0.03787106 0.127839 0.9910717 0.02094537 0.1285253 0.9914849 0.04420983 0.1342697 0.9899582 0.01781255 0.1366197 0.9904634 0.04401546 0.148229 0.9879731 0.01176351 0.1440193 0.989505 0.03012615 0.1630948 0.9861504 0.02430152 0.163331 0.986272 0.02666139 0.1687037 0.9853062 0.2346409 0.968361 0.08497363 -0.4023805 -0.791728 0.4596267 -0.3941177 -0.5882837 0.7061116 -0.3796245 -0.8882293 0.2587165 -0.3887066 -0.8461805 0.364535 -0.3733141 -0.892573 0.2528833 -0.3995153 -0.6343141 0.6618409 -0.1488285 0.07652324 0.9858977 -0.2031183 0.01724368 0.9790024 -0.1766064 0.114754 0.9775694 -0.2381089 -0.03014159 0.9707706 -0.3240351 -0.2627585 0.908823 -0.33212 -0.3004238 0.8941151 -0.3221043 -0.269153 0.9076373 -0.397871 -0.6375194 0.6597482 -0.1166329 0.1859831 0.975606 -0.09657567 0.1945853 0.9761197 -0.08352285 0.2480475 0.9651406 -0.021811 0.2889178 0.9571054 -0.02628505 0.2874725 0.9574282 -0.08351838 0.2480646 0.9651365 0.05764192 0.3570039 0.9323228 -1.03867e-4 0.3243514 0.9459366 -0.02239716 0.2864304 0.9578392 0.1220993 0.4452584 0.8870382 0.05699211 0.3504629 0.934841 0.05699259 0.3504654 0.93484 0.1654155 0.3952335 0.9035642 0.1654155 0.3952332 0.9035643 0.2349171 0.5170237 0.8231041 0.2596908 0.4796952 0.8381249 0.2761961 0.6333483 0.7229009 0.2873992 0.7660158 0.574997 0.3054105 0.6497533 0.6960928 0.2746267 0.9583619 -0.07824748 0.2413213 0.9482842 -0.2062069 0.2499625 0.886536 0.3893233 0.3123639 0.8497217 0.4247374 0.3078702 0.9172353 0.2527757 0.302091 0.9316317 0.2019988 0.2922233 0.9484422 0.1227315 0.5728276 0.8182022 0.04912841 -0.04226988 0.3562566 0.9334316 -0.003012239 0.3928495 0.9195979 -0.1831368 0.01156109 0.9830195 -0.2655633 -0.2659368 0.9266897 -0.2760989 -0.4024786 0.8728003 -0.2760957 -0.4024545 0.8728124 -0.1831426 0.01154196 0.9830186 -0.1831412 0.01154774 0.9830188 -0.18716 0.07439887 0.9795081 -0.07422399 0.2945445 0.9527509 -0.07422453 0.2945424 0.9527516 -0.07078909 0.2473118 0.9663466 -0.04181957 0.2832001 0.9581486 -0.04181975 0.283199 0.958149 -0.3225728 -0.7380561 0.5926381 -0.3031775 -0.5737257 0.7608693 -0.3092503 -0.7421526 0.5946207 -0.2875866 -0.919662 0.2674242 -0.3283769 -0.7361629 0.5918048 0.2144508 0.3684534 0.9045734 0.1279742 0.4055353 0.9050766 0.1537617 0.5514873 0.8198898 0.1963762 0.5971245 0.7777395 0.2193915 0.7933319 0.5678837 0.2325283 0.831437 0.5046219 0.2307745 0.9424431 0.2419587 0.2308257 0.959018 0.1643285 0.2383292 0.8907513 0.3869903 0.2346431 0.9683604 0.08497405 0.09112966 0.9724771 -0.214438 0.1258416 0.9755634 0.1801112 0.1002898 0.9919064 0.07786947 0.06258833 0.9740612 -0.2174566 0.06258565 0.9740579 -0.2174726 0.1223279 0.9691154 0.2141285 0.1223263 0.9691192 0.214113 0.122325 0.9691219 0.2141016 0.1536675 0.6683067 0.7278409 0.1320888 0.8931074 0.4300135 0.1303567 0.8813166 0.4541895 0.1291102 0.916426 0.3788061 0.1536643 0.6684067 0.7277499 0.1519417 0.6636212 0.7324756 0.1501785 0.6697311 0.7272597 0.01374691 0.4232637 0.9059022 0.02718418 0.5128696 0.8580361 0.07549244 0.4083265 0.909709 0.09795397 0.4868187 0.8679934 0.099981 0.5093808 0.8547134 0.07967805 0.4938383 0.8658956 0.1501785 0.6697324 0.7272586 -0.3240205 -0.8189211 0.4736864 -0.3138723 -0.9122256 0.2633031 -0.3367925 -0.6094269 0.7177533 -0.3299422 -0.5648976 0.7563259 -0.2958611 -0.3137002 0.9022518 -0.2773341 -0.261844 0.9244045 -0.2155364 0.02157217 0.9762576 -0.1724516 0.06931567 0.9825761 -0.1375935 0.2087075 0.9682506 -0.0815069 0.2510657 0.9645324 -0.06860148 0.3054217 0.9497428 -0.01121312 0.3452126 0.9384576 -0.004072427 0.3799098 0.9250146 0.05076807 0.4178697 0.9070873 0.05944919 0.4697583 0.8807911 0.1083254 0.5060827 0.8556553 0.1230856 0.6267952 0.7694009 0.1562029 0.6619526 0.7330889 0.1669571 0.8539769 0.492797 0.1757314 0.8808873 0.4394952 0.1653518 0.9744891 0.1517555 0.1645275 0.9821915 0.09072285 0.121535 0.9414165 -0.3145857 0.1409934 0.9733697 0.1807548 -0.07873541 0.3276502 -0.9415127 -0.2856124 -0.9465803 0.1497043 -0.01254504 -0.4957121 -0.8683964 -0.03122097 -0.05154973 -0.9981823 0.1367595 0.8418587 -0.5220831 0.03672027 0.5872229 -0.808592 0.1760293 0.8810843 -0.4389809 0.1960608 0.9073829 -0.3717746 0.1808767 0.8816788 -0.435805 0.250164 0.9507568 -0.1829741 0.05585592 0.5988258 -0.798929 0.05585217 0.5988169 -0.7989361 -0.01996707 0.4763638 -0.8790215 0.089284 0.7290617 -0.6785997 -0.0312215 -0.05154949 -0.9981823 -0.1004721 0.06154882 -0.9930343 -0.07208067 0.1549034 -0.9852966 -0.007409572 0.09859526 -0.9951 -0.0668354 0.2566605 -0.964188 -0.04954415 -0.1417645 -0.9886598 -0.03262323 -0.2990335 -0.9536848 -0.01787841 -0.2446265 -0.9694526 -0.02653044 -0.2711251 -0.9621784 -0.04520446 -0.2364373 -0.9705947 -0.05499964 -0.1604266 -0.9855142 -0.005863845 -0.3692452 -0.9293134 -0.0171017 -0.4850511 -0.8743186 0.01909661 -0.4541732 -0.8907088 0.01978355 -0.4534884 -0.8910426 0.01810705 -0.4529497 -0.8913521 -0.01254749 -0.4957169 -0.8683935 -0.06012207 -0.6516028 -0.756174 -0.06011843 -0.6515973 -0.756179 -0.1919419 -0.8549084 -0.4819647 -0.4052518 -0.6621164 0.6303752 -0.3652127 -0.9292403 0.05596572 -0.1919564 -0.8549226 -0.4819337 -0.2792619 -0.9273796 -0.2489575 -0.2838216 -0.929148 -0.2369162 -0.3194757 -0.9387655 -0.1290531 -0.08670026 -0.9934356 -0.07462453 -0.08794748 0.4108607 -0.9074463 -0.05158448 0.6432945 -0.7638792 -0.01602303 0.7671561 -0.6412603 -0.0879476 0.41086 -0.9074465 -0.08794063 0.4108852 -0.9074358 -0.1009183 0.3666424 -0.9248724 -0.1031743 -0.04645085 -0.9935781 -0.1093344 0.02852362 -0.9935957 -0.1371999 -0.0337994 -0.9899666 -0.1372014 -0.03381347 -0.9899659 -0.1008458 -0.2744076 -0.9563109 -0.1263348 -0.1730533 -0.9767764 -0.1636036 -0.248447 -0.9547292 -0.1031745 -0.04645299 -0.993578 -0.01602011 0.767167 -0.6412474 -0.1004807 0.3275836 -0.939464 0.01201099 0.7655698 -0.6432407 0.1367586 0.8418588 -0.5220831 0.125942 0.8034744 -0.5818656 0.09832215 0.7275882 -0.6789317 0.08378732 0.6718058 -0.7359733 0.02040952 0.4675775 -0.8837165 0.01135158 0.3968372 -0.9178187 -0.05632424 0.1498748 -0.9870994 -0.04198265 0.06629312 -0.9969167 -0.07276242 -0.04661041 -0.9962596 -0.04137939 -0.1615313 -0.9859997 -0.2442545 -0.938517 -0.2439782 -0.2622734 -0.9498657 -0.170199 -0.3809777 -0.6729198 0.6340624 -0.3579054 -0.9236276 0.1371703 -0.1005671 -0.8086743 -0.5795965 -0.1493492 -0.8165984 -0.5575498 -0.138635 -0.8197365 -0.5557087 -0.1549782 -0.8576129 -0.4903897 -0.1386002 -0.8623455 -0.4869806 -0.1087352 -0.8062929 -0.5814365 -0.2008294 -0.9454126 -0.2566368 -0.2008349 -0.9454172 -0.2566158 -0.2266414 -0.9601445 -0.1635731 -0.2892991 -0.942192 0.1690571 -0.2878263 -0.9442394 0.1598992 -0.2888372 -0.9422984 0.1692535 -0.2888248 -0.9423208 0.1691499 -0.05524873 -0.5288344 -0.8469249 -0.05524951 -0.5288357 -0.846924 -0.02447515 -0.4824615 -0.8755753 -0.0547589 -0.6513468 -0.7568017 -0.0547589 -0.6513468 -0.7568018 -0.001100718 -0.6037074 -0.7972052 -0.04346871 -0.5908263 -0.8056269 -0.03628641 -0.6564967 -0.7534556 -0.05438572 -0.6507817 -0.7573146 -0.1005688 -0.8086774 -0.579592 0.1212359 0.8041365 -0.5819503 0.1154136 0.912236 -0.3930716 0.04468882 0.6773002 -0.7343483 0.03709417 0.6337738 -0.7726284 -0.01548349 0.4028667 -0.9151276 -0.01832699 0.348312 -0.9371995 -0.07258284 0.0764752 -0.9944262 -0.05634045 0.01005864 -0.9983609 -0.0845074 -0.1285475 -0.9880961 -0.05671274 -0.2004125 -0.9780688 -0.06942164 -0.2547072 -0.9645231 -0.0397824 -0.326256 -0.944444 -0.005863904 -0.3692454 -0.9293134 -0.00996989 -0.3748438 -0.9270343 -0.0078336 -0.37562 -0.9267407 -0.0762183 -0.4549608 -0.8872438 -0.1486809 -0.4928498 -0.8573173 -0.1486827 -0.4928513 -0.8573162 -0.1008459 -0.2744081 -0.9563108 -0.1291337 -0.3431237 -0.9303712 -0.09422349 -0.3048866 -0.9477162 -0.08469462 -0.3970002 -0.9139025 -0.09335923 -0.4368674 -0.8946681 0.005589842 -0.2170767 -0.9761386 0.0348584 -0.2904797 -0.956246 0.07193368 -0.3414698 -0.9371361 0.1397867 -0.3639894 -0.9208536 0.08423733 -0.3402264 -0.936563 0.08425158 -0.3402289 -0.9365608 0.07193297 -0.338024 -0.9383844 0.08475756 -0.3283256 -0.9407542 0.1395104 -0.3581938 -0.9231653 0.1175037 -0.3584037 -0.9261423 0.1175034 -0.3584036 -0.9261424 0.1761105 -0.4768464 -0.8611636 0.1408562 -0.521591 -0.8414882 0.1802572 -0.5276584 -0.8301109 0.1413158 -0.5345728 -0.8332237 0.1255624 -0.5272002 -0.840413 0.1409525 -0.5242501 -0.839818 0.0792101 -0.5142256 -0.8539894 -0.006802797 -0.5110167 -0.8595439 -0.03417718 -0.535342 -0.8439436 0.07928311 -0.5662572 -0.8204067 -0.0757727 -0.4782181 -0.8749662 -0.1447041 -0.4802821 -0.8650953 -0.07968527 -0.5212628 -0.8496678 -0.03412067 -0.5054984 -0.8621526 -0.07700252 -0.491672 -0.8673692 -0.006803333 -0.5110168 -0.8595439 0.07928866 -0.5662581 -0.8204054 -0.03387677 -0.6620255 -0.7487153 0.1252063 -0.5231419 -0.8429982 0.1168316 -0.3957942 -0.9108772 0.1343357 -0.3968055 -0.9080195 0.1413111 -0.3979093 -0.9064764 0.13439 -0.3995664 -0.9067998 0.1741389 -0.4545167 -0.8735504 0.1351409 -0.4483662 -0.883575 0.1351445 -0.4483683 -0.8835733 -0.001215815 -0.1791184 -0.9838268 -0.001215934 -0.1791189 -0.9838268 -0.001089036 -0.1784338 -0.9839514 -0.005733311 -0.1899054 -0.9817857 -0.005733549 -0.1899057 -0.9817856 0.01285403 -0.2183407 -0.9757879 0.005616009 -0.2272831 -0.9738126 0.01778501 -0.2349205 -0.9718518 -0.005733311 -0.1899056 -0.9817856 0.006452798 -0.191284 -0.9815136 0.01292788 -0.1971881 -0.9802804 0.006594896 -0.1968733 -0.9804067 0.01292544 -0.1979014 -0.9801367 0.007056057 -0.2151216 -0.9765618 0.005589783 -0.2170767 -0.9761385 -0.1092953 -0.3871743 -0.9155057 -0.1092965 -0.3871745 -0.9155054 -0.09669351 -0.3563736 -0.9293268 -0.1401771 -0.4145247 -0.8991772 -0.1184204 -0.4514666 -0.884395 -0.0757718 -0.4782184 -0.8749662 0.004607498 -0.2465388 -0.969122 0.004607737 -0.2465388 -0.9691221 0.01765596 -0.2490307 -0.9683346 0.01765596 -0.2490307 -0.9683346 0.004171967 -0.2833017 -0.9590218 0.07182586 -0.2914498 -0.9538857 0.03485804 -0.2904797 -0.956246 0.03485929 -0.2904798 -0.956246 -0.0026986 0.3927378 0.9196465 -7.48222e-4 0.1731834 0.9848893 -0.02533209 0.4121428 0.910767 -0.09848552 0.5089044 0.8551708 -0.0650379 0.5151716 0.8546158 -0.06503772 0.5151717 0.8546158 -0.1087673 0.560168 0.8212074 -0.1087674 0.560168 0.8212074 -0.07111144 0.5686613 0.8194922 -0.01210272 0.5241762 0.8515238 0.008246779 0.5196406 0.8543453 0.008244037 0.5196414 0.8543447 -0.01434296 0.3054834 0.9520894 -0.01879072 0.3066001 0.951653 -0.0143612 0.3057361 0.952008 -0.01935034 0.3096076 0.9506675 -1.6938e-4 0.3260775 0.9453431 -0.02326297 0.3306028 0.9434832 -0.001168549 0.3318906 0.9433172 -0.03758728 0.3775944 0.9252079 -0.01864361 0.3730949 0.9276058 -0.04684394 0.4146197 0.9087883 -0.04684364 0.4146196 0.9087884 0.001461863 0.1748825 0.9845882 0.001461982 0.1748825 0.9845883 -0.001816093 0.1699765 0.9854464 -0.02066725 0.2480809 0.9685189 -0.01395827 0.2458709 0.9692021 -0.006441652 0.2376639 0.9713261 -0.01411885 0.2391335 0.970884 -6.32997e-4 0.1786349 0.9839152 -6.33637e-4 0.178635 0.9839152 0.001433491 0.1784972 0.9839394 -0.01492583 0.2046561 0.97872 -0.006762146 0.2151746 0.9765523 -0.006762146 0.2151746 0.9765522 0.03223598 0.4165576 0.9085376 0.02203953 0.4477089 0.8939076 0.04554975 0.4527804 0.8904579 0.004830479 0.4667952 0.8843522 0.04509514 0.4806041 0.8757774 0.008256077 0.5177999 0.8554618 0.04463148 0.5060795 0.8613313 0.008022785 0.5516348 0.8340472 -0.01529622 0.5506608 0.834589 -0.01529657 0.5506609 0.834589 -0.03424435 0.2598596 0.965039 -0.03424429 0.2598596 0.965039 -0.02051752 0.2729218 0.9618175 -0.03457075 0.2794324 0.9595428 -0.02049523 0.2764781 0.9608017 -0.0346955 0.2811713 0.9590302 -0.03469526 0.2811713 0.9590302 -0.2425396 -0.9540025 0.1762206 0.02387332 0.1192612 0.9925759 -0.09185737 -0.7052872 0.7029453 -0.1035744 -0.9684629 -0.2266096 -0.02207511 -0.3793386 0.9249946 -0.07586491 -0.8702627 0.4867107 0.0166471 0.1005042 0.9947974 0.1343311 -0.5400339 0.8308541 0.1344003 -0.5405583 0.8305019 0.01800137 -0.4247205 -0.9051455 0.01800215 -0.4247264 -0.9051427 0.01709342 0.2240132 0.9744363 0.06288534 -0.09717464 0.9932787 0.1193856 -0.539654 0.833379 0.1193922 -0.5397129 0.8333399 0.06286579 -0.09703725 0.9932934 0.07568514 -0.1353176 0.9879073 0.1335299 -0.5404993 0.8306806 -0.009181261 0.3615323 0.9323143 0.08472204 -0.9725915 0.2165359 0.06991404 -0.4592365 0.8855585 0.03400546 -0.04937106 0.9982014 0.05637001 -0.05282658 0.9970113 0.1157367 -0.5389825 0.8343278 0.1453672 -0.9875741 0.0597139 0.1290895 -0.9894645 0.06554448 0.02299869 0.02402591 0.9994468 0.02737087 -0.2882179 0.9571737 0.0166049 -0.9398165 0.3412756 0.009428203 -0.3650145 0.9309541 -0.02560359 -0.9356865 0.3519023 0.0141136 -0.2190746 0.975606 0.01950943 -0.086573 0.9960544 0.02515226 -0.01213204 0.9996101 -0.006726741 -0.7477499 -0.6639465 0.02296763 0.01127254 0.9996726 0.0207355 -0.05784529 0.9981102 0.0260089 -0.05885553 0.9979276 0.02601712 -0.05931746 0.9979001 0.02400875 -0.05896908 0.9979711 0.01445633 0.1264498 0.9918677 0.03314131 -0.2375478 0.9708103 0.04207402 -0.5476186 0.8356696 -0.002913832 -0.7475903 -0.6641538 -0.005300343 -0.2752268 0.9613647 -0.009915351 -0.2746489 0.9614934 0.01478582 -0.005214631 0.9998772 -0.02380377 -0.4195964 0.9073987 -9.82145e-4 -0.1492921 0.9887927 -0.01130026 -0.2861791 0.9581096 -0.01881021 -0.3733901 0.9274836 -0.01583987 -0.3737075 0.9274114 -0.03392326 -0.5867474 0.8090592 -0.03612524 -0.5866481 0.8090359 -0.08725488 -0.9782048 0.1884201 -0.08403509 -0.9435409 0.3204191 -0.07628005 -0.9437696 0.3216835 -0.06557983 -0.839232 0.5398046 -0.06333583 -0.839283 0.5399933 -0.04508537 -0.645236 0.7626519 -0.04178565 -0.5853846 0.8096782 -0.02521616 -0.4216948 0.9063871 -0.01001948 -0.2443234 0.9696421 -0.06569254 -0.8703773 0.4879835 -0.05074435 -0.7147923 0.6974933 -0.04845207 -0.7148571 0.6975899 -0.02903908 -0.4971253 0.8671926 -0.03170067 -0.4969043 0.8672261 -0.04547572 -0.645213 0.7626482 -0.02619874 -0.4193265 0.9074574 -0.05089277 -0.6851775 0.726596 -0.04284572 -0.5852942 0.8096882 0.01585686 0.01280969 0.9997922 0.004137516 -0.1501956 0.9886477 0.008657276 -0.08432328 0.9964008 -0.003848195 -0.2453227 0.9694339 -0.001645147 -0.216073 0.9763759 -0.01471924 -0.3803681 0.924718 -0.01322847 -0.3612461 0.9323767 -0.07848149 -0.9314581 0.3552838 -0.08498877 -0.9884485 0.125486 -0.07365465 -0.9067636 0.4151565 -0.07545477 -0.9066709 0.4150356 -0.0553652 -0.74254 0.6675096 -0.07982003 -0.9705548 0.227271 -0.06781458 -0.8552345 0.5137851 -0.05829912 -0.6548977 -0.7534655 -0.05768334 -0.8773922 0.4762935 -0.05562508 -0.8559766 0.5140135 -0.05985742 -0.8986184 0.4346288 -0.0454151 -0.7432953 0.6674201 -0.08548378 -0.984574 0.1526643 -0.08831071 -0.9958844 0.02038264 -0.08803141 -0.9959083 0.02042251 -0.08810275 -0.9751666 -0.2031947 -0.08980679 -0.9955807 0.02745503 -0.06340694 -0.7199379 -0.691136 -0.09046334 -0.9921864 -0.08592087 -0.0903415 -0.9957189 -0.01955127 -0.0870915 -0.9686955 -0.232474 -0.08807009 -0.9758221 -0.2000373 -0.08807015 -0.975822 -0.2000375 -0.08875477 -0.9795824 -0.1803907 -0.08942514 -0.9805679 -0.1746129 -0.1039 -0.9905603 -0.08941513 -0.08841019 -0.9716724 -0.2191719 -0.08809715 -0.971719 -0.2190911 -0.08955454 -0.9821062 -0.1656734 -0.1342496 -0.9511207 -0.2781125 -0.1342509 -0.9511203 -0.2781127 -0.1525933 -0.9805466 -0.1234651 -0.1876757 -0.9811257 0.0465855 -0.1876807 -0.9811238 0.04660415 -0.1035794 -0.9684621 -0.2266109 -0.1035755 -0.9684643 -0.2266033 -0.114456 -0.989627 -0.08682286 -0.137921 -0.9891099 0.05137395 -0.08806985 -0.9758221 -0.2000372 -0.08780717 -0.9928395 0.08099132 -0.08845937 -0.9908298 -0.1021338 -0.08982461 -0.9906852 -0.1023449 -0.08982264 -0.9910278 -0.09897387 -0.08922463 -0.9821481 -0.1656026 -0.08658993 -0.988343 0.1252209 -0.08798193 -0.9959398 -0.01905721 -0.0870918 -0.9686954 -0.2324741 -0.08709156 -0.968698 -0.2324636 -0.07368278 -0.8318041 -0.550157 -0.08869373 -0.9629739 -0.2545872 -0.08881717 -0.9588921 -0.2695133 -0.08257752 -0.8799341 -0.467864 -0.08257645 -0.8799339 -0.4678647 -0.1660264 -0.9539558 -0.2498068 -0.2158048 -0.9759925 -0.02944648 -0.1660188 -0.98592 -0.01998519 -0.1802073 -0.9812863 0.06784319 -0.1304979 -0.988114 0.08124673 -0.1341949 -0.9843106 0.1145614 -0.1024758 -0.9868919 0.1246714 0.01679837 -0.1250476 0.9920085 0.01575714 -0.1248677 0.9920482 0.01001936 -0.1965172 0.9804492 -0.08859223 -0.6514023 0.7535427 -0.0556432 -0.6516222 0.7565 -4.96941e-4 -0.1408705 0.9900279 -0.01332825 -0.3410751 0.9399416 -0.005747377 -0.3416603 0.9398059 0.03359496 0.5093635 0.8598954 0.03359502 0.5093635 0.8598954 0.01430672 -0.1601626 0.986987 0.01430648 -0.1601625 0.9869869 -0.02104067 -0.3829828 0.9235159 -0.02581083 -0.4980046 0.8667901 -0.07513064 -0.4966607 0.8646869 -0.09281724 -0.776269 0.6235314 -0.1054207 -0.05097949 0.9931201 -0.1200028 -0.1804839 0.9762299 -0.2419986 -0.9541223 0.176316 -0.1958939 -0.946375 0.2569046 -0.2177259 -0.2912127 0.9315527 -0.2177257 -0.2912128 0.9315528 -0.1054217 -0.05097961 0.99312 -0.121723 -0.1803994 0.9760326 -0.1524132 -0.7058048 0.6918162 -0.1528669 -0.8235401 0.5462723 -0.1003949 -0.8234267 0.5584708 -0.09965866 -0.8055722 0.5840563 -0.06909286 -0.8055438 0.5884941 -0.0618236 -0.6829515 0.7278428 -0.0447973 -0.6830176 0.729027 -0.03248983 -0.5121191 0.8582998 -0.02124029 -0.5125628 0.858387 0.04328101 0.08108043 0.9957674 0.06215691 -0.09699171 0.9933424 0.04168319 0.04773879 0.9979898 0.04536038 0.02289897 0.9987082 0.04788064 0.04671901 0.9977599 0.04788082 0.04672372 0.9977596 0.02387362 0.1192612 0.9925758 0.02449256 0.05108791 0.9983938 0.0341584 -0.05076205 0.9981265 0.0234512 -0.04906666 0.9985201 0.05257636 -0.9725333 0.2267482 0.03615349 -0.2894808 0.9565008 0.0478999 -0.584466 0.8100032 0.02482342 -0.582617 0.8123676 0.02487641 -0.0331164 0.9991419 -0.1755074 -0.9517561 -0.2517094 -0.175515 -0.9517669 -0.2516632 -0.1885547 -0.9667574 -0.1727054 -0.2056807 -0.9728021 -0.1065436 -0.1342532 -0.9511206 -0.2781113 -0.06110316 -0.7005128 -0.7110193 -0.07822346 -0.9955658 -0.05224722 0.4807446 -0.8528701 0.2037087 -0.07498377 -0.9832862 0.1659082 -0.00419116 -0.5065867 0.8621789 -0.07004088 -0.8674891 0.4925007 -0.06256544 -0.7780253 0.6251097 -0.05969685 -0.7781891 0.6251863 -0.05115956 -0.673206 0.7376831 -0.04790163 -0.6734659 0.7376646 -0.03970479 -0.5690418 0.8213495 -0.03044372 -0.5700221 0.8210651 -0.02633047 -0.5196493 0.8539739 0.001897513 -0.5234636 0.8520458 -0.02187323 -0.9070311 0.4204952 0.02621483 0.07867115 0.9965558 0.004749 -0.3613981 0.9323996 0.02646654 0.1030977 0.9943191 -0.2420103 -0.9541032 0.1764034 -0.2452817 -0.9485428 0.2002587 -0.1911789 -0.9590141 0.209147 -0.205801 -0.918864 0.3366528 -0.1488209 -0.9248072 0.3501197 -0.1503584 -0.9144604 0.3757054 -0.1048182 -0.9155269 0.3883602 -0.1047247 -0.900737 0.4215514 -0.0805146 -0.9010528 0.4261706 -0.08444601 -0.9733628 0.2131515 -0.04711532 -0.6672732 0.7433215 -0.04025715 -0.6673673 0.74364 -0.008040189 -0.3258152 0.9453994 -0.004519641 -0.3261557 0.9453052 0.01723057 -0.06454044 0.9977663 0.01343172 -0.06391143 0.9978652 0.02888041 0.1593551 0.9867988 0.02627903 0.1435613 0.9892925 0.01683622 0.0749244 0.9970471 0.0168367 0.07492434 0.997047 0.01671874 0.08990544 0.99581 0.02370589 0.05202054 0.9983646 0.02489608 0.05182993 0.9983456 0.02326768 0.08288693 0.9962873 0.02326768 0.08288693 0.9962872 0.0239169 0.08354276 0.9962172 0.02846252 0.1431378 0.9892935 0.02574497 0.08858251 0.9957361 0.02310049 0.08916723 0.9957488 0.002741336 -0.1642255 0.986419 0.005903542 -0.1646905 0.9863276 -0.02104812 -0.469959 0.8824373 -0.02308124 -0.4698244 0.8824581 -0.05321192 -0.7739365 0.6310235 -0.06533217 -0.773846 0.6299953 -0.08314555 -0.9476085 0.3084235 -0.1092045 -0.9467905 0.3027575 -0.1056476 -0.9772207 0.1840604 -0.1013699 -0.9924328 0.06929099 -0.08959388 -0.9933543 0.07225018 -0.0889095 -0.9852693 0.1460801 -0.08382362 -0.9855684 0.147066 -0.07827824 -0.9367837 0.3410409 -0.07626748 -0.9368537 0.3413041 -0.06275659 -0.8025882 0.5932232 -0.06426817 -0.8025238 0.5931485 -0.0778563 -0.931487 0.3553454 -0.07238769 -0.8673817 0.4923505 -0.08564287 -0.9845636 0.1526428 -0.08601707 -0.9878545 0.1294001 -0.08303987 -0.964669 0.2500363 -0.07964342 -0.9648715 0.2503598 -0.08331698 -0.9931836 0.08151543 -0.05941075 -0.6547937 -0.7534691 -0.05947214 -0.6555868 -0.7527742 -0.05903387 -0.6556276 -0.7527731 -0.09904873 0.303014 0.9478248 0.02040064 0.1572981 0.9873405 -0.0976786 0.3025498 0.9481152 0.03894066 0.2586853 0.9651765 0.02195298 0.1350101 0.990601 0.02285748 0.1318271 0.9910091 0.0350176 0.1298097 0.9909204 0.02285748 0.1318273 0.9910091 0.02468478 0.1345452 0.9905999 0.01711398 0.174333 0.9845379 0.01947683 0.1704497 0.9851739 0.01251572 0.1963229 0.9804594 0.02156794 0.1945297 0.9806595 0.01153647 0.2363085 0.9716095 0.02926272 0.2323747 0.972186 0.007793605 0.148014 0.9889545 0.01724904 0.1708546 0.9851453 0.01331359 0.1362512 0.9905849 0.02226507 0.1480537 0.9887287 0.03776443 0.1905412 0.9809526 0.03776437 0.1905412 0.9809525 0.03363651 0.1606314 0.9864412 0.02784967 0.1845794 0.982423 0.02784991 0.1845793 0.982423 -0.2074584 -0.9751461 0.07778769 -0.1832404 -0.3435192 0.9210958 -0.1955628 -0.4783794 0.8561007 -0.2452117 -0.4127312 0.8772252 -0.1732575 0.008114755 0.9848431 -0.2023128 -0.1774136 0.9631168 -0.1481476 -0.1930735 0.9699355 -0.1383754 -0.02261543 0.9901217 -0.0790072 -0.03426283 0.9962851 -0.07766407 0.07088571 0.9944565 -0.009722948 0.06082242 0.9981012 -0.01238471 0.1323763 0.9911222 0.04214632 0.1223495 0.9915918 0.0374872 0.1760739 0.9836629 0.05503588 0.1725104 0.983469 -0.1518283 -0.9179698 0.3664419 -0.1518285 -0.9179698 0.3664418 -0.1380284 -0.5822144 0.8012331 -0.1526974 -0.5813594 0.7991902 -0.04218643 -0.1845064 0.9819254 -0.05606293 -0.5650836 0.8231267 -0.05606293 -0.5650836 0.8231267 -0.1727444 -0.2929173 0.9404036 -0.1190178 -0.3008904 0.9462027 -0.09960007 -0.1421527 0.984821 -0.03927159 -0.1476224 0.9882637 -0.02354842 -0.01263409 0.9996429 0.01809859 -0.01873689 0.9996606 0.03027451 0.042822 0.9986239 0.05593013 0.2550166 0.9653179 0.0525546 0.2626158 0.9634682 0.04570955 0.2641153 0.9634075 0.0448997 0.26626 0.9628549 0.002505779 0.2753899 0.9613295 0.003716588 0.2712015 0.9625154 -0.04830455 0.2816755 0.958293 -0.04260253 0.2519792 0.9667944 -0.0851413 0.2622441 0.9612383 -0.07550233 0.1458212 0.9864257 -0.1053504 0.1551093 0.9822639 -0.1396093 0.09908163 0.9852371 -0.1732597 0.008101284 0.9848428 -0.1732609 0.00809592 0.9848427 0.02001333 0.3045393 0.9522895 2.87088e-4 0.3234177 0.9462563 0.03052413 0.3168438 0.9479864 -0.008177578 0.3723098 0.9280725 0.02023482 0.3672971 0.9298835 -0.03026545 0.4406292 0.8971788 -0.01660639 0.4378781 0.8988809 -0.03502005 0.4678225 0.8831284 0.008365571 0.500946 0.8654382 -0.01597315 0.4819223 0.8760684 -0.06126266 0.4820368 0.8740066 -0.06126242 0.4820367 0.8740065 -0.04267686 0.4965518 0.8669574 -0.06594097 0.5231097 0.8497105 0.008368909 0.500945 0.8654386 -0.01427251 0.2733021 0.9618223 -0.0235114 0.4082458 0.9125694 -0.001869857 0.4010245 0.9160654 -0.02828001 0.4301551 0.9023119 0.008705794 0.4434759 0.896244 0.008705675 0.4434759 0.8962441 0.001461267 0.1749771 0.9845713 0.008350014 0.1738667 0.9847338 0.01009047 0.1467638 0.9891201 0.01267611 0.1471908 0.9890269 -0.2539309 -0.7576122 0.6012843 -0.2174481 -0.9730644 0.07656377 -0.2678766 -0.7539691 0.5998106 -0.2513127 -0.4638543 0.8495182 -0.2588917 -0.7563704 0.6007319 -0.2452092 -0.4127101 0.877236 0.02226507 0.1480537 0.9887287 0.019535 0.1640987 0.9862505 0.02201002 0.1636018 0.9862809 0.0206834 0.1642307 0.9862051 0.03056001 0.2101475 0.977192 0.02849799 0.2106103 0.9771546 0.03749704 0.245911 0.9685669 -0.09767866 0.3025493 0.9481154 -0.09795194 0.3053553 0.9471873 -0.04512423 0.2876847 0.9566617 -0.07121473 0.3594244 0.9304529 -0.02410447 0.3446835 0.9384094 -0.04246389 0.4236666 0.9048224 -0.04085618 0.4232558 0.9050885 -0.03475463 0.4070089 0.9127628 -0.01380693 0.4023957 0.9153617 0.003303945 0.3662434 0.9305132 0.02085053 0.3623086 0.931825 0.04218006 0.324386 0.9449839 0.0291801 0.3272764 0.944478 0.0507974 0.2923946 0.9549477 0.02052164 0.2989177 0.9540582 0.03849554 0.270659 0.9619054 0.001980841 0.2784198 0.9604574 0.001420378 0.1801431 0.9836394 0.001420557 0.180143 0.9836395 0.006789624 0.1832454 0.9830437 -0.007034599 0.1957615 0.9806263 0.01252645 0.1922793 0.9812602 -0.0066486 0.2231821 0.9747541 -0.006648659 0.2231821 0.974754 -0.02052944 0.2710266 0.9623529 -0.02053004 0.2710267 0.9623528 0.00223422 0.2687862 0.9631973 -0.01326847 0.2906627 0.9567336 -0.01326835 0.2906627 0.9567336 -0.02081996 0.2198266 0.9753167 0.00369811 0.2319669 0.9727166 0.01190906 0.2524425 0.9675385 0.01909661 0.2508603 0.9678349 0.01910674 0.2531958 0.9672264 0.04416823 0.247797 0.9678047 0.0434215 0.2058854 0.9776122 0.05102747 0.2042872 0.9775802 0.0443924 0.04847908 0.9978373 0.02882528 0.05122923 0.9982708 0.03461092 -0.1177147 -0.9924441 0.06159973 0.7605643 -0.6463339 0.1097859 0.9207312 -0.3744345 0.06737661 0.3881694 -0.9191219 -0.01118713 0.3790213 -0.9253203 0.07996845 0.1622342 -0.9835065 0.08380138 0.1470892 -0.9855669 0.08380132 0.1470863 -0.9855673 0.006476104 0.1768665 -0.9842135 0.04022383 0.1939127 -0.9801938 0.07185202 0.1929162 -0.978581 0.001513659 0.2715517 -0.9624226 0.03995335 0.3773552 -0.9252063 -0.008182108 0.2603693 -0.9654744 0.001513838 0.2715517 -0.9624227 -0.003192842 0.367478 -0.9300267 -0.009062588 0.3814103 -0.9243614 -0.006014466 0.3930224 -0.9195093 -0.006015002 0.3930222 -0.9195093 -0.006069242 0.3930238 -0.9195083 -0.006015002 0.3933123 -0.9193853 -0.01118612 0.3790214 -0.9253203 -0.03374087 0.3438082 -0.9384335 -0.003572046 0.3373327 -0.9413787 -0.08418214 0.3419722 -0.9359318 -0.08419597 0.3419723 -0.9359306 -0.04435986 0.3189108 -0.946746 -0.03374075 0.3438083 -0.9384335 -0.03374141 0.3438082 -0.9384334 -0.1178076 0.339802 -0.9330894 -0.131934 0.3051213 -0.9431301 -0.1319362 0.3051155 -0.9431316 -0.1178048 0.3398017 -0.93309 -0.1178053 0.3398017 -0.9330899 -0.1361972 0.417651 -0.8983418 -0.136198 0.4176509 -0.8983417 -0.13361 0.4128239 -0.9009578 -0.1355561 0.4056206 -0.9039339 -0.1345193 0.4059392 -0.9039458 0.006178617 0.4982489 -0.867012 -0.02327787 0.3951208 -0.9183342 6.9877e-4 0.3945732 -0.9188643 -0.0777741 0.3864213 -0.9190374 -0.07777863 0.3864153 -0.9190396 -0.1045446 0.386197 -0.9164727 -0.07892835 0.4826111 -0.872271 -0.0789262 0.4826137 -0.8722699 0.04768747 0.3891089 -0.9199566 0.07444208 0.4633796 -0.8830276 0.07443195 0.4633696 -0.8830338 0.1349263 0.4986885 -0.8562154 0.06737625 0.3881691 -0.919122 0.09952872 0.4247266 -0.8998341 0.1117278 0.4040632 -0.907882 0.1244016 0.4032252 -0.9066056 0.1153907 0.4298437 -0.8954994 0.1129997 0.4299697 -0.8957438 0.1151568 0.4281812 -0.8963258 0.1343094 0.4989438 -0.8561636 0.1343091 0.4989414 -0.856165 0.1249145 0.6274482 -0.7685734 0.1249148 0.6274489 -0.7685728 0.1365421 0.7979311 -0.5870794 0.08564698 0.8130796 -0.5758179 0.1339816 0.89653 -0.4222357 0.1311898 0.8968855 -0.4223573 0.1455299 0.8990697 -0.4129101 0.1438204 0.9160462 -0.3743998 0.1098474 0.9207244 -0.3744331 0.08691585 0.9451674 -0.3148085 0.08691799 0.9451673 -0.3148085 0.08691585 0.945168 -0.3148065 0.06290417 0.8898563 -0.4518837 0.06763684 0.9180911 -0.3905559 0.06250745 0.9177609 -0.3921834 0.06392472 0.8866787 -0.457946 0.06290704 0.8898538 -0.4518883 0.03218168 0.8705953 -0.4909461 0.01249927 0.8711376 -0.49088 0.03315508 0.7681593 -0.6393997 0.06159955 0.7605643 -0.6463339 0.06159961 0.7605641 -0.6463342 0.06078463 0.8849105 -0.4617776 0.08147656 0.926305 -0.3678596 0.06290596 0.8898562 -0.4518837 0.06517392 0.6654125 -0.7436252 0.05063658 0.4941896 -0.8678782 0.02664309 0.2041767 -0.9785714 0.02664256 0.204178 -0.9785711 0.01379042 0.3674373 -0.929946 0.04724222 0.4898433 -0.8705295 0.05063688 0.4941896 -0.8678781 0.02586489 -0.05661171 -0.9980612 0.02586454 -0.05661076 -0.9980613 0.02683013 0.1824367 -0.9828515 0.03045153 0.1985841 -0.9796108 0.03045117 0.1985842 -0.9796107 0.02526021 -0.002147018 -0.9996786 0.02273327 -0.05256181 -0.9983589 0.02273362 -0.05256181 -0.9983589 0.06682497 -0.07233917 -0.9951389 0.05785131 -0.1402823 -0.98842 0.04439365 -0.1402596 -0.989119 0.05069977 -0.08241397 -0.9953078 0.0507 -0.08241289 -0.9953078 0.03974092 0.1729133 -0.984135 0.06330704 0.1837847 -0.9809259 0.07162517 0.1835158 -0.9804039 0.1223304 0.2306583 -0.9653145 0.03745037 0.2340761 -0.9714968 0.05995512 0.2753905 -0.959461 -0.008137345 0.2774454 -0.960707 -0.001523315 0.3008697 -0.9536641 -0.00997579 0.3010655 -0.9535512 -0.008472502 0.3064217 -0.9518582 -0.03559595 0.323086 -0.9456999 -0.04461503 0.3072624 -0.9505785 -0.008518874 0.3065983 -0.9518009 -0.00808078 0.3668246 -0.930255 -0.003193855 0.367478 -0.9300267 -0.1153739 0.5254535 -0.8429635 -0.08607465 0.6050452 -0.7915248 -0.09395009 0.6048008 -0.7908157 -0.06919431 0.6394518 -0.7657111 -0.01695352 0.6396628 -0.7684687 -0.004015445 0.6572503 -0.7536616 0.05159747 0.6550922 -0.7537851 0.05569571 0.660562 -0.7487028 0.1007337 0.6572232 -0.7469341 -0.1318888 0.4594486 -0.8783577 -0.1163958 0.5043176 -0.8556377 -0.102353 0.504697 -0.8572076 -0.09739518 0.5123853 -0.8532148 -0.02239352 0.5126244 -0.858321 -0.0189715 0.5179077 -0.8552261 0.04933118 0.5155773 -0.8554219 0.05011188 0.5167698 -0.8546566 0.1023465 0.513454 -0.8519919 0.09719175 0.505742 -0.8571925 0.1308324 0.5031265 -0.8542521 0.1087993 0.9189216 -0.3791381 0.1116487 0.8892593 -0.4435679 0.06906151 0.8931736 -0.4443776 0.02583152 0.8588885 -0.5115109 0.03211694 0.858658 -0.5115416 -0.0211749 0.8080571 -0.5887234 0.009822607 0.8078241 -0.5893418 -0.04449343 0.6850893 -0.7270991 0.1077983 0.9170929 -0.3838229 0.1050973 0.9209883 -0.3751467 0.1095159 0.8600776 -0.4982697 0.1213557 0.8587433 -0.4978279 0.122861 0.7760668 -0.6185674 0.1339131 0.7747855 -0.6178792 0.1217608 0.8025811 -0.5839845 0.1200249 0.6234968 -0.772558 0.1191086 0.6235826 -0.7726306 0.1222247 0.7746804 -0.6204285 0.07233619 0.7793189 -0.6224384 0.07464396 0.7899359 -0.6086294 0.07087332 0.9067452 -0.4156804 0.1077966 0.9170931 -0.3838229 -0.1345168 0.4059392 -0.9039461 -0.1171126 0.3900464 -0.9133172 -0.1131905 0.4599683 -0.8806912 -0.1042824 0.3632668 -0.9258307 -0.07206189 0.5265812 -0.8470651 -0.06678009 0.6017085 -0.7959192 -0.08629924 0.6011518 -0.7944613 -0.04307311 0.7092304 -0.7036597 -0.06563425 0.7087659 -0.7023839 -0.02356535 0.7590909 -0.6505579 -0.001887381 0.7589114 -0.6511912 0.02525132 0.7888438 -0.6140749 0.05574381 0.7873353 -0.6139999 0.09403538 0.8257957 -0.5560745 0.09446424 0.6490061 -0.7548957 0.1359093 0.6450276 -0.7519761 0.1284947 0.4997546 -0.856583 0.1346281 0.4992708 -0.8559228 0.1349266 0.4986924 -0.856213 0.05504423 0.724365 -0.6872157 0.05581843 0.7672399 -0.6389266 0.002272129 0.6219239 -0.7830744 0.005335688 0.6851709 -0.7283628 -0.04113805 0.5575205 -0.8291432 -0.04945188 0.3961596 -0.9168491 -0.06584006 0.3960671 -0.915858 -0.06727761 0.3634697 -0.9291736 -0.09090256 0.3233899 -0.9418894 -0.09076255 0.3268769 -0.9406985 -0.08419567 0.3419722 -0.9359306 0.0381428 0.1023911 -0.9940127 0.03814184 0.1023911 -0.9940128 0.1070423 0.07629638 -0.9913228 0.07018607 0.01927542 -0.9973477 0.04995036 0.01956135 -0.9985601 0.04972296 0.0187512 -0.998587 6.17897e-4 0.01936405 -0.9998123 0.01261895 0.1051101 -0.9943806 0.003419518 0.105239 -0.9944411 0.004771709 0.222759 -0.9748618 -0.01103228 0.2228305 -0.9747948 0.01197755 0.3142851 -0.9492531 -0.01606673 0.4598886 -0.8878313 0.03461098 -0.1177148 -0.9924442 0.03461122 -0.1177151 -0.9924441 0.009221792 -0.07790219 -0.9969183 0.02571749 0.01613676 -0.999539 0.01361745 0.016231 -0.9997755 0.01443207 0.05980688 -0.9981057 0.02682983 0.1824342 -0.9828519 0.0192306 0.1725689 -0.9848096 0.0192306 0.1725692 -0.9848096 0.05065953 0.1726161 -0.9836856 0.050565 0.1673232 -0.9846045 0.06295812 0.1669784 -0.9839484 0.06874144 0.1812704 -0.9810279 0.1212842 0.1793622 -0.9762783 0.1094281 0.1570266 -0.9815132 0.05791652 0.1586561 -0.9856337 0.05294287 0.1404845 -0.9886664 -0.003639996 0.1416642 -0.989908 0.003006756 0.1893198 -0.9819109 -0.009260475 0.189538 -0.9818297 -0.004339039 0.2600213 -0.9655931 -0.03692656 0.2603475 -0.9648087 -0.008677721 0.3153825 -0.948925 -0.04855674 0.3155936 -0.9476512 -0.01759761 0.4242936 -0.9053536 -0.01264178 0.4242713 -0.9054468 -0.01101911 0.4598996 -0.8879026 0.0385304 0.6212826 -0.7826387 0.03520637 0.5314746 -0.8463422 0.06517368 0.6654126 -0.7436253 -0.1713074 0.3413789 -0.924183 0.1806669 -0.4271304 -0.8859566 -0.1551822 0.2786555 -0.9477709 -0.1743427 0.2816158 -0.9435556 -0.1035148 0.2768853 -0.9553111 -0.05154216 0.2313681 -0.9715 -0.004853844 0.1643217 -0.9863948 -0.004853904 0.1643218 -0.9863948 -0.005249261 0.1589227 -0.9872771 -0.07433897 0.2515984 -0.9649725 -0.04447025 0.2348453 -0.9710149 -0.04456692 0.2230404 -0.9737899 -0.05270236 0.1917706 -0.9800238 -0.03101283 0.2044403 -0.9783876 -0.02447772 0.2033141 -0.9788075 -0.01313984 0.1656473 -0.9860975 -0.01130795 0.1755728 -0.9844015 -0.01193249 0.1756724 -0.9843764 -0.01769131 0.1745594 -0.9844877 -0.0319879 0.1892428 -0.9814091 -0.03198796 0.1892428 -0.9814091 -0.1071629 0.2802345 -0.9539313 -0.1065117 0.3084559 -0.9452567 -0.1104954 0.3092588 -0.9445368 -0.1369694 0.2383084 -0.9614824 -0.1503117 0.2944434 -0.9437741 -0.1336616 0.291086 -0.9473139 -0.1335874 0.290614 -0.9474692 -0.1026069 0.2853206 -0.9529239 -0.1019505 0.2775055 -0.9552993 0.2109628 -0.5384441 -0.8158264 0.225473 -0.4534209 -0.8623058 0.2254723 -0.453421 -0.8623059 0.220363 -0.5565391 -0.8010646 0.2137206 -0.5570343 -0.8025187 0.2118135 -0.6585192 -0.722141 0.2194331 -0.6194944 -0.753708 0.2194324 -0.6194946 -0.7537081 0.2125113 -0.5271365 -0.8227795 0.2125132 -0.5271362 -0.8227792 0.179439 -0.4306195 -0.884516 0.1868417 -0.4298319 -0.8833656 0.1443125 -0.4134404 -0.8990222 0.1806645 -0.4271462 -0.8859494 0.19505 -0.3633125 -0.9110211 0.2258722 -0.3686958 -0.9016903 0.2422188 -0.2800378 -0.9289289 0.2113138 -0.274173 -0.9381769 0.2218444 -0.1771969 -0.9588463 0.1536591 -0.1634963 -0.9745039 0.1538979 -0.06860005 -0.9857025 0.04929369 -0.04894751 -0.9975843 0.03867626 0.02519828 -0.9989341 -0.05808323 0.04008316 -0.9975067 -0.06843167 0.0874325 -0.9938172 -0.1135396 0.09403204 -0.9890736 -0.1350748 0.1796118 -0.9744201 -0.1586697 0.1833859 -0.9701513 -0.1702792 0.2456854 -0.9542765 -0.1709275 0.2457861 -0.9541347 -0.09921216 0.03683823 -0.9943841 -0.08190363 0.03425908 -0.9960513 -0.01468235 -0.1268725 -0.9918103 0.01978343 -0.1297596 -0.9913481 0.0581879 -0.2097994 -0.9760116 0.1098743 -0.2125048 -0.9709631 0.1466751 -0.3169896 -0.9370187 0.1855831 -0.3189758 -0.9294156 0.2025955 -0.4302114 -0.8797006 0.2221049 -0.430988 -0.8745964 0.222809 -0.5305438 -0.8178505 0.2197709 -0.5304812 -0.8187127 0.2117869 -0.6127168 -0.7613964 -0.147217 0.2064605 -0.9673165 -0.1304655 0.1291502 -0.9830051 -0.1196165 0.1266108 -0.984714 -0.05956274 -0.08704775 -0.9944219 0.01604825 -0.1612076 -0.9867901 -0.002062022 -0.1591123 -0.9872583 0.2722837 -0.759331 -0.5909975 0.2722841 -0.759331 -0.5909974 0.2254256 4.67134e-4 -0.9742603 0.2254256 4.66651e-4 -0.9742603 0.225422 4.56139e-4 -0.9742611 0.213709 -0.02945983 -0.9764531 0.2112601 -0.02859216 -0.9770116 0.2392392 0.04388797 -0.9699683 0.1702247 0.06823807 -0.9830397 0.1943072 0.1338449 -0.9717666 0.08125895 0.170475 -0.9820057 0.09802961 0.2204397 -0.9704621 -0.05433422 0.2606477 -0.9639039 -0.04771018 0.2842652 -0.9575579 -0.1616042 0.306048 -0.9381997 -0.160351 0.3102999 -0.9370173 -0.1906663 0.3150279 -0.929733 -0.1902541 0.3220368 -0.9274134 -0.2013623 0.3236872 -0.924489 -0.2014202 0.323329 -0.9246016 -0.1864915 0.3211687 -0.9284781 -0.187972 0.3159272 -0.9299767 -0.1450846 0.3094143 -0.9397941 -0.156071 0.2834332 -0.9462069 -0.1407896 0.385922 -0.911725 -0.1407905 0.3859221 -0.9117248 -0.1996269 0.4143937 -0.8879341 -0.1733823 0.4462007 -0.877977 -0.2058569 0.4505134 -0.868712 -0.1783043 0.5029845 -0.8457035 -0.200288 0.5060186 -0.8389458 -0.1799759 0.5240309 -0.8324664 0.1232834 0.4174761 -0.900286 0.1407287 0.4221153 -0.8955523 0.1782432 0.4069328 -0.8958991 -0.1275209 0.5496482 -0.825606 -0.1275219 0.5496485 -0.8256057 -0.1106534 0.5312931 -0.8399307 0.03407317 0.4954001 -0.8679964 0.02472066 0.4981125 -0.8667599 0.03410899 0.5066603 -0.8614708 0.03410917 0.5066602 -0.8614708 0.1276468 0.2635017 -0.9561764 -0.03313148 0.2279685 -0.9731046 -0.033692 0.2097538 -0.9771736 -0.01793205 0.218075 -0.9757672 0.00145775 0.1631032 -0.9866079 0.00145781 0.1631032 -0.9866079 -0.01775825 0.1728882 -0.9847814 -0.01299881 0.1740816 -0.9846454 -0.02556109 0.1761273 -0.9840356 -0.01294308 0.1919167 -0.9813258 -0.01294296 0.1919167 -0.9813258 0.09417337 -0.7683928 -0.6330119 0.06248193 -0.9182741 -0.3909841 0.1220254 -0.7676976 -0.6290868 0.1585276 -0.611826 -0.7749439 0.1129508 -0.7679861 -0.630428 0.1878226 -0.4282353 -0.8839328 -0.1071631 0.2802346 -0.9539312 -0.07478171 0.267253 -0.9607204 -0.07551342 0.2715717 -0.9594512 -0.06792086 0.2504005 -0.965757 -0.05637788 0.2686865 -0.9615764 0.1478191 0.3748846 -0.9152109 0.1862618 0.2387187 -0.9530582 0.1862617 0.2387183 -0.9530583 0.1386238 0.03326892 -0.989786 0.2016405 0.1956435 -0.9597212 0.175643 0.2064746 -0.9625579 0.2114493 0.2603257 -0.9420827 0.1262969 0.2940734 -0.9474017 0.1552392 0.3351157 -0.9293 0.03427267 0.3766916 -0.9257044 0.05127149 0.3999601 -0.9150974 -0.09618222 0.4388874 -0.8933795 -0.09663873 0.4382538 -0.8936412 -0.1897474 0.4551503 -0.8699621 -0.2019131 0.4394041 -0.8753029 -0.2040221 0.4397037 -0.8746632 -0.2145075 0.4076071 -0.8876052 -0.1983509 0.40539 -0.8923653 -0.2124048 0.372728 -0.9033039 -0.1741288 0.3673693 -0.9136296 -0.189644 0.3387523 -0.9215649 -0.1306232 0.3297728 -0.9349799 -0.1449594 0.3082437 -0.9401981 -0.07770317 0.2965819 -0.9518411 -0.01752293 0.2629501 -0.9646503 -0.07171148 0.2693709 -0.9603628 -0.07700276 0.2704091 -0.9596612 -0.07175141 0.2768344 -0.958235 -0.1282107 0.2868902 -0.9493451 -0.07191824 0.359452 -0.9303882 -0.1384278 0.3364462 -0.9314729 -0.01777267 0.2361292 -0.9715591 -0.03739279 0.2399768 -0.9700582 -0.05639225 0.2693368 -0.9613937 -0.09282803 0.2764588 -0.956532 -0.09374022 0.2928359 -0.9515566 -0.136766 0.3002367 -0.9440091 -0.1347704 0.285631 -0.9488161 -0.1535634 0.2886494 -0.9450396 -0.1500068 0.2717788 -0.9505968 -0.1446871 0.2706293 -0.9517487 0.02748245 -0.9737813 -0.22582 -0.08061921 -0.9263646 0.3678984 0.1902906 -0.5952686 -0.7806695 -0.05952268 -0.9778338 0.2007441 0.363363 -0.9315007 -0.01654326 0.3606038 -0.9325881 -0.01563477 0.2361547 -0.8621596 0.4482319 0.1229007 -0.5444264 -0.8297562 -0.073596 0.07086819 -0.994767 -0.004728257 0.2376923 -0.971329 0.002174556 0.2895755 -0.9571528 0.017982 0.4068486 -0.9133185 0.07207387 0.7726556 -0.6307208 0.01793956 0.4065355 -0.9134588 0.0021829 0.2896308 -0.957136 0.002172708 0.2895541 -0.9571591 -0.01155561 0.4577675 -0.888997 -0.0115565 0.4577555 -0.889003 -0.006996452 0.513718 -0.8579306 -0.006854891 0.5136949 -0.8579456 -0.04507237 -0.09107595 -0.9948235 -0.01248419 0.4550287 -0.8903893 -0.005949854 0.5258117 -0.8505802 0.006410539 0.5237464 -0.8518501 -0.003006815 0.4368772 -0.8995161 0.02251327 0.4324194 -0.9013915 -0.004721939 0.2377378 -0.9713179 -0.06296092 0.1737748 -0.9827707 -0.04010945 0.4806188 -0.8760119 -0.04010945 0.4806187 -0.876012 -0.1010717 0.2715148 -0.9571124 -0.09167283 0.1909135 -0.9773168 0.1642297 -0.562044 -0.8106387 0.1521742 -0.5632691 -0.8121396 0.0480228 -0.3031606 -0.9517287 0.03497928 -0.3023804 -0.9525453 -0.03481417 -0.08780705 -0.9955289 -0.0286557 -0.1089535 -0.9936338 0.08554679 -0.4221066 -0.9025008 0.09585654 -0.4220974 -0.9014685 0.01545083 -0.237997 -0.971143 0.06988018 -0.4055723 -0.9113878 0.08142864 -0.405695 -0.9103741 0.1393907 -0.566236 -0.8123712 0.1547275 -0.5648327 -0.8105698 0.2015581 -0.67747 -0.7073957 0.215285 -0.6748372 -0.7058662 0.2445747 -0.7394524 -0.6272108 0.2490066 -0.7382574 -0.6268746 -0.0635038 -0.009928703 -0.9979323 -0.06348067 -0.01008975 -0.9979321 0.2336659 -0.8416429 0.4868648 0.2350974 -0.8543416 0.4634972 0.1705337 -0.8402858 -0.5146241 0.1868042 -0.7197976 -0.6685774 0.2029864 -0.716633 -0.6672583 0.2758306 -0.8834035 -0.3788348 0.2968115 -0.8761593 -0.3797997 0.338797 -0.9400782 -0.03833502 0.2229129 -0.8086469 -0.5444263 0.2403072 -0.8040394 -0.5438503 0.3047795 -0.9344776 -0.1840143 0.3264899 -0.9264035 -0.1875655 0.3445518 -0.9315912 0.1158526 0.2361404 -0.8621617 0.4482352 0.2361138 -0.8619549 0.4486469 0.2361109 -0.8619438 0.4486697 0.1326628 -0.9788951 -0.1554512 0.1123504 -0.9308331 0.3477456 0.2625082 -0.9030427 -0.3400049 0.2625073 -0.903043 -0.3400047 0.2618864 -0.8832506 0.3889523 0.3665761 -0.9092156 -0.197355 0.376178 -0.9046151 -0.2004041 -0.06614714 -0.9771099 0.2021899 -0.03076034 -0.997927 0.05652946 0.02888 -0.9985595 0.04521864 0.04948836 -0.9984833 -0.0241248 0.09885251 -0.994543 -0.03335094 0.1146386 -0.9889788 -0.09369623 0.1905043 -0.975666 -0.1085545 0.1998482 -0.9662824 -0.1623549 0.3127707 -0.931171 -0.1873371 0.3141397 -0.9218178 -0.2270861 0.3716648 -0.8963323 -0.2417716 0.3709642 -0.8939498 -0.2514742 0.3441099 -0.9064269 -0.2449051 0.3475404 -0.9126362 -0.2151993 0.3423802 -0.9148261 -0.2141703 0.3304095 -0.8925706 -0.3068342 0.3254705 -0.8945751 -0.3062747 0.3093311 -0.8638947 -0.3974924 0.2923954 -0.8700435 -0.3968996 0.37211 -0.9267799 0.05111861 0.3649621 -0.9283165 0.07092982 0.3664124 -0.9277893 0.07034868 0.3629019 -0.9103118 0.1990842 0.3629017 -0.9103118 0.1990852 0.249521 -0.8284876 -0.5013458 0.2693012 -0.8225668 -0.50086 0.3222475 -0.92211 -0.2141722 0.3388608 -0.9155358 -0.2167203 0.356081 -0.9334695 -0.04290741 0.3621553 -0.928965 0.07660007 0.3624388 -0.9255414 0.1095953 0.3607183 -0.9323153 0.02589327 0.1718766 -0.3515757 0.9202461 -0.0955761 0.05833679 -0.9937113 -0.09557628 0.05833673 -0.9937113 0.05869853 -0.3285829 -0.9426493 -0.1123524 0.1595419 -0.9807769 -0.08632349 0.07797467 -0.993211 -0.1228702 0.2692879 -0.9551895 -0.1178657 0.1599293 -0.9800665 -0.09817248 0.2372071 -0.9664858 -0.1097058 0.239178 -0.9647582 -0.1005733 0.1924004 -0.9761492 -0.01170974 -0.1796878 -0.9836539 -0.01170885 -0.179692 -0.9836533 -0.01170176 -0.1797201 -0.9836482 -0.01172953 -0.1796914 -0.9836531 -0.03807407 -0.1683255 -0.984996 -0.06348884 -0.01003146 -0.9979321 0.1787895 -0.5971175 -0.781975 0.1138613 -0.4366568 -0.8923937 0.1036762 -0.4369608 -0.8934856 0.02725338 -0.2376886 -0.970959 0.01917284 -0.2370172 -0.9713163 -0.06787854 -0.009864449 -0.9976449 -0.09891432 0.09669959 -0.9903864 -0.09640032 0.09629607 -0.9906736 -0.09989738 0.1114557 -0.9887356 -0.09545731 0.08175259 -0.9920707 0.04734581 -0.2381354 -0.9700773 0.047347 -0.2381354 -0.9700772 -0.1404275 0.2226358 -0.9647349 -0.1030017 0.1003987 -0.9896013 -0.1030013 0.1003987 -0.9896013 -0.1117662 0.1234636 -0.986035 -0.03941303 -0.1156631 -0.9925062 -0.02328759 -0.1176757 -0.992779 -0.006433069 -0.1641482 -0.9864147 0.1167917 -0.4523687 -0.8841506 0.1262097 -0.451862 -0.8831149 0.2149016 -0.6511949 -0.7278479 0.2854932 -0.8457283 -0.4508187 0.2274649 -0.7128715 -0.6633808 0.2854958 -0.8457275 -0.4508182 0.2532006 -0.6605517 -0.7067962 0.24624 -0.6624637 -0.7074657 -0.001700341 -0.9747467 -0.2233074 0.1132766 -0.8082154 -0.5778894 0.1801494 -0.9424321 -0.2817233 0.1801502 -0.9424319 -0.2817233 0.1962217 -0.806873 -0.5571831 -0.01128214 -0.986903 0.16092 -0.004637002 -0.987015 0.1605608 -0.05155038 -0.9461438 0.3196161 -0.0515502 -0.9461438 0.3196161 -0.1354921 0.2238103 -0.9651688 0.2568678 -0.6514007 -0.7139299 0.252636 -0.6410809 -0.7247002 0.2963016 -0.7391213 -0.6049007 0.2625658 -0.7512604 -0.6055305 0.2555061 -0.7359646 -0.6269551 0.2461112 -0.7386473 -0.6275584 0.1907551 -0.6086136 -0.7701961 0.1811381 -0.6101089 -0.771334 0.09821617 -0.4043241 -0.909327 0.08289408 -0.4042842 -0.9108693 -0.002371966 -0.1687152 -0.985662 -0.01422691 -0.1674003 -0.9857864 -0.07422822 0.0279538 -0.9968494 -0.07367283 0.0278688 -0.996893 -0.04097884 -0.08699458 -0.9953656 0.2511638 -0.876433 0.4108306 -0.007787227 -0.2359543 -0.9717329 -0.006238579 0.2037 -0.9790135 -0.006234169 0.2037355 -0.9790061 -0.009305775 0.1811376 -0.9834138 -0.03573626 0.1292182 -0.9909721 -0.04314035 0.2726994 -0.9611316 -0.05058473 0.1036627 -0.9933253 -0.01183027 0.4547553 -0.8905379 -0.0115562 0.457759 -0.8890013 -0.0115562 0.4577591 -0.8890013 -0.03573638 0.1292182 -0.9909721 -0.03640687 0.1227098 -0.9917746 -0.03613555 0.1226686 -0.9917897 -0.02120339 0.207759 -0.9779502 -0.01419216 0.156888 -0.9875144 -0.01297414 0.1567007 -0.9875609 -0.01123583 0.1814423 -0.9833374 0.1326618 -0.9788952 -0.1554511 0.1099629 -0.9913359 -0.07184183 0.1156462 -0.990611 -0.07290923 -0.03448063 -0.9528795 0.3013829 0.06367629 -0.9624153 -0.2640114 0.04029327 -0.9660075 -0.2553547 -0.04254585 -0.9794819 0.19699 -0.06348896 -0.01003181 -0.9979321 -0.06348741 -0.01004314 -0.9979321 -0.1060206 0.3364936 -0.9356986 -0.1035677 0.3357883 -0.9362265 -0.07772231 0.2082642 -0.9749796 -0.07687819 0.4180402 -0.9051697 -0.07687819 0.4180401 -0.9051697 0.02997732 -0.9736621 -0.2260164 0.01507502 -0.9862871 -0.1643484 0.08000475 -0.9819687 -0.1712797 0.1019281 -0.9634519 -0.2477321 0.1409472 -0.957689 -0.2509298 0.1589021 -0.9316958 -0.3266394 0.2118926 -0.9198016 -0.3302524 0.2216312 -0.8855293 -0.4083105 0.3000875 -0.8598056 -0.4131365 0.2959101 -0.8224918 -0.4857411 0.3305671 -0.8079776 -0.4877474 0.3347432 -0.8181908 -0.4674513 0.3028019 -0.8319303 -0.4649765 0.3108316 -0.8480641 -0.4291515 0.3052108 -0.8502447 -0.428871 0.2870334 -0.8126018 -0.5072377 0.281707 -0.8144113 -0.5073218 0.2653847 -0.7805041 -0.5660249 0.2503347 -0.7848216 -0.5669106 0.2210439 -0.718717 -0.659231 0.2028397 -0.7225497 -0.6608918 0.1467474 -0.5758411 -0.8042837 0.1319985 -0.5772107 -0.8058562 0.06886738 -0.3920739 -0.9173523 0.03445512 -0.3912606 -0.9196347 0.07842248 -0.5470058 -0.8334473 0.1138774 -0.6663009 -0.7369362 0.1657052 -0.659601 -0.7331224 0.2307397 -0.8256462 -0.514847 0.2415899 -0.6097384 0.7548863 0.2978461 -0.8300131 0.4715569 0.1438929 -0.2721552 0.9514338 0.2398517 -0.7830446 -0.5738574 0.1718764 -0.3515757 0.9202461 -0.05320477 0.1735349 -0.9833894 -0.05320489 0.1735349 -0.9833895 -0.06241893 0.2588528 -0.9638979 -0.07314342 0.2120592 -0.9745158 -0.07791966 0.2128137 -0.9739809 -0.0749548 0.2735545 -0.9589315 -0.09190827 0.2698399 -0.9585089 -0.1051412 0.2629155 -0.9590728 -0.1009728 0.2621925 -0.9597185 -0.09539163 0.1821182 -0.9786385 -0.09539175 0.1821182 -0.9786385 -0.110688 -0.6840646 0.7209742 0.03416955 -0.29534 0.954781 -0.001727104 -0.2160698 0.9763764 0.002933681 -0.2168108 0.9762093 -0.1173487 -0.9900619 0.07750225 -0.05664765 -0.5023918 0.8627825 -0.003668069 -0.2157602 0.9764394 0.006260931 -0.1830694 0.9830801 0.05189269 -0.2715606 0.9610214 0.01387625 -0.2493738 0.9683079 0.0347743 -0.2532451 0.9667769 5.59053e-4 -0.1821541 0.9832698 0.004706203 -0.1876906 0.9822168 4.56152e-4 -0.1870127 0.9823574 0.01589399 -0.2029325 0.9790638 1.72871e-4 -0.2003695 0.9797204 0.0236994 -0.2054474 0.9783812 0.01463764 -0.2171682 0.9760244 0.0146377 -0.2171683 0.9760245 0.006914794 -0.631024 0.7757325 0.025945 -0.635989 0.7712618 -0.05687141 -0.5899491 0.8054351 -0.04296064 -0.5819827 0.8120656 0.02824199 -0.6537057 0.7562216 0.02824193 -0.6537058 0.7562217 0.1076164 -0.6259285 0.7724197 0.1235647 -0.6338283 0.7635401 0.1819765 -0.6426353 0.7442477 0.1138039 -0.5852615 0.8028186 0.1138033 -0.5852614 0.8028187 0.1367841 -0.5316665 0.8358355 0.07257014 -0.5153949 0.8538745 0.1253858 -0.5245774 0.8420789 0.0521878 -0.4358142 0.8985224 0.09354245 -0.4433623 0.891448 0.06729745 -0.8184571 -0.570613 0.06729769 -0.8184571 -0.570613 0.1204442 -0.5117254 0.8506646 0.1204197 -0.5114861 0.850812 0.1204205 -0.5114928 0.8508079 0.2184054 -0.9474244 -0.2338505 0.1344708 -0.6646192 0.7349823 0.1127771 -0.9543066 -0.2767315 -0.01623982 -0.3476048 -0.9375005 0.1719113 -0.8555175 -0.4884018 0.1338855 -0.7080401 -0.6933642 0.1338844 -0.7080405 -0.693364 0.2240401 -0.9215431 -0.3171188 0.2406638 -0.9006705 0.3617643 0.1830056 -0.6618134 0.7269883 0.2161775 -0.6629787 0.7167472 0.3109074 -0.8362913 0.4516119 0.3308303 -0.9377001 -0.1061587 0.3308304 -0.9377002 -0.1061585 0.3700538 -0.8996039 0.2318904 0.2294844 -0.7072749 0.6686547 0.2746262 -0.7064364 0.6523252 0.2934951 -0.7839281 0.5470989 0.3352708 -0.7795261 0.5290865 0.3376686 -0.8437505 0.4172109 0.3519902 -0.8671144 0.3524425 0.3432272 -0.8689153 0.3566249 0.3614822 -0.9036259 0.2297629 0.3614836 -0.9036254 0.2297622 0.3545622 -0.886856 0.2962636 0.3545616 -0.886856 0.2962639 0.2986696 -0.9481045 0.1090614 0.1584202 -0.8701885 0.4665564 0.1584209 -0.8701886 0.4665561 -0.01167476 -0.8751481 0.4837143 -0.02457243 -0.8628078 0.5049344 -0.02457195 -0.8628079 0.5049343 -0.060777 -0.8779993 0.4747878 -0.1249125 -0.8187793 0.5603547 -0.1249121 -0.8187794 0.5603546 -0.1432965 -0.8778957 0.4569085 -0.110881 -0.6839928 0.7210125 -0.1108818 -0.6839973 0.7210083 -0.08417141 -0.8454791 0.527333 -0.08415246 -0.8453733 0.527506 -0.08417606 -0.8455055 0.5272901 -0.05568474 -0.671932 0.7385165 -0.04665499 -0.6140419 0.7878932 -0.04666244 -0.6140909 0.7878547 -0.0182535 -0.4100159 0.9118957 -0.0182535 -0.4100159 0.9118958 -0.01825702 -0.4100413 0.9118843 -0.07379263 -0.778485 -0.6233102 -0.07372468 -0.7742681 -0.6285488 -0.07374513 -0.7702499 -0.6334641 -0.07090157 -0.7703922 -0.6336156 0.001501739 -0.5758562 0.8175495 0.002932071 -0.2168222 0.9762067 -0.06431108 -0.6997901 0.7114477 -0.02576053 -0.7054891 0.7082524 -0.07379299 -0.7784969 -0.6232953 -0.07379287 -0.7784969 -0.6232953 0.03914231 -0.2412633 0.9696699 -0.07076698 -0.7627267 -0.6428374 -0.07364898 -0.7625834 -0.6426836 -0.07369118 -0.7698477 -0.6339591 -0.06879603 -0.7700903 -0.6342145 0.05798298 0.1169528 0.9914434 -0.06093335 -0.477487 -0.8765233 0.06267064 -0.2328006 0.970503 -0.04405838 -0.4103725 -0.910853 -0.04405814 -0.4103725 -0.910853 0.08263725 -0.3247589 0.9421798 -0.01836282 -0.3354923 -0.9418639 -0.0183624 -0.3354922 -0.941864 -0.06149744 -0.3790226 -0.9233417 -0.059978 -0.4775002 -0.8765822 -0.06006407 -0.4672721 -0.882071 -0.05199331 -0.4673638 -0.8825348 -0.05480843 -0.3954263 -0.916861 -0.03893721 -0.3946069 -0.9180247 -0.0452972 -0.32055 -0.9461479 -0.0177918 -0.3163471 -0.9484767 0.1504733 -0.8586736 0.489936 0.7917811 -0.609789 0.03521257 0.2420896 -0.9632194 0.1166241 -0.003363728 -0.6266533 0.7792909 0.02056699 -0.6295318 0.7767024 0.01593476 -0.6837832 0.7295112 0.0506218 -0.6872365 0.7246679 0.04911398 -0.7115249 0.7009424 0.0888198 -0.7144996 0.6939751 0.088355 -0.736122 0.6710572 0.1443538 -0.7385475 0.6585662 0.1496824 -0.8914387 0.4277057 0.2249506 -0.8919649 0.3921683 0.1143321 -0.6973566 -0.7075464 0.1389501 -0.686557 -0.7136753 0.2663245 -0.8947334 0.3585017 0.2568845 -0.8945807 0.3656991 0.2402844 -0.8968076 0.371483 0.03337866 -0.4409714 0.8969002 0.01266324 -0.4379085 0.8989304 0.01630973 -0.3974782 0.9174667 -1.36949e-4 -0.3950074 0.9186779 -0.01818674 -0.5732005 0.8192133 -0.03012657 -0.6757332 0.7365304 0.03523796 0.008653879 0.9993415 0.03524315 0.008705735 0.9993408 -0.06756132 -0.4971272 -0.8650434 0.1725444 -0.6166512 0.7680948 0.1433744 -0.6144797 0.7757954 0.1495621 -0.9207273 0.360406 0.1156238 -0.5500046 0.8271192 0.08822774 -0.5466 0.832733 0.0872538 -0.521881 0.848544 0.05729579 -0.5178946 0.8535234 0.05742847 -0.4932055 0.8680152 0.02978694 -0.4892513 0.8716341 -0.001727342 -0.2160721 0.9763759 -0.006004095 -0.2760557 0.9611228 0.01351153 -0.2791116 0.9601637 0.01349443 -0.2909647 0.9566386 0.02240169 -0.2923544 0.9560476 0.02151674 -0.3227061 0.9462547 0.03754317 -0.3252835 0.944871 0.03720337 -0.3650205 0.9302559 0.05821579 -0.3684802 0.927811 0.05985468 -0.3912191 0.9183492 0.08212268 -0.394839 0.9150727 0.08506721 -0.4199954 0.9035305 0.1020883 -0.4227613 0.9004726 0.1075883 -0.4447289 0.88918 0.1154407 -0.4458871 0.8876137 0.1267448 -0.4824068 0.8667292 0.1393245 -0.4840409 0.8638826 0.156607 -0.5296939 0.8336058 0.1736306 -0.5314771 0.8290866 0.1965141 -0.5814695 0.789478 0.219092 -0.5830332 0.7823497 0.2628404 -0.6815664 0.6829218 0.2689863 -0.6815866 0.6805045 0.3117558 -0.7646936 0.5639611 0.2951329 -0.7657163 0.5714676 0.3306612 -0.829833 0.449489 0.3294205 -0.8299852 0.4501185 0.3515447 -0.8525836 0.3866747 0.2413482 -0.8645101 0.440878 0.2545934 -0.8770823 0.4073191 0.08562827 -0.8764208 0.4738717 0.15342 -0.9374673 0.3124378 -0.01924085 -0.8738628 0.4857916 -0.04296058 -0.5819827 0.8120656 -0.08594238 -0.514173 0.8533698 -0.0441665 -0.5294495 0.847191 -0.05662107 -0.5185257 0.8531854 -0.03936767 -0.5086007 0.8601021 0.03710377 -0.3756486 0.9260192 0.03128272 -0.3733027 0.927182 0.06835907 -0.380059 0.9224328 0.02634334 -0.3470564 0.9374743 0.05403727 -0.3299165 0.9424623 0.0219888 -0.3237738 0.9458791 0.05583035 -0.3283668 0.9428989 0.03698348 -0.3134471 0.9488852 0.06286478 -0.318268 0.945914 0.03569436 -0.2952662 0.954748 0.03569471 -0.2952663 0.954748 -0.1258448 -0.4757174 0.8705493 -0.07176661 -0.5956019 0.8000676 -0.1157621 -0.5798466 0.8064596 -0.07403492 -0.6379315 0.7665262 -0.07217556 -0.6385293 0.7662056 -0.04430735 -0.6709481 0.7401794 0.0162692 -0.6868662 0.7266018 0.01922345 -0.6897221 0.723819 0.1581291 -0.7145767 0.6814509 0.1243141 -0.6880924 0.714895 0.243306 -0.7010205 0.6703524 0.1868193 -0.6598974 0.7277595 0.2209838 -0.6631903 0.7150838 0.1499889 -0.578462 0.8018013 0.1935376 -0.5837603 0.7885221 0.115057 -0.4922512 0.8628155 0.1547201 -0.4980133 0.8532552 0.08413285 -0.4124582 0.9070832 0.1137683 -0.4172948 0.9016218 0.06794089 -0.3783778 0.9231545 0.09437441 -0.3829334 0.9189426 0.05794906 -0.3502389 0.9348662 0.08358478 -0.35484 0.9311832 0.05586755 -0.3286438 0.9428002 0.0819633 -0.3334631 0.9391936 0.06256145 -0.3141813 0.9472994 0.07079434 -0.3157601 0.9461944 0.04931473 -0.2773784 0.9594944 0.03422367 -0.274525 0.9609708 -0.1108818 -0.6839974 0.7210081 -0.1107485 -0.6843296 0.7207134 -0.1255072 -0.6792195 0.7231244 -0.0876668 -0.7289614 0.6789181 -0.06470608 -0.7356572 0.6742562 -0.04141598 -0.7610014 0.647427 0.04487419 -0.7795889 0.624682 0.04466849 -0.7794045 0.6249266 0.2112388 -0.7973577 0.5653308 0.1801315 -0.7751855 0.6055082 0.3086048 -0.7773833 0.5481225 0.2583289 -0.743389 0.6169595 0.287373 -0.743525 0.6038107 0.2206839 -0.6622965 0.7160042 0.2627538 -0.6643302 0.6997327 0.1885008 -0.56977 0.7998935 0.2155423 -0.5722441 0.7912511 0.1472826 -0.4757405 0.8671671 0.1594803 -0.4773134 0.86414 0.1178058 -0.4323244 0.8939896 0.1293078 -0.4340243 0.891573 0.09698146 -0.3955147 0.9133251 0.1085774 -0.3973879 0.9112047 0.08537733 -0.3671196 0.9262473 0.09747397 -0.3691933 0.9242268 0.08330059 -0.3490739 0.9333854 0.08078444 -0.3486172 0.9337772 0.0709781 -0.3226323 0.9438594 0.05898642 -0.3205077 0.9454075 0.05155217 -0.2985093 0.9530134 0.039011 -0.2963094 0.954295 0.03441172 -0.2617173 0.9645309 0.02463513 -0.2600829 0.9652719 0.02196758 -0.2355805 0.9716065 0.01702237 -0.2347933 0.9718962 0.01450634 -0.2246825 0.9743241 -0.00282222 -0.2219342 0.9750576 -0.003668069 -0.2157604 0.9764394 -0.005021393 -0.0863685 0.9962506 0.005286633 0.1787893 -0.9838732 0.05005359 0.4013321 -0.9145639 0.02684402 0.1272518 -0.9915071 -0.0324651 9.07229e-4 -0.9994724 0.01002681 0.1003116 -0.9949055 0.02612674 0.1103004 -0.9935549 0.009105622 0.1061194 -0.9943118 0.03189134 0.1028053 -0.9941902 0.01671463 0.08943945 -0.995852 0.0819205 0.5086271 -0.8570808 0.01229411 0.130549 -0.9913657 -0.002647757 0.108752 -0.9940654 0.01176619 0.1123663 -0.9935972 0.006045758 0.1064913 -0.9942952 0.01478278 0.09815913 -0.995061 0.01905459 0.1034949 -0.9944475 0.01244693 0.1007727 -0.9948316 0.01143485 0.09438431 -0.9954702 0.02715706 0.1058674 -0.9940093 0.02684581 0.1272559 -0.9915066 -0.02087414 0.03728199 -0.9990867 0.09913194 0.346058 -0.9329613 0.07192605 0.3232138 -0.9435886 0.1278502 0.4767316 -0.8697018 0.1806304 0.6442073 -0.7432157 -0.04232227 -0.003829002 -0.9990966 0.01291632 0.08203971 -0.9965454 0.02100157 0.08675694 -0.996008 0.007523775 0.1623206 -0.9867094 8.75082e-4 0.1508388 -0.9885581 -0.01977568 0.06053161 -0.9979704 0.04473787 0.4025257 -0.9143149 0.1197893 0.7652057 -0.6325432 0.009659051 0.2011793 -0.9795069 0.009652137 0.2011458 -0.9795138 0.0167182 0.2342484 -0.972033 0.02753907 0.2854258 -0.9580051 -0.01077109 0.1024998 -0.9946747 0.02593827 0.2857345 -0.9579577 0.02595961 0.2858385 -0.9579262 0.02359306 0.2600709 -0.9653012 0.0220431 0.2599368 -0.9653741 0.01672434 0.234278 -0.9720258 0.005286931 0.1787906 -0.983873 0.005363702 0.1791444 -0.9838082 0.005474627 0.1791403 -0.9838083 0.0418868 0.3454211 -0.9375125 0.0795027 0.5072795 -0.8581066 -0.02064371 0.03800529 -0.9990643 0.01163744 0.1592683 -0.9871667 0.001376569 0.1579023 -0.9874538 0.001918315 0.1604734 -0.9870383 0.002488553 0.1604525 -0.9870404 0.003125607 0.1630349 -0.9866154 -0.0381906 0.008408546 -0.9992351 0.05103838 0.0827012 -0.9952666 0.00540781 0.05334866 -0.9985613 0.03616958 0.09404337 -0.9949108 0.0207073 0.08526456 -0.9961431 0.03222334 0.0970453 -0.9947582 0.03439348 0.09844917 -0.9945476 -3.31843e-4 0.1193616 -0.9928508 0.009240746 0.1217596 -0.9925165 0.006768465 0.1089692 -0.9940221 0.02081245 0.11475 -0.9931764 0.006970167 0.0786072 -0.9968813 -0.02791094 0.02394407 -0.9993236 0.02036273 0.1547544 -0.9877431 0.008438706 0.1328752 -0.9910969 0.03600412 0.1269437 -0.9912562 0.03600406 0.1269438 -0.9912563 0.1124234 0.5823589 -0.8051205 0.001347005 0.1388716 -0.9903095 -6.13925e-4 0.138608 -0.9903472 -0.002535045 0.1285635 -0.991698 0.008266389 0.1505655 -0.9885655 0.008531808 0.1527907 -0.9882217 0.007523775 0.1623208 -0.9867094 -0.02606695 -0.1654222 0.9858783 -0.1373295 -0.7478938 0.649458 -0.2389345 0.6353341 0.7343438 -0.03906983 -0.1185597 0.992178 -0.0371747 -0.1294479 0.9908891 -0.01283162 -0.03375416 0.9993478 -0.03139686 -0.1277065 0.991315 -0.3919727 -0.7812457 0.4858112 -0.2689675 -0.8845375 0.3811166 -0.1714001 0.5405952 0.8236377 -0.1714926 0.5411593 0.8232477 -0.1714385 0.5408294 0.8234758 -0.008295536 -0.1281961 0.9917141 -0.00830233 -0.1282281 0.99171 -0.180995 -0.9109158 0.3707737 0.02087634 -0.0372762 0.9990869 -0.3042002 -0.7243688 0.6186696 -0.1116441 -0.2851361 0.9519628 -0.0784716 -0.2169887 0.973015 -0.2253877 -0.5986164 0.7686734 -0.02014392 -0.1543858 0.9878053 -0.02420526 -0.1553894 0.9875566 -0.0386098 -0.2044481 0.9781157 -0.0369746 -0.2005715 0.9789811 -0.2436688 -0.8005602 0.5474749 -0.1919872 -0.6765708 0.71091 -0.08608448 -0.1181188 0.9892611 -0.08246499 -0.1205914 0.9892711 -0.02044707 -0.09663838 0.9951096 -0.05663251 -0.1523885 0.9866967 -0.04757267 -0.1178311 0.9918935 -0.2389357 0.6353344 0.7343432 -0.1695826 0.257225 0.9513553 -0.1102966 0.01968783 0.9937037 -0.111357 0.02467322 0.9934741 -0.08777654 -0.06413984 0.9940732 -0.1667254 0.1631396 0.9724135 -0.1247785 0.0221278 0.9919378 -0.2774829 0.4951218 0.8233211 -0.2774816 0.495122 0.8233215 -0.08812654 -0.0585671 0.9943861 -0.09018629 -0.05894643 0.994179 -0.09095042 -0.0539658 0.994392 -0.08565276 -0.05265522 0.9949327 -0.08653217 -0.04975789 0.9950056 -0.05878067 -0.09085929 0.9941275 -0.2795722 0.2867572 0.9163022 -0.2792264 0.2867777 0.9164012 -0.1626395 0.100349 0.9815694 -0.1459784 0.05390644 0.987818 -0.169518 0.1625678 0.9720264 -0.07032829 -0.1069768 0.9917711 -0.07670539 -0.1019666 0.9918261 -0.07008045 -0.1007587 0.9924396 -0.07612651 -0.09642457 0.9924248 -0.06193178 -0.09293842 0.9937439 -0.06623685 -0.09029376 0.9937101 -0.05756562 -0.08751821 0.9944983 -0.1031346 -0.09903466 0.9897249 -0.06359505 -0.1356932 0.9887078 -0.0766021 -0.1209802 0.9896949 -0.08999055 -0.125252 0.9880352 -0.1208736 -0.1148703 0.9859991 -0.1247777 -0.1152606 0.9854671 -0.7394407 0.6553872 0.1539322 -0.9325221 0.3610991 0.003149032 -0.419878 0.2733463 0.8654387 -0.1406813 -0.07390111 0.987293 -0.09116071 -0.09984213 0.9908185 -0.0900194 -0.09984761 0.9909223 -0.06549429 -0.115361 0.9911621 -0.05908519 -0.1136444 0.9917631 -0.04976928 -0.1287043 0.9904333 -0.03670603 -0.1249552 0.9914832 -0.932597 0.3609072 0.002979338 -0.4516135 0.03884804 0.8913675 -0.2790694 0.1316778 0.9511999 -0.3371574 0.1857897 0.9229339 -0.02464956 -0.1540851 0.9877501 -0.02953332 -0.1497459 0.9882833 -0.04567003 -0.156297 0.9866536 -0.04423332 -0.170476 0.9843686 -0.05480492 -0.1513373 0.9869617 -0.04970657 -0.1253511 0.9908665 -0.07671332 -0.1346616 0.9879177 -0.08848953 -0.1244347 0.988274 -0.1107546 -0.1323307 0.9849984 -0.1463255 -0.1269894 0.9810518 -0.1361964 -0.1025077 0.9853643 -0.1583684 -0.1080073 0.9814549 -0.08835631 -0.05710101 0.9944509 -0.5425992 -0.1031048 0.8336399 -0.3281848 -0.1397686 0.9342159 -0.3281838 -0.1397686 0.9342163 -0.2539513 -0.1243314 0.9591927 -0.23924 -0.1133288 0.9643241 -0.1822215 -0.1323227 0.9743131 -0.1255686 -0.1281265 0.9837765 0.2648147 -0.03706198 0.9635869 -0.523159 -0.1636855 0.8363682 -0.4148662 -0.1491255 0.8975787 -0.6918861 -0.1796398 0.6993019 -0.3101327 -0.01897138 0.950504 -0.3030279 -0.01703876 0.9528294 -0.2471035 -0.08421361 0.9653226 -0.3447533 -0.0855953 0.9347826 -0.4188017 -0.1128271 0.9010412 -0.05878317 -0.09086132 0.9941271 -0.05886548 -0.09071397 0.9941357 -0.1044309 -0.04659759 0.9934399 -0.5945693 0.6987976 0.397705 -0.0872125 -0.04997688 0.9949353 -0.08740329 -0.04962563 0.9949362 -0.05945777 -0.08660781 0.9944666 -0.0906412 0.1012609 0.9907222 -0.1713864 0.5405095 0.8236967 -0.1714377 0.5408254 0.8234786 -0.07085651 0.01347583 0.9973955 -0.05966198 -0.04477059 0.9972141 -0.05965876 -0.04478657 0.9972136 -0.08884018 0.1010353 0.9909083 -0.04006946 -0.1289637 0.9908395 -0.04006916 -0.1289651 0.9908393 -0.05355572 -0.07328623 0.9958719 -0.05243211 -0.07955378 0.9954508 -0.05878585 -0.04492157 0.9972593 -0.204413 0.765101 0.6106029 -0.2011976 0.7649027 0.6119178 -0.09065812 0.1013452 0.990712 -0.05129283 -0.1045339 0.9931977 -0.05159765 -0.1180338 0.9916681 -0.06497889 -0.06118619 0.996009 -0.06286311 -0.07290273 0.9953559 -0.08570355 0.02298688 0.9960554 -0.08369541 0.01393955 0.9963939 -0.04396826 -0.1489973 0.9878597 -0.0906077 0.04798322 0.9947301 -0.0442143 -0.1078568 0.9931828 -0.0380131 -0.107954 0.9934289 -0.0532518 -0.1128277 0.9921866 -0.04044044 -0.1138112 0.9926789 -0.06434053 -0.1196806 0.9907255 -0.0456236 -0.1220806 0.9914711 -0.06604939 -0.1258106 0.9898532 -0.04547387 -0.129348 0.9905561 -0.04627215 -0.1294508 0.9905057 -0.03137779 -0.1441775 0.9890543 -0.03710579 -0.1439411 0.9888904 -0.0265311 -0.1562845 0.9873557 -0.1769983 -0.9810225 0.07916152 0.01093459 -0.1017396 0.994751 -0.1488288 -0.8353629 0.5291681 -0.148765 -0.8351055 0.5295918 -0.003137111 -0.1667675 0.9859913 -0.1540844 -0.8342965 0.5293462 -0.09931087 -0.6057462 0.7894358 -0.09928756 -0.6056436 0.7895174 -0.132193 -0.7481554 0.6502218 -0.05280411 -0.4045417 0.9129939 -0.0527988 -0.4045173 0.9130049 -0.05279964 -0.4045212 0.9130032 -0.01399803 -0.2141002 0.9767115 -0.03364872 -0.3149492 0.9485118 -0.01003593 -0.2147334 0.9766212 -0.01436287 -0.2327717 0.9724252 -0.01172375 -0.2144624 0.9766619 -0.01172298 -0.2144585 0.9766628 -0.01959496 -0.2325672 0.9723829 -0.01429337 -0.2142593 0.9766723 -0.0358572 -0.3148511 0.9484636 -0.03244781 -0.3006259 0.95319 -0.1562379 -0.8268356 0.540308 -0.1809954 -0.9109159 0.3707733 -0.2196195 -0.8746122 0.4322278 -0.04228639 -0.3018016 0.9524325 -0.0170859 -0.1992164 0.9798065 -0.0230953 -0.2154007 0.9762526 -0.01299124 -0.1696172 0.9854244 -0.007281959 -0.1688596 0.9856132 -0.01711779 -0.1887494 0.9818761 -0.005291879 -0.1891977 0.9819248 -0.01932996 -0.213222 0.9768124 -0.01932984 -0.2132217 0.9768127 -0.01438021 -0.1797337 0.9836102 -0.01438003 -0.179732 0.9836105 -0.9067579 -0.3613628 0.2172718 -0.9067163 -0.3607611 0.2184419 -0.4842826 -0.2077658 0.8498846 -0.6693032 -0.2755315 0.6900113 -0.4187922 -0.1128312 0.9010451 -0.5083028 -0.094343 0.8559952 -0.1549264 -0.1284909 0.9795345 -0.1544604 -0.1282225 0.9796433 -0.1294776 -0.1282901 0.9832483 -0.06419372 -0.08615726 0.9942113 -0.04531031 -0.09662443 0.994289 -3.82634e-4 -0.03776717 0.9992864 -0.6764948 0.1606837 0.718704 -0.2687289 -0.03996944 0.9623862 -0.1796848 0.002518534 0.983721 -0.106886 -0.05830669 0.9925602 -0.1075997 -0.05793493 0.9925048 -0.0694552 -0.0904119 0.9934796 -0.06888681 -0.09046852 0.993514 -0.04982161 -0.1093949 0.992749 -0.04586267 -0.1085314 0.9930346 -0.03830105 -0.12596 0.9912957 -0.03342711 -0.1239679 0.991723 -0.0254302 -0.1238557 0.9919744 -0.03787118 -0.1278389 0.9910716 -0.02094519 -0.1285253 0.9914851 -0.04420971 -0.1342697 0.9899582 -0.01781255 -0.1366198 0.9904634 -0.04401546 -0.1482291 0.9879731 -0.01176351 -0.1440194 0.989505 -0.03012615 -0.1630948 0.9861504 -0.02430152 -0.1633311 0.9862719 -0.02666145 -0.1687039 0.9853062 -0.2346433 -0.9683676 0.08489263 0.02228754 -0.2709804 0.9623268 0.4023828 0.7917145 0.459648 -0.04624664 0.998768 -0.01799768 0.3948704 0.8391501 0.3740381 0.3968726 0.8172762 0.4177939 0.3981623 0.5866999 0.7051596 0.3872245 0.8203001 0.4209097 0.1726195 -0.05424171 0.9834939 0.2055125 -0.0180788 0.9784874 0.1888199 -0.07993054 0.9787533 0.2349032 0.03358948 0.9714383 0.3012495 0.1838464 0.9356545 0.327091 0.3023039 0.8953346 0.3776151 0.4861042 0.788105 0.3870973 0.8210713 0.4195204 0.01836842 -0.2876759 0.9575517 0.04614758 -0.2788863 0.9592147 0.09415423 -0.2307742 0.9684412 0.1030259 -0.1968268 0.9750102 0.0651735 -0.2128631 0.974906 0.1392419 -0.1667978 0.9761097 0.00853908 -0.3163919 0.9485902 -0.05339711 -0.3586331 0.93195 -0.05539089 -0.3367705 0.9399561 -0.1219234 -0.4453293 0.8870267 -0.05772107 -0.3516165 0.934363 -0.05772143 -0.3516182 0.9343623 -0.1645659 -0.3964203 0.9031993 -0.164566 -0.396421 0.903199 -0.2425044 -0.5135534 0.8230763 -0.2586598 -0.4854897 0.8351018 -0.2791729 -0.6362427 0.7192063 -0.29044 -0.7646815 0.5752451 -0.3074849 -0.6521859 0.6928973 -0.2746353 -0.9583615 -0.07822132 -0.2413185 -0.9482821 -0.2062193 -0.24997 -0.8864403 0.3895364 -0.312209 -0.836592 0.4501549 -0.3078426 -0.9172455 0.252772 -0.3023469 -0.9309801 0.2046031 -0.2923585 -0.9482363 0.1239937 -0.5755247 -0.8163027 0.0492075 0.04226988 -0.3562566 0.9334316 0.003012597 -0.3928496 0.9195978 0.1831375 -0.01156103 0.9830194 0.2655642 0.2659372 0.9266893 0.2760993 0.4024687 0.8728048 0.2760991 0.4024668 0.8728057 0.1831408 -0.01154959 0.9830188 0.1831412 -0.01154774 0.9830188 0.18716 -0.07439774 0.9795082 0.07422375 -0.2945444 0.952751 0.07422453 -0.2945414 0.9527518 0.07078921 -0.2473119 0.9663467 0.04181939 -0.2832005 0.9581485 0.04181975 -0.2831985 0.9581491 0.3225733 0.7380552 0.5926391 0.3031763 0.5737106 0.7608814 0.3092495 0.7421519 0.5946218 0.2875883 0.9196571 0.2674395 0.3283761 0.7361571 0.5918123 -0.2080976 -0.3708121 0.9050932 -0.1279013 -0.4051359 0.9052658 -0.1537615 -0.5514878 0.8198895 -0.1963767 -0.597126 0.7777383 -0.2193918 -0.7933318 0.5678837 -0.2325283 -0.8314356 0.5046242 -0.2307745 -0.9424431 0.2419587 -0.2308259 -0.9590147 0.1643478 -0.2383292 -0.8906599 0.3872004 -0.2346437 -0.9683675 0.08489274 -0.09113264 -0.9724768 -0.2144377 -0.1258461 -0.9755563 0.1801461 -0.100288 -0.9919071 0.07786256 -0.06258493 -0.9740573 -0.2174751 -0.06258529 -0.9740579 -0.2174727 -0.1223281 -0.9691158 0.214127 -0.1223285 -0.969115 0.2141304 -0.1223278 -0.9691163 0.214125 -0.1536692 -0.6684045 0.7277509 -0.1320869 -0.8931067 0.4300156 -0.1303572 -0.8813276 0.454168 -0.1291123 -0.9164019 0.3788633 -0.1536691 -0.6684082 0.7277474 -0.1519458 -0.6636207 0.7324753 -0.1501807 -0.6697371 0.7272539 -0.01374661 -0.4232639 0.9059021 -0.02718383 -0.5128698 0.8580359 -0.07549232 -0.4083261 0.9097091 -0.09795439 -0.4868202 0.8679925 -0.09998124 -0.5093804 0.8547136 -0.07967811 -0.4938379 0.8658958 -0.1501807 -0.6697369 0.7272539 0.3240215 0.8189107 0.4737039 0.3138747 0.9122201 0.2633197 0.3367936 0.6094405 0.7177412 0.3299386 0.564882 0.7563391 0.2958592 0.3137001 0.9022526 0.2773327 0.2618451 0.9244045 0.2155348 -0.021573 0.9762579 0.1724519 -0.06931465 0.9825761 0.1375935 -0.2087073 0.9682506 0.08150678 -0.2510657 0.9645323 0.06860131 -0.3054221 0.9497427 0.01121306 -0.3452127 0.9384576 0.004072308 -0.3799098 0.9250146 -0.05076789 -0.4178694 0.9070875 -0.05944895 -0.4697579 0.8807914 -0.1083256 -0.5060824 0.8556554 -0.1230859 -0.626796 0.7694003 -0.1562032 -0.6619536 0.733088 -0.1669574 -0.8539761 0.4927982 -0.1757314 -0.8808857 0.4394983 -0.1653528 -0.9744865 0.1517719 -0.1645282 -0.9821919 0.09071648 -0.1215379 -0.9414206 -0.3145726 -0.1409984 -0.9733625 0.1807896 0.07874059 -0.3276051 -0.941528 0.2856066 0.9465875 0.1496697 0.01786464 -0.4445468 -0.8955775 -0.1367542 -0.8418449 -0.5221068 0.0160818 0.5052632 -0.8628154 0.03234273 0.3001691 -0.9533375 0.0193811 0.2479385 -0.9685819 0.02690893 0.2709828 -0.962208 0.04334229 0.2404332 -0.9696975 0.05491602 0.1718697 -0.9835879 0.006251931 0.3698824 -0.9290575 0.01589637 0.4854716 -0.8741079 -0.01799386 0.4556388 -0.8899828 -0.01950246 0.4541314 -0.8907212 -0.01585137 0.4529539 -0.891393 0.01608514 0.5052697 -0.8628116 0.07113164 0.6725647 -0.7366119 0.07113188 0.672565 -0.7366116 0.1944705 0.8575992 -0.4761354 0.4052519 0.6621205 0.6303707 0.3652123 0.9292404 0.05596578 0.1944579 0.8575868 -0.4761629 0.2792594 0.9273805 -0.2489572 0.283864 0.929166 -0.2367949 0.3194803 0.9387664 -0.1290353 0.0853812 0.9935553 -0.07455146 -0.223194 -0.9324345 -0.2841663 -0.1288797 -0.7720565 -0.6223495 -0.2012957 -0.9120947 -0.3571602 -0.08854109 -0.72918 -0.6785699 -0.1103187 -0.7647533 -0.6348088 0.007079064 -0.4736481 -0.8806858 0.0103414 -0.449647 -0.8931465 -0.1103171 -0.76475 -0.6348131 -0.09901672 0.07377815 -0.992347 0.1170119 -0.009514451 -0.9930849 0.07265967 -0.1550866 -0.9852253 -0.03746837 -0.05823987 -0.9975993 0.05986702 -0.1951942 -0.9789358 0.08794808 -0.4108561 -0.9074482 0.05158358 -0.6432987 -0.7638756 0.01602047 -0.7671651 -0.6412495 0.08794671 -0.4108642 -0.9074448 0.08794903 -0.4108559 -0.9074483 0.1009185 -0.3666407 -0.9248731 0.1031739 0.04645264 -0.993578 0.1093342 -0.02852421 -0.9935957 0.1372012 0.03380197 -0.9899663 0.1372004 0.0337944 -0.9899666 0.1008455 0.2744089 -0.9563106 0.1263349 0.1730527 -0.9767764 0.1636059 0.2484509 -0.9547278 0.1031736 0.04645127 -0.9935781 0.01601928 -0.7671696 -0.6412444 0.1004869 -0.3275386 -0.9394791 -0.01201301 -0.7655658 -0.6432456 -0.1367557 -0.8418446 -0.5221069 -0.1259478 -0.8034912 -0.5818411 -0.09832161 -0.7275883 -0.6789316 -0.08378517 -0.6717994 -0.7359794 -0.02040964 -0.4675775 -0.8837165 -0.01135182 -0.3968382 -0.9178184 0.05632418 -0.1498742 -0.9870994 0.04198276 -0.06629347 -0.9969165 0.06434637 0.01543581 -0.9978082 0.06374365 0.1364238 -0.9885976 0.02318716 0.08567833 -0.9960529 0.05491501 0.1718663 -0.9835885 0.244255 0.9385169 -0.2439782 0.2622788 0.9498681 -0.1701777 0.3809767 0.6729243 0.6340579 0.3578975 0.9236371 0.1371271 0.1006767 0.8088411 -0.5793448 0.1492156 0.8166383 -0.5575273 0.138635 0.8197365 -0.5557087 0.154978 0.8576124 -0.4903905 0.1386211 0.8623394 -0.4869856 0.1088385 0.8064998 -0.5811302 0.200816 0.9454033 -0.2566813 0.2008146 0.9454022 -0.2566865 0.2266464 0.9601463 -0.1635553 0.2893046 0.9421848 0.1690882 0.2878227 0.9442448 0.1598746 0.2888262 0.9423187 0.1691591 0.2888276 0.9423162 0.1691704 0.05531114 0.5289995 -0.8468177 0.05531203 0.5290011 -0.8468167 0.0243954 0.4824898 -0.8755619 0.05485242 0.6515477 -0.7566218 0.05485248 0.651548 -0.7566217 0.002639353 0.6032607 -0.7975397 0.04346865 0.590826 -0.8056271 0.03628635 0.6564965 -0.7534559 0.0543527 0.6507921 -0.7573081 0.100679 0.8088451 -0.5793388 -0.1212467 -0.8041528 -0.5819256 -0.1154127 -0.912232 -0.393081 -0.04468762 -0.6772935 -0.7343545 -0.03709548 -0.6337816 -0.7726221 0.01548355 -0.4028677 -0.9151272 0.01832711 -0.3483104 -0.9372001 0.07258248 -0.07647556 -0.9944261 0.05634021 -0.01005893 -0.9983609 0.08450716 0.1285476 -0.9880962 0.05671268 0.2004122 -0.9780688 0.06942164 0.254707 -0.9645231 0.03978228 0.3262561 -0.944444 0.006251394 0.3698809 -0.9290581 0.009890198 0.374873 -0.9270234 0.007842123 0.3756172 -0.9267418 0.0762127 0.4549421 -0.8872539 0.148909 0.492949 -0.8572208 0.1489055 0.4929462 -0.8572229 0.1008454 0.2744082 -0.9563108 0.1291328 0.3431233 -0.9303715 0.09422338 0.3048869 -0.9477162 0.0846945 0.397 -0.9139026 0.09337866 0.436957 -0.8946223 -0.005608022 0.2170885 -0.9761359 -0.0352385 0.2910729 -0.9560517 -0.07192844 0.341515 -0.93712 -0.139787 0.3640248 -0.9208396 -0.0842719 0.3402633 -0.9365464 -0.08425825 0.3402609 -0.9365485 -0.07192742 0.3380539 -0.9383741 -0.08479332 0.3283255 -0.9407511 -0.1395131 0.3582792 -0.9231317 -0.1175477 0.3584491 -0.9261192 -0.1175454 0.3584488 -0.9261197 -0.1761177 0.47693 -0.8611157 -0.1408442 0.5215945 -0.8414881 -0.1802558 0.5276638 -0.8301077 -0.1413041 0.5345714 -0.8332266 -0.1255815 0.5272102 -0.8404039 0.006874024 0.5110375 -0.8595309 0.03416216 0.5352566 -0.8439984 0.07581007 0.4782263 -0.8749586 0.1447023 0.4802881 -0.8650923 0.07972282 0.5212556 -0.8496686 0.03410619 0.5054808 -0.8621634 0.07702887 0.4916406 -0.8673847 0.006872773 0.5110374 -0.8595311 -0.1409412 0.5242657 -0.8398101 -0.07911115 0.5141463 -0.8540463 -0.1252197 0.5230854 -0.8430312 -0.07918727 0.5667891 -0.8200484 0.03415811 0.5793377 -0.8143715 -0.07918745 0.5662698 -0.8204071 -0.07918632 0.5662695 -0.8204075 -0.1168757 0.3957682 -0.9108829 -0.1343473 0.3968088 -0.9080162 -0.1413096 0.3979105 -0.9064761 -0.1343982 0.3995653 -0.9067992 -0.1741375 0.4545016 -0.8735586 -0.13515 0.4483531 -0.8835802 -0.1351525 0.4483545 -0.8835791 0.001225054 0.1791168 -0.9838271 0.001225113 0.1791169 -0.983827 0.001098394 0.1784333 -0.9839514 0.005795478 0.1900224 -0.9817626 0.005795478 0.1900224 -0.9817627 -0.01285195 0.2183488 -0.9757862 -0.005635678 0.227256 -0.9738187 -0.0177896 0.2342392 -0.9720162 0.005795598 0.1900225 -0.9817627 -0.006420195 0.1912116 -0.9815279 -0.01292568 0.1971589 -0.9802864 -0.006564915 0.1968427 -0.9804132 -0.01292341 0.1978754 -0.9801419 -0.00703144 0.2151632 -0.9765529 -0.005607485 0.2170885 -0.9761359 0.1093035 0.3871706 -0.9155064 0.1093025 0.3871703 -0.9155064 0.09669965 0.3563706 -0.9293272 0.1401739 0.4145078 -0.8991855 0.1184245 0.4514372 -0.8844094 0.07580965 0.4782264 -0.8749585 -0.00466746 0.2465014 -0.9691312 -0.004668116 0.2465015 -0.9691312 -0.01765495 0.2489822 -0.9683471 -0.01765483 0.2489824 -0.9683471 -0.004234373 0.2830986 -0.9590814 -0.07182759 0.2929454 -0.9534274 -0.03523868 0.291073 -0.9560517 -0.0352391 0.291073 -0.9560517 0.002695798 -0.3927369 0.9196469 7.48674e-4 -0.1731835 0.9848892 0.02535074 -0.412132 0.9107714 0.0984947 -0.5089557 0.8551392 0.06500548 -0.5151686 0.8546202 0.0650053 -0.5151684 0.8546203 0.1087735 -0.5602052 0.8211812 0.1087728 -0.5602051 0.8211813 0.07108259 -0.5687159 0.8194568 0.01208466 -0.5241594 0.8515344 -0.008262455 -0.519588 0.8543771 -0.008263468 -0.5195877 0.8543772 0.01433205 -0.3054841 0.9520894 0.01879262 -0.306604 0.9516516 0.01435059 -0.3057376 0.9520077 0.01935321 -0.3096237 0.9506622 1.6413e-4 -0.3260747 0.945344 0.02326309 -0.3306013 0.9434838 0.001164138 -0.3318899 0.9433174 0.03760242 -0.377654 0.9251829 0.01867061 -0.373125 0.9275932 0.04684025 -0.4146044 0.9087954 0.04684048 -0.4146045 0.9087954 -0.001461565 -0.1748828 0.9845882 -0.001461684 -0.1748828 0.9845882 0.00181657 -0.1699766 0.9854464 0.02067238 -0.2480939 0.9685154 0.01395982 -0.2458826 0.9691991 0.006443142 -0.2376682 0.9713249 0.01412063 -0.239138 0.9708828 6.33437e-4 -0.1786354 0.9839151 6.33432e-4 -0.1786354 0.9839151 -0.001433134 -0.178498 0.9839392 0.01492756 -0.2046604 0.9787192 0.006763577 -0.2151775 0.9765515 0.006763458 -0.2151775 0.9765516 -0.03223252 -0.4165588 0.9085371 -0.02203601 -0.4476956 0.8939145 -0.0455513 -0.4527793 0.8904583 -0.004832267 -0.4667938 0.8843529 -0.04509603 -0.4806196 0.875769 -0.008274137 -0.517782 0.8554726 -0.04463332 -0.5060673 0.8613383 -0.008043527 -0.5515838 0.8340807 0.01527184 -0.5506002 0.8346294 0.01527267 -0.5506005 0.8346292 0.03425192 -0.2598625 0.965038 0.03425192 -0.2598625 0.965038 0.02052307 -0.2729384 0.9618126 0.03456759 -0.2794331 0.9595426 0.02050143 -0.2764809 0.9608008 0.03469204 -0.2811828 0.9590269 0.03469198 -0.2811828 0.959027 -0.02387374 -0.1192649 0.9925754 0.09185749 0.7052872 0.7029453 0.1062905 0.978712 -0.1755708 0.06053096 0.6852094 -0.7258265 0.07586485 0.8702626 0.4867107 -0.01950931 0.08657485 0.9960544 -0.02737087 0.2882159 0.9571742 -0.134272 0.539358 0.8313025 -0.1344046 0.5403824 0.8306156 -0.1343665 0.5400892 0.8308125 -0.0170077 0.4177317 -0.9084112 -0.01699697 0.4176511 -0.9084485 -0.0628826 0.09715533 0.9932808 -0.1193787 0.5395928 0.8334196 -0.1193426 0.5392713 0.833633 -0.06287151 0.09707731 0.9932891 -0.03443634 -0.1180155 0.9924145 -0.1335168 0.5403941 0.8307511 0.009028136 -0.3607054 0.9326361 -0.08581638 0.9648659 0.2483333 -0.07144469 0.4784053 0.875228 -0.03400534 0.04937052 0.9982014 -0.05637001 0.0528261 0.9970115 -0.1159839 0.5392651 0.8341109 -0.1472992 0.9826552 0.1126573 -0.1311284 0.9842537 0.1185331 -0.02388328 -0.01452082 0.9996093 0.02632427 0.5195752 0.8540191 -0.001903355 0.5233865 0.8520932 -0.009428858 0.365063 0.930935 -0.01411408 0.2190625 0.9756088 0.02556884 0.9353253 0.3528637 -0.01662516 0.9394962 0.3421557 -0.0246675 0.06081676 0.997844 -0.02296757 -0.01127219 0.9996726 -0.0207355 0.05784624 0.9981101 -0.0260089 0.05885654 0.9979276 -0.02601712 0.05932033 0.9978999 -0.02400892 0.05897182 0.9979709 -0.01783037 0.9983435 -0.05470162 -0.01782929 0.9983436 -0.05470144 -0.0406531 0.4990321 0.8656294 0.005301117 0.2752352 0.9613623 0.009916007 0.274656 0.9614915 0.03612387 0.5866374 0.8090437 0.06569212 0.8703773 0.4879835 0.05074071 0.7147567 0.6975301 0.04844832 0.7148203 0.697628 0.02903985 0.4971371 0.8671859 0.03170162 0.4969149 0.8672201 0.1660206 0.98592 -0.01997059 0.1304981 0.988114 0.08124667 0.1341943 0.9843116 0.1145535 0.1024757 0.9868927 0.1246656 0.08725613 0.9782159 0.1883615 0.08403754 0.943566 0.320345 0.07628315 0.9437932 0.3216133 0.06558179 0.8392474 0.5397803 0.0633369 0.8392979 0.5399699 0.04508501 0.6452357 0.7626523 0.04547572 0.645213 0.7626482 0.02619695 0.4193056 0.9074671 0.03044664 0.5700584 0.8210398 0.01323217 0.3612942 0.932358 0.01471924 0.3803675 0.9247183 0.001644253 0.2160616 0.9763784 0.003846347 0.2452993 0.9694398 -0.008657157 0.08432495 0.9964007 -0.004137516 0.1501942 0.9886479 -0.01585686 -0.01280933 0.9997922 -0.0147857 0.005216479 0.999877 0.07848465 0.9314879 0.3552049 0.08498883 0.9884485 0.1254856 0.07545536 0.9066709 0.4150356 0.06256359 0.7780014 0.6251395 0.07004374 0.8675205 0.4924452 0.05983877 0.6840974 -0.7269319 0.08548343 0.984574 0.1526643 0.08831036 0.9958845 0.02038264 0.08803194 0.9959083 0.02042239 0.08759105 0.9490371 -0.3027477 0.08092314 0.8741114 -0.4789372 0.09046351 0.9921889 -0.08589315 0.09034186 0.9957182 -0.01958352 0.0871104 0.9659772 -0.2435153 0.08834987 0.9778079 -0.1899627 0.08835136 0.9778065 -0.1899697 0.08866477 0.9793273 -0.1818145 0.08950495 0.9802945 -0.1761006 0.1021477 0.9907861 -0.0889312 0.08911496 0.9715641 -0.2193668 0.08809673 0.9717163 -0.2191036 0.08955544 0.9821128 -0.1656331 0.1622518 0.982924 -0.08680325 0.1802068 0.9812863 0.06784307 0.1484231 0.977639 -0.1489713 0.162245 0.9829232 -0.08682554 0.1062927 0.9787116 -0.1755714 0.1062912 0.9787124 -0.1755683 0.1100116 0.9858976 -0.1261098 0.1169812 0.9891226 -0.08917325 0.08835369 0.9778074 -0.1899638 0.08781027 0.9928616 0.08071613 0.08846038 0.9908553 -0.1018846 0.08982414 0.9907108 -0.1020961 0.08982235 0.9910278 -0.09897387 0.08922481 0.9821548 -0.165562 0.08658993 0.988343 0.1252209 0.08798199 0.9959391 -0.01908832 0.08711093 0.9659772 -0.2435154 0.08711093 0.9659771 -0.2435155 0.08108323 0.904614 -0.4184485 0.08807903 0.9563502 -0.2786328 0.08814507 0.9462726 -0.3111248 0.06983536 0.7214888 -0.6888955 0.06983608 0.7214895 -0.6888946 -0.01680153 0.1250013 0.9920144 -0.01576077 0.1248216 0.992054 -0.01001948 0.1965156 0.9804494 0.08859235 0.6514023 0.7535427 0.05564343 0.6516222 0.7565 4.96745e-4 0.1408681 0.9900283 0.01332837 0.3410785 0.9399403 0.005747973 0.3416645 0.9398045 -0.03356218 -0.5090391 0.8600888 -0.03356242 -0.5090391 0.8600888 -0.01431101 0.1601017 0.9869968 -0.01431065 0.1601017 0.9869968 0.02105647 0.3831661 0.9234395 0.02581566 0.4980008 0.8667922 0.07513082 0.4966621 0.8646861 0.0928232 0.7763859 0.623385 0.1053685 0.05058622 0.9931458 0.1199978 0.1804966 0.9762281 0.2420002 0.9541187 0.1763333 0.1958953 0.946371 0.2569182 0.2177157 0.2911511 0.9315745 0.2177153 0.2911509 0.9315745 0.1053693 0.05058622 0.9931457 0.1217241 0.1804116 0.9760301 0.1524131 0.7058048 0.6918162 0.1528666 0.8235511 0.546256 0.1003954 0.8234336 0.5584602 0.0996589 0.8055722 0.584056 0.06909316 0.8055438 0.5884941 0.06182384 0.6829513 0.7278429 0.04479682 0.6830175 0.7290269 0.03248947 0.5121191 0.8582998 0.02124059 0.5125628 0.858387 -0.04328197 -0.08108031 0.9957674 -0.06215953 0.09701126 0.9933403 -0.04168134 -0.04775118 0.9979892 -0.04535931 -0.0229066 0.998708 -0.04788118 -0.04671889 0.9977598 -0.04788142 -0.0467236 0.9977596 -0.0238738 -0.1192649 0.9925754 -0.02449262 -0.05108743 0.9983938 -0.034159 0.05076813 0.9981262 -0.02345144 0.04907107 0.99852 -0.05285435 0.9645439 0.2585757 -0.0361486 0.2894802 0.9565012 -0.01800209 -0.0848006 0.9962354 -0.03671407 0.3138427 0.9487649 -0.01417106 -0.1297872 0.9914407 0.1857348 0.9633054 -0.1937656 0.1732949 0.9522645 -0.2513189 0.2425428 0.9539967 0.1762477 0.1660106 0.9539409 -0.2498747 0.2158095 0.975992 -0.02942973 0.1775377 0.9581883 -0.2244004 0.1857425 0.9633095 -0.1937379 0.1410381 0.9665182 -0.2143611 0.1409621 0.9665235 -0.2143877 0.1409713 0.9665216 -0.2143897 0.05089151 0.6851621 0.7266106 0.04284721 0.5853123 0.8096749 0.0417872 0.5854021 0.8096655 0.0596947 0.7781662 0.625215 0.05115741 0.6731827 0.7377045 0.07365465 0.9067636 0.4151565 0.07982212 0.9705751 0.2271836 0.06780606 0.8551499 0.5139269 0.05553257 0.8558988 0.514153 0.06407773 0.9407021 0.3331269 0.04178828 0.9460402 0.3213437 0.07117354 0.8864262 -0.4573654 0.07284986 0.8860713 -0.4577886 -0.01871907 0.07881993 0.9967131 0.03392231 0.5867372 0.8090666 0.01583898 0.3736977 0.9274153 0.01880943 0.3733812 0.9274873 0.01130068 0.2861839 0.9581081 9.82173e-4 0.1492924 0.9887926 0.02380198 0.4195753 0.9074084 0.01001757 0.2442998 0.969648 0.02521818 0.4217166 0.906377 0.02207547 0.3793385 0.9249946 0.04790031 0.6734439 0.7376849 0.03970801 0.5690779 0.8213243 0.05537337 0.7426287 0.6674101 0.04542315 0.7433859 0.6673185 0.06626933 0.9580338 0.2788903 0.02781105 0.965732 0.2580471 -0.02221173 0.03816783 0.9990244 -0.02621656 -0.09362596 0.9952622 0.2419984 0.9541217 0.1763198 0.2452824 0.9485411 0.2002659 0.1911798 0.9590126 0.2091537 0.2057998 0.9188682 0.3366417 0.1488203 0.9248104 0.3501118 0.1503599 0.914448 0.3757352 0.1048182 0.9155163 0.3883852 0.1047247 0.900737 0.4215514 0.0805149 0.9010528 0.4261705 0.08444648 0.9733676 0.2131296 0.04711288 0.6672524 0.7433402 0.0402553 0.6673465 0.7436587 0.008040785 0.3258205 0.9453975 0.004519999 0.3261611 0.9453034 -0.01723045 0.06454217 0.9977662 -0.01343166 0.06391274 0.9978652 -0.02888077 -0.1593595 0.9867981 -0.02627944 -0.1435606 0.9892926 -0.01683694 -0.07492351 0.9970471 -0.0168367 -0.07492357 0.9970472 -0.0167188 -0.08990502 0.99581 -0.02370578 -0.05202317 0.9983645 -0.02489608 -0.05183255 0.9983454 -0.02326798 -0.08288341 0.9962877 -0.02326816 -0.08288335 0.9962876 -0.0239166 -0.08353948 0.9962174 -0.02846252 -0.1431372 0.9892935 -0.02574497 -0.08858293 0.995736 -0.02310049 -0.08916771 0.9957488 -0.002741396 0.1642252 0.9864191 -0.005903542 0.1646898 0.9863277 0.02104961 0.469976 0.8824282 0.02308267 0.4698414 0.882449 0.05320936 0.7739147 0.6310507 0.06533014 0.7738242 0.6300223 0.08314371 0.9475905 0.3084791 0.1092064 0.9467705 0.3028196 0.1056457 0.9772326 0.183999 0.1013686 0.9924354 0.06925719 0.08959412 0.9933568 0.07221615 0.08890873 0.9852597 0.1461456 0.0838223 0.9855594 0.147128 0.07827872 0.9367893 0.3410252 0.07626783 0.93686 0.3412867 0.06275224 0.802546 0.593281 0.06426376 0.8024821 0.5932053 0.07785946 0.9315169 0.3552662 0.07239097 0.8674131 0.4922947 0.08564287 0.9845636 0.1526428 0.08601588 0.9878442 0.1294803 0.08303689 0.9646418 0.2501422 0.0796402 0.9648451 0.2504624 0.08332061 0.9932054 0.08124601 0.0617206 0.6839234 -0.7269383 0.08146995 0.956847 -0.2789383 0.06053102 0.6852095 -0.7258264 0.09904897 -0.3030141 0.9478248 -0.0204007 -0.1572981 0.9873404 0.0976783 -0.3025502 0.9481151 -0.03894066 -0.2586854 0.9651765 -0.02195364 -0.1350096 0.990601 -0.02285754 -0.131827 0.9910091 -0.03501844 -0.1298096 0.9909204 -0.0228576 -0.1318274 0.9910091 -0.0246846 -0.1345448 0.9906 -0.01711636 -0.1743192 0.9845405 -0.01947683 -0.1704497 0.985174 -0.01251572 -0.196323 0.9804594 -0.02156794 -0.1945298 0.9806595 -0.01153647 -0.2363085 0.9716096 -0.02926272 -0.2323746 0.972186 -0.007793605 -0.1480142 0.9889545 -0.01724898 -0.1708546 0.9851453 -0.01331353 -0.1362515 0.9905849 -0.02226507 -0.148053 0.9887288 -0.03776407 -0.1905287 0.9809549 -0.03776389 -0.1905288 0.980955 -0.03363609 -0.1606218 0.9864427 -0.02785032 -0.1845808 0.9824227 -0.02785015 -0.1845808 0.9824226 0.2074458 0.9751547 0.07771438 0.1832411 0.3435264 0.9210931 0.1955626 0.4783767 0.8561022 0.2452108 0.4127228 0.8772295 0.1732575 -0.008114695 0.9848431 0.2023122 0.1774095 0.9631177 0.1481473 0.1930705 0.9699361 0.1383752 0.02261567 0.9901216 0.0790072 0.03426295 0.996285 0.07766407 -0.07088583 0.9944564 0.009722888 -0.06082254 0.9981012 0.01238471 -0.1323769 0.991122 -0.04214632 -0.1223493 0.9915919 -0.03748726 -0.1760731 0.983663 -0.05503588 -0.1725095 0.9834692 0.1518236 0.9179642 0.3664579 0.1518236 0.9179642 0.3664578 0.1380366 0.5823917 0.8011028 0.1527015 0.5815364 0.7990605 0.04217582 0.1843714 0.9819512 0.05604946 0.5648464 0.8232903 0.05604952 0.5648464 0.8232904 0.172743 0.2929068 0.940407 0.119017 0.3008821 0.9462056 0.09960007 0.1421527 0.984821 0.03927159 0.1476224 0.9882637 0.02354842 0.01263403 0.9996429 -0.01809716 0.01873666 0.9996607 -0.03027319 -0.04279786 0.998625 -0.05593013 -0.2550168 0.9653177 -0.0525546 -0.262616 0.9634681 -0.04570955 -0.2641155 0.9634073 -0.04489976 -0.2662599 0.962855 -0.002505779 -0.2753897 0.9613294 -0.003716528 -0.2712014 0.9625155 0.04830461 -0.2816751 0.9582931 0.04260259 -0.2519791 0.9667945 0.08514124 -0.2622442 0.9612382 0.07550227 -0.1458216 0.9864256 0.1053501 -0.1551097 0.9822638 0.1396098 -0.09908074 0.985237 0.17326 -0.008101344 0.9848428 0.1732596 -0.008103191 0.9848428 -0.0200113 -0.3045614 0.9522824 -2.9186e-4 -0.3234184 0.9462561 -0.03052383 -0.3168457 0.9479858 0.008173763 -0.372305 0.9280744 -0.02022957 -0.3673406 0.9298665 0.03028804 -0.4406465 0.8971695 0.01660746 -0.4378913 0.8988747 0.0350486 -0.4678794 0.8830972 -0.008383631 -0.5009917 0.8654115 0.01597106 -0.4819547 0.8760505 0.06123059 -0.4820227 0.8740165 0.0612303 -0.4820227 0.8740165 0.04267603 -0.496513 0.8669795 0.06589829 -0.5230237 0.8497668 -0.008382439 -0.500992 0.8654113 0.01426875 -0.2732999 0.9618231 0.02350926 -0.408249 0.9125679 0.001866996 -0.4010277 0.9160641 0.02827787 -0.4301726 0.9023036 -0.008721172 -0.4434828 0.8962404 -0.008722126 -0.4434826 0.8962405 -0.001460909 -0.1749774 0.9845714 -0.008349955 -0.1738669 0.9847337 -0.01009041 -0.1467636 0.9891201 -0.01267683 -0.1471909 0.9890269 0.2539289 0.7576063 0.6012925 0.2174368 0.9730727 0.07648968 0.2678766 0.7539691 0.5998106 0.2513129 0.4638515 0.8495197 0.2588919 0.7563686 0.6007341 0.2452108 0.4127215 0.8772301 -0.02226543 -0.1480529 0.9887288 -0.019535 -0.1641003 0.9862503 -0.02201044 -0.1636033 0.9862806 -0.0206834 -0.1642329 0.9862047 -0.03056025 -0.2101475 0.977192 -0.02849799 -0.2106103 0.9771546 -0.0374971 -0.245911 0.9685668 0.09767866 -0.302548 0.9481158 0.09795206 -0.3053556 0.9471871 0.04512435 -0.2876847 0.9566615 0.07121473 -0.3594239 0.930453 0.02410441 -0.3446835 0.9384095 0.04246389 -0.4236666 0.9048224 0.04085624 -0.4232559 0.9050885 0.03475463 -0.4070088 0.9127628 0.01380687 -0.4023956 0.9153618 -0.003303885 -0.3662435 0.9305133 -0.02085065 -0.3623086 0.931825 -0.04218012 -0.324386 0.9449838 -0.02918004 -0.3272764 0.944478 -0.0507974 -0.2923945 0.9549476 -0.02052158 -0.2989177 0.9540583 -0.03849554 -0.2706589 0.9619054 -0.0019809 -0.2784197 0.9604575 -0.00142008 -0.1801435 0.9836393 -0.00142014 -0.1801435 0.9836394 -0.006789624 -0.1832467 0.9830435 0.00703603 -0.1957626 0.9806261 -0.01252645 -0.1922801 0.9812602 0.006649971 -0.2231851 0.9747534 0.00665009 -0.2231851 0.9747534 0.02053505 -0.2710319 0.9623513 0.02053594 -0.2710322 0.9623512 -0.002233624 -0.2688096 0.9631908 0.01325631 -0.2906564 0.9567357 0.01325637 -0.2906564 0.9567357 0.02082479 -0.2198225 0.9753176 -0.003697276 -0.2319648 0.9727172 -0.01190912 -0.2524425 0.9675386 -0.01909661 -0.2508603 0.967835 -0.01910674 -0.2531958 0.9672264 -0.04416835 -0.2477969 0.9678047 -0.04342156 -0.2058852 0.9776123 -0.05102735 -0.2042871 0.9775803 -0.04439169 -0.04846471 0.997838 -0.02882444 -0.05121475 0.9982716 + + + + + + + + + + + + + + + 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 +

0 0 1 0 2 0 3 1 4 1 5 1 5 2 4 2 6 2 5 3 6 3 2 3 2 4 6 4 7 4 2 5 7 5 0 5 8 6 9 6 3 6 3 7 9 7 10 7 3 8 10 8 4 8 11 9 12 9 13 9 14 10 15 10 16 10 17 11 18 11 16 11 16 12 18 12 19 12 16 13 19 13 14 13 20 14 21 14 17 14 17 15 21 15 22 15 17 16 22 16 18 16 13 17 23 17 11 17 11 18 23 18 24 18 11 19 24 19 8 19 8 20 24 20 25 20 8 21 25 21 9 21 26 22 27 22 28 22 28 23 27 23 29 23 28 24 29 24 12 24 12 25 29 25 30 25 12 26 30 26 13 26 14 27 31 27 15 27 15 28 31 28 32 28 15 29 32 29 26 29 26 30 32 30 33 30 26 31 33 31 27 31 34 32 35 32 36 32 36 33 35 33 37 33 36 34 37 34 38 34 39 35 40 35 34 35 34 36 40 36 41 36 34 37 41 37 35 37 37 38 42 38 38 38 38 39 42 39 43 39 38 40 43 40 20 40 20 41 43 41 44 41 20 42 44 42 21 42 45 43 46 43 39 43 39 44 46 44 47 44 39 45 47 45 40 45 48 46 49 46 45 46 45 47 49 47 50 47 45 48 50 48 46 48 0 49 51 49 1 49 1 50 51 50 52 50 1 51 52 51 53 51 53 52 52 52 54 52 53 53 54 53 48 53 48 54 54 54 55 54 48 55 55 55 49 55 56 56 57 56 1 56 1 57 57 57 2 57 57 58 58 58 2 58 2 59 58 59 59 59 2 60 59 60 5 60 5 61 59 61 60 61 5 62 60 62 3 62 3 63 60 63 61 63 3 64 61 64 8 64 8 65 61 65 62 65 8 66 62 66 11 66 11 67 62 67 63 67 11 68 63 68 12 68 12 69 63 69 64 69 12 70 64 70 28 70 28 71 64 71 65 71 28 72 65 72 26 72 26 73 65 73 66 73 26 74 66 74 15 74 15 75 66 75 67 75 15 76 67 76 16 76 16 77 67 77 68 77 16 78 68 78 17 78 17 79 68 79 69 79 17 80 69 80 20 80 20 81 69 81 70 81 20 82 70 82 38 82 38 83 70 83 71 83 38 84 71 84 36 84 36 85 71 85 72 85 36 86 72 86 34 86 34 87 72 87 73 87 34 88 73 88 39 88 39 89 73 89 74 89 39 90 74 90 45 90 45 91 74 91 75 91 45 92 75 92 48 92 48 93 75 93 56 93 48 94 56 94 53 94 53 95 56 95 1 95 76 96 77 96 51 96 51 97 77 97 52 97 77 98 78 98 52 98 52 99 78 99 79 99 52 100 79 100 54 100 54 101 79 101 80 101 54 102 80 102 55 102 55 103 80 103 81 103 55 104 81 104 49 104 49 105 81 105 82 105 49 106 82 106 50 106 50 107 82 107 83 107 50 108 83 108 46 108 46 109 83 109 84 109 46 110 84 110 47 110 47 111 84 111 85 111 47 112 85 112 40 112 40 113 85 113 86 113 40 114 86 114 41 114 41 115 86 115 87 115 41 116 87 116 35 116 35 117 87 117 88 117 35 118 88 118 37 118 37 119 88 119 89 119 37 120 89 120 42 120 42 121 89 121 90 121 42 122 90 122 43 122 43 123 90 123 91 123 43 124 91 124 44 124 44 125 91 125 92 125 44 126 92 126 21 126 21 127 92 127 93 127 21 128 93 128 22 128 22 129 93 129 94 129 22 130 94 130 18 130 18 131 94 131 95 131 18 132 95 132 19 132 19 133 95 133 96 133 19 134 96 134 14 134 14 135 96 135 97 135 14 136 97 136 31 136 31 137 97 137 98 137 31 138 98 138 32 138 32 139 98 139 99 139 32 140 99 140 33 140 33 141 99 141 100 141 33 142 100 142 27 142 27 143 100 143 101 143 27 144 101 144 29 144 29 145 101 145 102 145 29 146 102 146 30 146 30 147 102 147 103 147 30 148 103 148 13 148 13 149 103 149 104 149 13 150 104 150 23 150 23 151 104 151 105 151 23 152 105 152 24 152 24 153 105 153 106 153 24 154 106 154 25 154 25 155 106 155 107 155 25 156 107 156 9 156 9 157 107 157 108 157 9 158 108 158 10 158 10 159 108 159 109 159 10 160 109 160 4 160 4 161 109 161 110 161 4 162 110 162 6 162 6 163 110 163 111 163 6 164 111 164 7 164 7 165 111 165 76 165 7 166 76 166 0 166 0 167 76 167 51 167 112 168 113 168 114 168 114 169 113 169 115 169 114 170 115 170 116 170 116 171 115 171 117 171 116 172 117 172 118 172 118 173 117 173 119 173 118 174 119 174 120 174 120 175 119 175 121 175 66 176 119 176 67 176 67 177 119 177 117 177 67 178 117 178 68 178 68 179 117 179 69 179 66 180 65 180 119 180 119 181 65 181 64 181 119 182 64 182 121 182 121 183 64 183 63 183 63 184 62 184 121 184 121 185 62 185 61 185 121 186 61 186 122 186 122 187 61 187 60 187 60 188 59 188 122 188 122 189 59 189 58 189 122 190 58 190 113 190 113 191 58 191 57 191 113 192 57 192 56 192 73 193 115 193 74 193 74 194 115 194 113 194 74 195 113 195 75 195 75 196 113 196 56 196 73 197 72 197 115 197 115 198 72 198 71 198 115 199 71 199 117 199 117 200 71 200 70 200 117 201 70 201 69 201 123 202 122 202 112 202 112 203 122 203 113 203 124 204 125 204 126 204 126 205 125 205 123 205 126 206 123 206 112 206 126 207 127 207 124 207 124 208 127 208 128 208 124 209 128 209 129 209 129 210 128 210 130 210 130 211 131 211 129 211 129 212 131 212 132 212 129 213 132 213 133 213 134 214 127 214 114 214 114 215 127 215 126 215 114 216 126 216 112 216 134 217 135 217 127 217 127 218 135 218 136 218 127 219 136 219 128 219 128 220 136 220 137 220 128 221 137 221 130 221 130 222 137 222 138 222 130 223 138 223 131 223 131 224 138 224 139 224 131 225 139 225 132 225 114 226 116 226 140 226 141 227 135 227 140 227 140 228 135 228 134 228 140 229 134 229 114 229 138 230 137 230 141 230 141 231 137 231 136 231 141 232 136 232 135 232 141 233 142 233 138 233 138 234 142 234 143 234 138 235 143 235 139 235 116 236 118 236 144 236 116 237 144 237 140 237 140 238 144 238 145 238 140 239 145 239 141 239 141 240 145 240 146 240 141 241 146 241 142 241 142 242 146 242 147 242 142 243 147 243 143 243 118 244 120 244 148 244 118 245 148 245 144 245 144 246 148 246 149 246 144 247 149 247 145 247 145 248 149 248 150 248 145 249 150 249 146 249 146 250 150 250 151 250 146 251 151 251 147 251 120 252 121 252 123 252 123 253 121 253 122 253 91 254 90 254 143 254 86 255 139 255 87 255 87 256 139 256 88 256 99 257 98 257 147 257 105 258 104 258 151 258 151 259 104 259 103 259 143 260 90 260 139 260 139 261 90 261 89 261 139 262 89 262 88 262 94 263 93 263 143 263 143 264 93 264 92 264 143 265 92 265 91 265 111 266 110 266 133 266 133 267 110 267 109 267 82 268 81 268 132 268 132 269 81 269 80 269 132 270 80 270 79 270 79 271 78 271 132 271 132 272 78 272 77 272 132 273 77 273 133 273 133 274 77 274 76 274 133 275 76 275 111 275 86 276 85 276 139 276 139 277 85 277 84 277 139 278 84 278 132 278 132 279 84 279 83 279 132 280 83 280 82 280 98 281 97 281 147 281 147 282 97 282 96 282 147 283 96 283 143 283 143 284 96 284 95 284 143 285 95 285 94 285 109 286 108 286 133 286 133 287 108 287 107 287 133 288 107 288 151 288 151 289 107 289 106 289 151 290 106 290 105 290 103 291 102 291 151 291 151 292 102 292 101 292 151 293 101 293 147 293 147 294 101 294 100 294 147 295 100 295 99 295 120 296 123 296 125 296 120 297 125 297 148 297 148 298 125 298 124 298 148 299 124 299 149 299 149 300 124 300 129 300 149 301 129 301 150 301 150 302 129 302 133 302 150 303 133 303 151 303 152 304 153 304 154 304 152 305 154 305 155 305 156 306 157 306 154 306 154 307 157 307 158 307 154 308 158 308 155 308 159 309 160 309 154 309 154 310 160 310 161 310 154 311 161 311 156 311 162 312 163 312 154 312 154 313 163 313 164 313 154 314 164 314 159 314 165 315 166 315 167 315 168 316 169 316 167 316 167 317 169 317 170 317 167 318 170 318 165 318 171 319 172 319 167 319 167 320 172 320 173 320 167 321 173 321 168 321 174 322 175 322 167 322 167 323 175 323 176 323 167 324 176 324 171 324 177 325 178 325 179 325 180 326 181 326 182 326 183 327 184 327 185 327 186 328 187 328 188 328 189 329 190 329 191 329 191 330 190 330 192 330 193 331 194 331 195 331 195 332 194 332 196 332 195 333 196 333 197 333 198 334 199 334 200 334 201 335 202 335 203 335 203 336 202 336 204 336 203 337 204 337 189 337 205 338 206 338 207 338 207 339 206 339 208 339 207 340 208 340 209 340 210 341 211 341 212 341 212 342 211 342 213 342 213 343 214 343 205 343 205 344 214 344 215 344 205 345 215 345 206 345 210 346 212 346 216 346 216 347 212 347 217 347 216 348 217 348 218 348 219 349 220 349 217 349 217 350 220 350 221 350 217 351 221 351 218 351 222 352 223 352 224 352 222 353 224 353 188 353 188 354 224 354 225 354 188 355 225 355 186 355 226 356 227 356 228 356 228 357 227 357 229 357 228 358 229 358 222 358 222 359 229 359 230 359 222 360 230 360 223 360 184 361 231 361 185 361 185 362 231 362 232 362 185 363 232 363 228 363 228 364 232 364 233 364 228 365 233 365 226 365 182 366 181 366 185 366 185 367 181 367 234 367 185 368 234 368 183 368 235 369 236 369 237 369 237 370 236 370 238 370 180 371 182 371 239 371 239 372 182 372 240 372 239 373 240 373 241 373 241 374 240 374 237 374 241 375 237 375 242 375 242 376 237 376 238 376 242 377 238 377 243 377 244 378 245 378 246 378 246 379 245 379 247 379 248 380 249 380 250 380 250 381 249 381 251 381 250 382 251 382 252 382 252 383 251 383 253 383 254 384 255 384 256 384 256 385 255 385 257 385 256 386 257 386 258 386 258 387 257 387 259 387 258 388 259 388 260 388 261 389 262 389 263 389 263 390 262 390 264 390 265 391 266 391 267 391 267 392 266 392 268 392 267 393 268 393 269 393 270 394 271 394 272 394 272 395 271 395 273 395 272 396 273 396 267 396 267 397 273 397 274 397 267 398 274 398 265 398 270 399 272 399 275 399 275 400 272 400 276 400 275 401 276 401 277 401 277 402 276 402 278 402 278 403 276 403 279 403 278 404 279 404 280 404 281 405 282 405 279 405 279 406 282 406 283 406 279 407 283 407 280 407 284 408 285 408 281 408 281 409 285 409 286 409 281 410 286 410 282 410 287 411 288 411 284 411 284 412 288 412 289 412 284 413 289 413 285 413 290 414 291 414 292 414 292 415 291 415 293 415 294 416 295 416 296 416 296 417 295 417 297 417 294 418 298 418 295 418 295 419 298 419 299 419 295 420 299 420 300 420 301 421 302 421 303 421 303 422 302 422 304 422 303 423 304 423 305 423 306 424 307 424 308 424 308 425 307 425 309 425 308 426 309 426 303 426 303 427 309 427 310 427 303 428 310 428 301 428 311 429 312 429 253 429 249 430 244 430 251 430 251 431 244 431 246 431 251 432 246 432 253 432 253 433 246 433 313 433 253 434 313 434 311 434 311 435 314 435 312 435 312 436 314 436 315 436 312 437 315 437 316 437 316 438 315 438 317 438 316 439 317 439 318 439 260 440 252 440 258 440 258 441 252 441 253 441 258 442 253 442 256 442 256 443 253 443 312 443 256 444 312 444 254 444 254 445 312 445 316 445 264 446 319 446 263 446 263 447 319 447 320 447 263 448 320 448 321 448 321 449 320 449 322 449 321 450 322 450 323 450 319 451 255 451 320 451 320 452 255 452 254 452 320 453 254 453 322 453 322 454 254 454 316 454 322 455 316 455 323 455 323 456 316 456 318 456 323 457 318 457 324 457 324 458 318 458 325 458 290 459 287 459 291 459 291 460 287 460 284 460 291 461 284 461 326 461 326 462 284 462 281 462 326 463 281 463 327 463 327 464 281 464 279 464 327 465 279 465 328 465 328 466 279 466 276 466 328 467 276 467 329 467 329 468 276 468 272 468 329 469 272 469 330 469 330 470 272 470 267 470 330 471 267 471 331 471 331 472 267 472 269 472 332 473 333 473 334 473 334 474 333 474 335 474 334 475 335 475 336 475 336 476 335 476 337 476 336 477 337 477 338 477 338 478 337 478 339 478 338 479 339 479 325 479 325 480 339 480 340 480 325 481 340 481 324 481 333 482 293 482 335 482 335 483 293 483 291 483 335 484 291 484 337 484 337 485 291 485 326 485 337 486 326 486 339 486 339 487 326 487 327 487 339 488 327 488 340 488 340 489 327 489 328 489 340 490 328 490 324 490 324 491 328 491 329 491 324 492 329 492 323 492 323 493 329 493 330 493 323 494 330 494 321 494 321 495 330 495 331 495 321 496 331 496 263 496 263 497 331 497 269 497 263 498 269 498 261 498 341 499 342 499 343 499 343 500 342 500 344 500 343 501 344 501 195 501 195 502 344 502 345 502 195 503 345 503 193 503 193 504 345 504 346 504 193 505 346 505 347 505 303 506 341 506 308 506 308 507 341 507 343 507 308 508 343 508 306 508 306 509 343 509 195 509 306 510 195 510 348 510 348 511 195 511 197 511 349 512 350 512 351 512 189 513 191 513 203 513 203 514 191 514 352 514 203 515 352 515 201 515 199 516 347 516 200 516 200 517 347 517 346 517 200 518 346 518 353 518 353 519 346 519 345 519 353 520 345 520 354 520 354 521 345 521 344 521 354 522 344 522 355 522 355 523 344 523 342 523 355 524 342 524 356 524 356 525 342 525 341 525 356 526 341 526 357 526 357 527 341 527 303 527 357 528 303 528 300 528 300 529 303 529 305 529 300 530 305 530 295 530 295 531 305 531 358 531 295 532 358 532 297 532 198 533 200 533 192 533 192 534 200 534 353 534 192 535 353 535 191 535 191 536 353 536 354 536 191 537 354 537 352 537 352 538 354 538 355 538 352 539 355 539 359 539 359 540 355 540 356 540 359 541 356 541 332 541 332 542 356 542 357 542 332 543 357 543 333 543 333 544 357 544 300 544 333 545 300 545 293 545 293 546 300 546 299 546 293 547 299 547 292 547 185 548 360 548 182 548 182 549 360 549 361 549 182 550 361 550 240 550 240 551 361 551 362 551 240 552 362 552 237 552 237 553 362 553 179 553 237 554 179 554 235 554 235 555 179 555 178 555 351 556 350 556 363 556 363 557 350 557 364 557 363 558 364 558 365 558 365 559 364 559 366 559 365 560 366 560 188 560 188 561 366 561 367 561 188 562 367 562 222 562 222 563 367 563 368 563 222 564 368 564 228 564 228 565 368 565 369 565 228 566 369 566 185 566 185 567 369 567 370 567 185 568 370 568 360 568 187 569 219 569 188 569 188 570 219 570 217 570 188 571 217 571 365 571 365 572 217 572 212 572 365 573 212 573 363 573 363 574 212 574 213 574 363 575 213 575 351 575 351 576 213 576 205 576 351 577 205 577 349 577 349 578 205 578 207 578 247 579 177 579 246 579 246 580 177 580 179 580 246 581 179 581 313 581 313 582 179 582 362 582 313 583 362 583 311 583 311 584 362 584 361 584 311 585 361 585 314 585 314 586 361 586 360 586 314 587 360 587 315 587 315 588 360 588 370 588 315 589 370 589 317 589 317 590 370 590 369 590 317 591 369 591 318 591 318 592 369 592 368 592 318 593 368 593 325 593 325 594 368 594 367 594 325 595 367 595 338 595 338 596 367 596 366 596 338 597 366 597 336 597 336 598 366 598 364 598 336 599 364 599 334 599 334 600 364 600 350 600 334 601 350 601 332 601 332 602 350 602 349 602 332 603 349 603 359 603 359 604 349 604 207 604 359 605 207 605 352 605 352 606 207 606 209 606 352 607 209 607 201 607 371 608 372 608 373 608 374 609 375 609 376 609 377 610 378 610 379 610 380 611 381 611 382 611 382 612 381 612 383 612 384 613 385 613 386 613 387 614 388 614 389 614 372 615 371 615 390 615 391 616 392 616 393 616 394 617 387 617 395 617 395 618 387 618 389 618 395 619 389 619 396 619 388 620 397 620 398 620 398 621 397 621 399 621 398 622 399 622 400 622 393 623 390 623 391 623 391 624 390 624 371 624 391 625 371 625 401 625 401 626 371 626 400 626 401 627 400 627 402 627 402 628 400 628 399 628 403 629 385 629 404 629 404 630 385 630 384 630 404 631 384 631 405 631 405 632 384 632 406 632 407 633 406 633 408 633 408 634 406 634 384 634 408 635 384 635 409 635 409 636 384 636 386 636 409 637 386 637 410 637 411 638 412 638 413 638 414 639 415 639 416 639 416 640 415 640 417 640 416 641 417 641 418 641 418 642 417 642 419 642 418 643 419 643 413 643 413 644 419 644 420 644 413 645 420 645 411 645 411 646 421 646 412 646 412 647 421 647 422 647 412 648 422 648 423 648 423 649 422 649 424 649 423 650 424 650 425 650 378 651 426 651 379 651 379 652 426 652 427 652 379 653 427 653 428 653 428 654 427 654 429 654 428 655 429 655 430 655 430 656 429 656 431 656 430 657 431 657 432 657 432 658 431 658 433 658 432 659 433 659 434 659 434 660 433 660 435 660 434 661 435 661 436 661 436 662 435 662 437 662 436 663 437 663 438 663 438 664 437 664 439 664 438 665 439 665 440 665 381 666 440 666 383 666 383 667 440 667 439 667 383 668 439 668 441 668 441 669 439 669 437 669 441 670 437 670 425 670 425 671 437 671 435 671 425 672 435 672 423 672 423 673 435 673 433 673 423 674 433 674 412 674 412 675 433 675 431 675 412 676 431 676 413 676 413 677 431 677 429 677 413 678 429 678 418 678 418 679 429 679 427 679 418 680 427 680 416 680 442 681 382 681 443 681 443 682 382 682 383 682 443 683 383 683 444 683 444 684 383 684 441 684 444 685 441 685 445 685 445 686 441 686 425 686 445 687 425 687 446 687 446 688 425 688 424 688 447 689 448 689 449 689 449 690 448 690 450 690 450 691 377 691 449 691 449 692 377 692 379 692 449 693 379 693 451 693 451 694 379 694 428 694 451 695 428 695 452 695 452 696 428 696 430 696 452 697 430 697 453 697 453 698 430 698 432 698 453 699 432 699 454 699 454 700 432 700 434 700 454 701 434 701 455 701 455 702 434 702 436 702 455 703 436 703 456 703 456 704 436 704 438 704 456 705 438 705 457 705 457 706 438 706 440 706 457 707 440 707 458 707 458 708 440 708 381 708 458 709 381 709 459 709 459 710 381 710 380 710 376 711 460 711 374 711 374 712 460 712 461 712 374 713 461 713 462 713 462 714 461 714 463 714 462 715 463 715 464 715 464 716 463 716 465 716 464 717 465 717 466 717 466 718 465 718 467 718 468 719 469 719 470 719 470 720 469 720 471 720 470 721 471 721 472 721 467 722 473 722 466 722 466 723 473 723 474 723 466 724 474 724 475 724 475 725 474 725 476 725 475 726 476 726 468 726 468 727 476 727 477 727 468 728 477 728 469 728 471 729 478 729 479 729 388 730 398 730 389 730 389 731 398 731 480 731 389 732 480 732 396 732 373 733 481 733 371 733 371 734 481 734 482 734 371 735 482 735 400 735 400 736 482 736 483 736 400 737 483 737 398 737 398 738 483 738 484 738 398 739 484 739 480 739 485 740 414 740 486 740 486 741 414 741 416 741 486 742 416 742 487 742 487 743 416 743 427 743 487 744 427 744 488 744 488 745 427 745 426 745 403 746 489 746 385 746 385 747 489 747 394 747 385 748 394 748 386 748 386 749 394 749 395 749 386 750 395 750 410 750 471 751 479 751 472 751 472 752 479 752 490 752 472 753 490 753 491 753 491 754 447 754 472 754 472 755 447 755 449 755 472 756 449 756 470 756 470 757 449 757 451 757 470 758 451 758 468 758 468 759 451 759 452 759 468 760 452 760 475 760 475 761 452 761 453 761 475 762 453 762 466 762 466 763 453 763 454 763 466 764 454 764 464 764 464 765 454 765 455 765 464 766 455 766 462 766 462 767 455 767 456 767 462 768 456 768 374 768 374 769 456 769 457 769 374 770 457 770 375 770 375 771 457 771 458 771 375 772 458 772 492 772 492 773 458 773 459 773 492 774 459 774 493 774 494 775 495 775 493 775 493 776 495 776 496 776 493 777 496 777 492 777 492 778 496 778 497 778 492 779 497 779 375 779 375 780 497 780 498 780 375 781 498 781 376 781 396 782 494 782 395 782 395 783 494 783 493 783 395 784 493 784 410 784 410 785 493 785 459 785 410 786 459 786 409 786 409 787 459 787 380 787 409 788 380 788 408 788 408 789 380 789 382 789 408 790 382 790 407 790 407 791 382 791 442 791 499 792 500 792 501 792 502 793 503 793 504 793 505 794 506 794 507 794 508 795 509 795 510 795 511 796 512 796 513 796 512 797 511 797 514 797 515 798 516 798 517 798 518 799 519 799 520 799 521 800 522 800 523 800 524 801 525 801 526 801 526 802 525 802 527 802 528 803 525 803 529 803 529 804 525 804 530 804 528 805 531 805 525 805 525 806 531 806 532 806 525 807 532 807 527 807 533 808 534 808 535 808 535 809 534 809 536 809 535 810 536 810 537 810 537 811 536 811 538 811 537 812 538 812 525 812 539 813 535 813 540 813 540 814 535 814 537 814 540 815 537 815 541 815 541 816 537 816 525 816 541 817 525 817 542 817 542 818 525 818 524 818 543 819 544 819 545 819 545 820 544 820 546 820 545 821 546 821 547 821 548 822 549 822 550 822 550 823 549 823 551 823 552 824 553 824 554 824 554 825 553 825 555 825 554 826 555 826 556 826 556 827 555 827 557 827 558 828 557 828 559 828 559 829 557 829 555 829 559 830 555 830 560 830 560 831 555 831 553 831 561 832 558 832 562 832 562 833 558 833 559 833 562 834 559 834 563 834 563 835 559 835 560 835 563 836 560 836 564 836 564 837 560 837 553 837 564 838 553 838 565 838 565 839 553 839 552 839 565 840 552 840 566 840 567 841 568 841 551 841 551 842 568 842 569 842 517 843 570 843 571 843 571 844 570 844 572 844 571 845 572 845 573 845 520 846 574 846 518 846 518 847 574 847 575 847 518 848 575 848 576 848 576 849 575 849 577 849 576 850 577 850 578 850 519 851 518 851 579 851 579 852 518 852 576 852 579 853 576 853 580 853 580 854 576 854 578 854 580 855 578 855 581 855 517 856 516 856 570 856 570 857 516 857 582 857 570 858 582 858 572 858 583 859 584 859 585 859 583 860 585 860 586 860 585 861 587 861 586 861 586 862 587 862 588 862 586 863 588 863 589 863 589 864 588 864 590 864 589 865 590 865 513 865 500 866 508 866 501 866 501 867 508 867 510 867 501 868 510 868 591 868 591 869 510 869 592 869 591 870 592 870 593 870 593 871 592 871 583 871 593 872 583 872 594 872 594 873 583 873 586 873 594 874 586 874 595 874 595 875 586 875 589 875 595 876 589 876 596 876 596 877 589 877 513 877 596 878 513 878 597 878 597 879 513 879 512 879 597 880 512 880 598 880 598 881 512 881 514 881 598 882 514 882 599 882 599 883 514 883 600 883 599 884 600 884 601 884 590 885 602 885 513 885 513 886 602 886 603 886 513 887 603 887 511 887 511 888 603 888 604 888 511 889 604 889 605 889 574 890 601 890 575 890 575 891 601 891 600 891 575 892 600 892 577 892 577 893 600 893 514 893 577 894 514 894 578 894 578 895 514 895 511 895 578 896 511 896 581 896 581 897 511 897 605 897 581 898 605 898 606 898 442 899 443 899 607 899 607 900 443 900 444 900 607 901 444 901 608 901 609 902 610 902 406 902 572 903 611 903 610 903 610 904 611 904 405 904 610 905 405 905 406 905 548 906 611 906 549 906 549 907 611 907 572 907 549 908 572 908 551 908 551 909 572 909 612 909 551 910 612 910 613 910 613 911 612 911 522 911 613 912 522 912 551 912 551 913 522 913 521 913 551 914 521 914 567 914 506 915 505 915 614 915 614 916 505 916 615 916 614 917 615 917 616 917 615 918 617 918 616 918 616 919 617 919 618 919 616 920 618 920 609 920 609 921 618 921 619 921 609 922 619 922 610 922 610 923 619 923 620 923 610 924 620 924 572 924 444 925 445 925 608 925 608 926 445 926 446 926 608 927 446 927 621 927 406 928 407 928 609 928 609 929 407 929 442 929 609 930 442 930 616 930 616 931 442 931 607 931 616 932 607 932 614 932 614 933 607 933 608 933 614 934 608 934 506 934 506 935 608 935 621 935 506 936 621 936 507 936 622 937 421 937 411 937 622 938 411 938 623 938 421 939 622 939 422 939 422 940 622 940 624 940 422 941 624 941 424 941 485 942 625 942 414 942 414 943 625 943 626 943 411 944 420 944 623 944 623 945 420 945 419 945 623 946 419 946 627 946 627 947 419 947 417 947 627 948 417 948 626 948 626 949 417 949 415 949 626 950 415 950 414 950 446 951 424 951 621 951 621 952 424 952 624 952 621 953 624 953 507 953 507 954 624 954 628 954 507 955 628 955 505 955 505 956 628 956 566 956 505 957 566 957 615 957 615 958 566 958 552 958 615 959 552 959 617 959 617 960 552 960 554 960 617 961 554 961 618 961 618 962 554 962 556 962 618 963 556 963 619 963 619 964 556 964 557 964 619 965 557 965 620 965 620 966 557 966 558 966 620 967 558 967 572 967 572 968 558 968 561 968 542 969 629 969 541 969 541 970 629 970 630 970 541 971 630 971 631 971 539 972 399 972 397 972 397 973 545 973 539 973 539 974 545 974 547 974 539 975 547 975 535 975 535 976 547 976 632 976 535 977 632 977 533 977 399 978 539 978 402 978 402 979 539 979 540 979 402 980 540 980 401 980 401 981 540 981 541 981 401 982 541 982 391 982 391 983 541 983 631 983 391 984 631 984 392 984 584 985 583 985 633 985 633 986 583 986 592 986 633 987 592 987 634 987 634 988 592 988 510 988 634 989 510 989 504 989 504 990 510 990 509 990 504 991 509 991 502 991 569 992 635 992 551 992 551 993 635 993 636 993 551 994 636 994 550 994 550 995 636 995 637 995 550 996 637 996 543 996 543 997 637 997 638 997 543 998 638 998 544 998 625 999 499 999 626 999 626 1000 499 1000 501 1000 626 1001 501 1001 627 1001 627 1002 501 1002 591 1002 627 1003 591 1003 623 1003 623 1004 591 1004 593 1004 623 1005 593 1005 622 1005 622 1006 593 1006 594 1006 622 1007 594 1007 624 1007 624 1008 594 1008 595 1008 624 1009 595 1009 628 1009 628 1010 595 1010 596 1010 628 1011 596 1011 566 1011 566 1012 596 1012 597 1012 566 1013 597 1013 565 1013 565 1014 597 1014 598 1014 565 1015 598 1015 564 1015 564 1016 598 1016 599 1016 564 1017 599 1017 563 1017 563 1018 599 1018 601 1018 563 1019 601 1019 562 1019 562 1020 601 1020 574 1020 562 1021 574 1021 561 1021 561 1022 574 1022 520 1022 561 1023 520 1023 572 1023 572 1024 520 1024 519 1024 572 1025 519 1025 573 1025 573 1026 519 1026 579 1026 573 1027 579 1027 571 1027 571 1028 579 1028 580 1028 571 1029 580 1029 517 1029 517 1030 580 1030 581 1030 517 1031 581 1031 515 1031 515 1032 581 1032 606 1032 397 1033 388 1033 545 1033 545 1034 388 1034 387 1034 545 1035 387 1035 543 1035 543 1036 387 1036 394 1036 543 1037 394 1037 550 1037 550 1038 394 1038 489 1038 550 1039 489 1039 548 1039 548 1040 489 1040 403 1040 548 1041 403 1041 611 1041 611 1042 403 1042 404 1042 611 1043 404 1043 405 1043 639 1044 640 1044 641 1044 642 1045 643 1045 644 1045 645 1046 646 1046 647 1046 648 1047 649 1047 650 1047 651 1048 530 1048 525 1048 652 1049 653 1049 654 1049 655 1050 656 1050 657 1050 655 1051 657 1051 658 1051 659 1052 660 1052 661 1052 661 1053 660 1053 662 1053 661 1054 662 1054 663 1054 664 1055 658 1055 665 1055 665 1056 658 1056 657 1056 665 1057 657 1057 666 1057 666 1058 657 1058 667 1058 666 1059 667 1059 668 1059 668 1060 667 1060 663 1060 668 1061 663 1061 669 1061 669 1062 663 1062 662 1062 670 1063 671 1063 672 1063 672 1064 671 1064 673 1064 673 1065 671 1065 674 1065 673 1066 674 1066 675 1066 672 1067 676 1067 670 1067 670 1068 676 1068 677 1068 670 1069 677 1069 678 1069 678 1070 677 1070 679 1070 678 1071 679 1071 680 1071 679 1072 681 1072 680 1072 680 1073 681 1073 682 1073 680 1074 682 1074 683 1074 683 1075 682 1075 684 1075 683 1076 684 1076 685 1076 685 1077 684 1077 686 1077 685 1078 686 1078 687 1078 635 1079 569 1079 688 1079 688 1080 569 1080 568 1080 568 1081 567 1081 689 1081 567 1082 521 1082 689 1082 689 1083 521 1083 523 1083 689 1084 523 1084 522 1084 568 1085 689 1085 688 1085 688 1086 689 1086 690 1086 688 1087 690 1087 635 1087 612 1088 691 1088 692 1088 612 1089 572 1089 691 1089 691 1090 572 1090 582 1090 691 1091 582 1091 693 1091 693 1092 582 1092 516 1092 694 1093 695 1093 696 1093 696 1094 695 1094 697 1094 698 1095 515 1095 699 1095 699 1096 515 1096 606 1096 699 1097 606 1097 605 1097 700 1098 701 1098 602 1098 695 1099 698 1099 697 1099 697 1100 698 1100 699 1100 697 1101 699 1101 702 1101 702 1102 699 1102 605 1102 702 1103 605 1103 703 1103 703 1104 605 1104 604 1104 703 1105 604 1105 701 1105 701 1106 604 1106 603 1106 701 1107 603 1107 602 1107 602 1108 590 1108 700 1108 700 1109 590 1109 588 1109 700 1110 588 1110 704 1110 704 1111 588 1111 587 1111 704 1112 587 1112 585 1112 705 1113 706 1113 584 1113 584 1114 633 1114 705 1114 705 1115 633 1115 634 1115 705 1116 634 1116 707 1116 707 1117 634 1117 504 1117 707 1118 504 1118 503 1118 503 1119 708 1119 707 1119 707 1120 708 1120 709 1120 707 1121 709 1121 710 1121 711 1122 712 1122 525 1122 525 1123 712 1123 713 1123 525 1124 713 1124 651 1124 714 1125 715 1125 525 1125 525 1126 715 1126 716 1126 525 1127 716 1127 711 1127 717 1128 718 1128 714 1128 714 1129 718 1129 719 1129 714 1130 719 1130 715 1130 533 1131 720 1131 534 1131 534 1132 720 1132 721 1132 534 1133 721 1133 536 1133 536 1134 721 1134 722 1134 723 1135 724 1135 725 1135 649 1136 717 1136 650 1136 650 1137 717 1137 714 1137 650 1138 714 1138 726 1138 533 1139 632 1139 720 1139 720 1140 632 1140 547 1140 720 1141 547 1141 727 1141 722 1142 721 1142 724 1142 724 1143 721 1143 720 1143 724 1144 720 1144 725 1144 725 1145 720 1145 727 1145 725 1146 727 1146 728 1146 729 1147 546 1147 544 1147 729 1148 544 1148 730 1148 544 1149 638 1149 730 1149 730 1150 638 1150 637 1150 730 1151 637 1151 690 1151 690 1152 637 1152 636 1152 690 1153 636 1153 635 1153 547 1154 546 1154 727 1154 727 1155 546 1155 729 1155 727 1156 729 1156 728 1156 728 1157 729 1157 730 1157 728 1158 730 1158 731 1158 731 1159 730 1159 690 1159 731 1160 690 1160 732 1160 732 1161 690 1161 689 1161 732 1162 689 1162 692 1162 692 1163 689 1163 522 1163 692 1164 522 1164 612 1164 723 1165 725 1165 733 1165 733 1166 725 1166 728 1166 733 1167 728 1167 734 1167 734 1168 728 1168 731 1168 734 1169 731 1169 735 1169 735 1170 731 1170 732 1170 735 1171 732 1171 736 1171 736 1172 732 1172 692 1172 736 1173 692 1173 694 1173 694 1174 692 1174 691 1174 694 1175 691 1175 695 1175 695 1176 691 1176 693 1176 695 1177 693 1177 698 1177 698 1178 693 1178 516 1178 698 1179 516 1179 515 1179 734 1180 737 1180 733 1180 733 1181 737 1181 726 1181 733 1182 726 1182 723 1182 723 1183 726 1183 714 1183 723 1184 714 1184 724 1184 724 1185 714 1185 525 1185 724 1186 525 1186 722 1186 722 1187 525 1187 538 1187 722 1188 538 1188 536 1188 696 1189 738 1189 694 1189 694 1190 738 1190 739 1190 694 1191 739 1191 736 1191 736 1192 739 1192 740 1192 736 1193 740 1193 735 1193 735 1194 740 1194 741 1194 735 1195 741 1195 734 1195 734 1196 741 1196 742 1196 734 1197 742 1197 737 1197 646 1198 648 1198 647 1198 647 1199 648 1199 650 1199 647 1200 650 1200 743 1200 743 1201 650 1201 726 1201 743 1202 726 1202 744 1202 744 1203 726 1203 737 1203 744 1204 737 1204 745 1204 745 1205 737 1205 742 1205 745 1206 742 1206 746 1206 746 1207 742 1207 741 1207 746 1208 741 1208 747 1208 747 1209 741 1209 740 1209 747 1210 740 1210 748 1210 748 1211 740 1211 739 1211 748 1212 739 1212 749 1212 749 1213 739 1213 738 1213 749 1214 738 1214 750 1214 750 1215 738 1215 696 1215 750 1216 696 1216 751 1216 751 1217 696 1217 697 1217 751 1218 697 1218 752 1218 752 1219 697 1219 702 1219 752 1220 702 1220 753 1220 753 1221 702 1221 703 1221 753 1222 703 1222 754 1222 754 1223 703 1223 701 1223 754 1224 701 1224 755 1224 755 1225 701 1225 700 1225 755 1226 700 1226 756 1226 756 1227 700 1227 704 1227 756 1228 704 1228 706 1228 706 1229 704 1229 585 1229 706 1230 585 1230 584 1230 675 1231 674 1231 757 1231 757 1232 674 1232 654 1232 757 1233 654 1233 758 1233 758 1234 654 1234 653 1234 758 1235 653 1235 759 1235 686 1236 760 1236 687 1236 687 1237 760 1237 761 1237 687 1238 761 1238 762 1238 762 1239 761 1239 763 1239 762 1240 763 1240 764 1240 764 1241 763 1241 765 1241 764 1242 765 1242 766 1242 766 1243 765 1243 767 1243 766 1244 767 1244 642 1244 642 1245 767 1245 768 1245 642 1246 768 1246 643 1246 640 1247 652 1247 641 1247 641 1248 652 1248 654 1248 641 1249 654 1249 769 1249 769 1250 654 1250 674 1250 769 1251 674 1251 770 1251 770 1252 674 1252 671 1252 770 1253 671 1253 771 1253 771 1254 671 1254 670 1254 771 1255 670 1255 772 1255 772 1256 670 1256 678 1256 772 1257 678 1257 773 1257 773 1258 678 1258 680 1258 773 1259 680 1259 774 1259 774 1260 680 1260 683 1260 774 1261 683 1261 775 1261 775 1262 683 1262 685 1262 775 1263 685 1263 776 1263 776 1264 685 1264 687 1264 776 1265 687 1265 777 1265 777 1266 687 1266 762 1266 777 1267 762 1267 778 1267 778 1268 762 1268 764 1268 778 1269 764 1269 779 1269 779 1270 764 1270 766 1270 779 1271 766 1271 780 1271 780 1272 766 1272 642 1272 780 1273 642 1273 659 1273 659 1274 642 1274 644 1274 659 1275 644 1275 660 1275 710 1276 639 1276 707 1276 707 1277 639 1277 641 1277 707 1278 641 1278 705 1278 705 1279 641 1279 769 1279 705 1280 769 1280 706 1280 706 1281 769 1281 770 1281 706 1282 770 1282 756 1282 756 1283 770 1283 771 1283 756 1284 771 1284 755 1284 755 1285 771 1285 772 1285 755 1286 772 1286 754 1286 754 1287 772 1287 773 1287 754 1288 773 1288 753 1288 753 1289 773 1289 774 1289 753 1290 774 1290 752 1290 752 1291 774 1291 775 1291 752 1292 775 1292 751 1292 751 1293 775 1293 776 1293 751 1294 776 1294 750 1294 750 1295 776 1295 777 1295 750 1296 777 1296 749 1296 749 1297 777 1297 778 1297 749 1298 778 1298 748 1298 748 1299 778 1299 779 1299 748 1300 779 1300 747 1300 747 1301 779 1301 780 1301 747 1302 780 1302 746 1302 746 1303 780 1303 659 1303 746 1304 659 1304 745 1304 745 1305 659 1305 661 1305 745 1306 661 1306 744 1306 744 1307 661 1307 663 1307 744 1308 663 1308 743 1308 743 1309 663 1309 667 1309 743 1310 667 1310 647 1310 647 1311 667 1311 657 1311 647 1312 657 1312 645 1312 645 1313 657 1313 656 1313 781 1314 782 1314 783 1314 392 1315 631 1315 784 1315 531 1316 528 1316 785 1316 786 1317 782 1317 787 1317 788 1318 789 1318 790 1318 791 1319 792 1319 793 1319 793 1320 792 1320 794 1320 793 1321 794 1321 795 1321 796 1322 797 1322 798 1322 798 1323 797 1323 799 1323 789 1324 788 1324 800 1324 795 1325 801 1325 793 1325 793 1326 801 1326 802 1326 793 1327 802 1327 791 1327 791 1328 802 1328 803 1328 804 1329 799 1329 803 1329 803 1330 799 1330 797 1330 803 1331 797 1331 791 1331 791 1332 797 1332 796 1332 791 1333 796 1333 792 1333 786 1334 787 1334 805 1334 806 1335 805 1335 807 1335 807 1336 805 1336 787 1336 807 1337 787 1337 808 1337 808 1338 787 1338 809 1338 808 1339 809 1339 810 1339 781 1340 811 1340 804 1340 804 1341 811 1341 812 1341 804 1342 812 1342 799 1342 390 1343 393 1343 813 1343 813 1344 393 1344 814 1344 785 1345 528 1345 815 1345 815 1346 528 1346 529 1346 815 1347 529 1347 530 1347 630 1348 629 1348 816 1348 816 1349 629 1349 542 1349 524 1350 526 1350 817 1350 817 1351 526 1351 527 1351 817 1352 527 1352 785 1352 785 1353 527 1353 532 1353 785 1354 532 1354 531 1354 818 1355 816 1355 817 1355 817 1356 816 1356 542 1356 817 1357 542 1357 524 1357 631 1358 630 1358 784 1358 784 1359 630 1359 816 1359 784 1360 816 1360 800 1360 800 1361 816 1361 818 1361 800 1362 818 1362 789 1362 788 1363 810 1363 800 1363 800 1364 810 1364 819 1364 800 1365 819 1365 784 1365 784 1366 819 1366 814 1366 784 1367 814 1367 392 1367 392 1368 814 1368 393 1368 781 1369 820 1369 811 1369 811 1370 820 1370 821 1370 811 1371 821 1371 812 1371 812 1372 821 1372 822 1372 812 1373 822 1373 799 1373 799 1374 822 1374 823 1374 799 1375 823 1375 798 1375 801 1376 809 1376 802 1376 802 1377 809 1377 787 1377 802 1378 787 1378 803 1378 803 1379 787 1379 782 1379 803 1380 782 1380 804 1380 804 1381 782 1381 781 1381 373 1382 372 1382 824 1382 824 1383 372 1383 795 1383 824 1384 795 1384 825 1384 825 1385 795 1385 794 1385 810 1386 809 1386 819 1386 819 1387 809 1387 801 1387 819 1388 801 1388 814 1388 814 1389 801 1389 795 1389 814 1390 795 1390 813 1390 813 1391 795 1391 372 1391 813 1392 372 1392 390 1392 826 1393 827 1393 828 1393 818 1394 817 1394 829 1394 830 1395 831 1395 832 1395 833 1396 834 1396 835 1396 835 1397 834 1397 836 1397 837 1398 781 1398 838 1398 839 1399 840 1399 841 1399 782 1400 842 1400 781 1400 808 1401 810 1401 843 1401 844 1402 845 1402 846 1402 846 1403 845 1403 847 1403 846 1404 847 1404 197 1404 810 1405 788 1405 848 1405 848 1406 788 1406 790 1406 848 1407 790 1407 789 1407 805 1408 807 1408 786 1408 786 1409 807 1409 849 1409 786 1410 849 1410 782 1410 782 1411 849 1411 850 1411 782 1412 850 1412 842 1412 851 1413 852 1413 853 1413 853 1414 852 1414 850 1414 853 1415 850 1415 843 1415 843 1416 850 1416 849 1416 843 1417 849 1417 808 1417 808 1418 849 1418 807 1418 854 1419 855 1419 856 1419 856 1420 855 1420 857 1420 781 1421 842 1421 857 1421 857 1422 842 1422 858 1422 857 1423 858 1423 856 1423 831 1424 859 1424 832 1424 832 1425 859 1425 860 1425 832 1426 860 1426 861 1426 861 1427 860 1427 862 1427 861 1428 862 1428 863 1428 864 1429 862 1429 865 1429 865 1430 862 1430 860 1430 865 1431 860 1431 866 1431 866 1432 860 1432 859 1432 863 1433 862 1433 867 1433 867 1434 862 1434 864 1434 867 1435 864 1435 868 1435 868 1436 864 1436 869 1436 868 1437 869 1437 870 1437 871 1438 872 1438 873 1438 873 1439 872 1439 869 1439 873 1440 869 1440 874 1440 874 1441 869 1441 864 1441 874 1442 864 1442 875 1442 875 1443 864 1443 865 1443 876 1444 863 1444 877 1444 877 1445 863 1445 867 1445 877 1446 867 1446 878 1446 878 1447 867 1447 868 1447 878 1448 868 1448 879 1448 879 1449 868 1449 870 1449 879 1450 870 1450 880 1450 837 1451 838 1451 881 1451 882 1452 883 1452 884 1452 884 1453 883 1453 885 1453 884 1454 885 1454 886 1454 886 1455 885 1455 887 1455 886 1456 887 1456 888 1456 889 1457 890 1457 891 1457 892 1458 893 1458 894 1458 894 1459 893 1459 895 1459 896 1460 887 1460 897 1460 897 1461 887 1461 885 1461 897 1462 885 1462 898 1462 898 1463 885 1463 883 1463 898 1464 883 1464 899 1464 899 1465 883 1465 882 1465 899 1466 882 1466 900 1466 892 1467 901 1467 893 1467 893 1468 901 1468 891 1468 893 1469 891 1469 895 1469 895 1470 891 1470 890 1470 852 1471 902 1471 850 1471 850 1472 902 1472 900 1472 850 1473 900 1473 842 1473 842 1474 900 1474 882 1474 842 1475 882 1475 858 1475 858 1476 882 1476 884 1476 858 1477 884 1477 856 1477 856 1478 884 1478 886 1478 856 1479 886 1479 854 1479 854 1480 886 1480 888 1480 881 1481 903 1481 837 1481 837 1482 903 1482 904 1482 837 1483 904 1483 781 1483 905 1484 906 1484 907 1484 907 1485 906 1485 908 1485 907 1486 908 1486 909 1486 903 1487 910 1487 904 1487 904 1488 910 1488 781 1488 881 1489 907 1489 903 1489 903 1490 907 1490 909 1490 903 1491 909 1491 910 1491 910 1492 909 1492 911 1492 910 1493 911 1493 912 1493 912 1494 911 1494 913 1494 896 1495 914 1495 887 1495 887 1496 914 1496 839 1496 887 1497 839 1497 888 1497 888 1498 839 1498 841 1498 888 1499 841 1499 915 1499 871 1500 916 1500 872 1500 872 1501 916 1501 890 1501 872 1502 890 1502 869 1502 869 1503 890 1503 889 1503 869 1504 889 1504 870 1504 870 1505 889 1505 917 1505 870 1506 917 1506 880 1506 918 1507 919 1507 846 1507 846 1508 919 1508 920 1508 846 1509 920 1509 844 1509 921 1510 922 1510 923 1510 923 1511 924 1511 921 1511 921 1512 924 1512 925 1512 921 1513 925 1513 926 1513 835 1514 927 1514 833 1514 833 1515 927 1515 928 1515 833 1516 928 1516 922 1516 922 1517 928 1517 929 1517 922 1518 929 1518 923 1518 930 1519 921 1519 846 1519 846 1520 921 1520 926 1520 846 1521 926 1521 918 1521 876 1522 834 1522 863 1522 863 1523 834 1523 833 1523 863 1524 833 1524 861 1524 861 1525 833 1525 922 1525 861 1526 922 1526 832 1526 832 1527 922 1527 921 1527 832 1528 921 1528 830 1528 830 1529 921 1529 930 1529 880 1530 931 1530 879 1530 879 1531 931 1531 932 1531 879 1532 932 1532 878 1532 878 1533 932 1533 933 1533 878 1534 933 1534 877 1534 877 1535 933 1535 934 1535 877 1536 934 1536 876 1536 876 1537 934 1537 935 1537 876 1538 935 1538 834 1538 834 1539 935 1539 828 1539 834 1540 828 1540 836 1540 836 1541 828 1541 827 1541 530 1542 651 1542 815 1542 815 1543 651 1543 785 1543 651 1544 713 1544 785 1544 785 1545 713 1545 712 1545 785 1546 712 1546 817 1546 817 1547 712 1547 711 1547 711 1548 716 1548 817 1548 817 1549 716 1549 715 1549 817 1550 715 1550 829 1550 829 1551 715 1551 719 1551 829 1552 719 1552 718 1552 718 1553 717 1553 829 1553 829 1554 717 1554 649 1554 829 1555 649 1555 936 1555 645 1556 937 1556 646 1556 646 1557 937 1557 936 1557 646 1558 936 1558 648 1558 648 1559 936 1559 649 1559 937 1560 938 1560 936 1560 936 1561 938 1561 939 1561 936 1562 939 1562 829 1562 829 1563 939 1563 848 1563 829 1564 848 1564 818 1564 818 1565 848 1565 789 1565 810 1566 848 1566 843 1566 843 1567 848 1567 939 1567 843 1568 939 1568 853 1568 853 1569 939 1569 938 1569 853 1570 938 1570 851 1570 851 1571 938 1571 937 1571 851 1572 937 1572 940 1572 940 1573 937 1573 645 1573 940 1574 645 1574 656 1574 656 1575 655 1575 940 1575 940 1576 655 1576 658 1576 940 1577 658 1577 664 1577 913 1578 941 1578 912 1578 912 1579 941 1579 942 1579 912 1580 942 1580 910 1580 910 1581 942 1581 781 1581 915 1582 905 1582 888 1582 888 1583 905 1583 907 1583 888 1584 907 1584 854 1584 854 1585 907 1585 881 1585 854 1586 881 1586 855 1586 855 1587 881 1587 838 1587 855 1588 838 1588 857 1588 857 1589 838 1589 781 1589 901 1590 914 1590 891 1590 891 1591 914 1591 896 1591 891 1592 896 1592 889 1592 889 1593 896 1593 897 1593 889 1594 897 1594 917 1594 917 1595 897 1595 898 1595 917 1596 898 1596 880 1596 880 1597 898 1597 899 1597 880 1598 899 1598 931 1598 931 1599 899 1599 900 1599 931 1600 900 1600 932 1600 932 1601 900 1601 902 1601 932 1602 902 1602 933 1602 933 1603 902 1603 852 1603 933 1604 852 1604 934 1604 934 1605 852 1605 851 1605 934 1606 851 1606 935 1606 935 1607 851 1607 940 1607 935 1608 940 1608 828 1608 828 1609 940 1609 664 1609 828 1610 664 1610 826 1610 943 1611 944 1611 945 1611 946 1612 947 1612 948 1612 948 1613 949 1613 950 1613 154 1614 946 1614 951 1614 951 1615 946 1615 948 1615 951 1616 948 1616 952 1616 952 1617 948 1617 950 1617 953 1618 954 1618 955 1618 955 1619 954 1619 956 1619 955 1620 956 1620 957 1620 953 1621 958 1621 954 1621 954 1622 958 1622 959 1622 954 1623 959 1623 949 1623 949 1624 959 1624 960 1624 949 1625 960 1625 950 1625 957 1626 956 1626 961 1626 961 1627 956 1627 962 1627 961 1628 962 1628 963 1628 964 1629 965 1629 962 1629 962 1630 965 1630 966 1630 962 1631 966 1631 963 1631 967 1632 968 1632 964 1632 964 1633 968 1633 969 1633 964 1634 969 1634 965 1634 970 1635 971 1635 967 1635 967 1636 971 1636 972 1636 967 1637 972 1637 968 1637 973 1638 974 1638 975 1638 974 1639 973 1639 976 1639 976 1640 973 1640 977 1640 976 1641 977 1641 978 1641 978 1642 977 1642 979 1642 979 1643 977 1643 980 1643 979 1644 980 1644 981 1644 982 1645 983 1645 984 1645 984 1646 983 1646 985 1646 984 1647 985 1647 986 1647 981 1648 980 1648 987 1648 987 1649 980 1649 985 1649 987 1650 985 1650 988 1650 988 1651 985 1651 983 1651 988 1652 983 1652 989 1652 990 1653 991 1653 992 1653 992 1654 991 1654 993 1654 994 1655 995 1655 996 1655 996 1656 995 1656 997 1656 996 1657 997 1657 998 1657 998 1658 997 1658 999 1658 994 1659 1000 1659 995 1659 995 1660 1000 1660 1001 1660 995 1661 1001 1661 1002 1661 1001 1662 1003 1662 1002 1662 1002 1663 1003 1663 1004 1663 1002 1664 1004 1664 990 1664 990 1665 1004 1665 1005 1665 990 1666 1005 1666 991 1666 999 1667 997 1667 1006 1667 1006 1668 997 1668 1007 1668 1006 1669 1007 1669 1008 1669 1008 1670 1007 1670 1009 1670 1008 1671 1009 1671 1010 1671 975 1672 971 1672 973 1672 973 1673 971 1673 970 1673 973 1674 970 1674 977 1674 977 1675 970 1675 1011 1675 977 1676 1011 1676 980 1676 980 1677 1011 1677 1012 1677 980 1678 1012 1678 985 1678 985 1679 1012 1679 945 1679 985 1680 945 1680 986 1680 986 1681 945 1681 944 1681 485 1682 1013 1682 625 1682 625 1683 1013 1683 1014 1683 1015 1684 500 1684 1014 1684 1014 1685 500 1685 499 1685 1014 1686 499 1686 625 1686 502 1687 509 1687 1015 1687 1015 1688 509 1688 508 1688 1015 1689 508 1689 500 1689 1016 1690 709 1690 708 1690 1016 1691 708 1691 1015 1691 1015 1692 708 1692 503 1692 1015 1693 503 1693 502 1693 709 1694 1016 1694 710 1694 710 1695 1016 1695 1017 1695 710 1696 1017 1696 639 1696 993 1697 759 1697 992 1697 992 1698 759 1698 653 1698 992 1699 653 1699 1018 1699 1018 1700 653 1700 652 1700 1018 1701 652 1701 1017 1701 1017 1702 652 1702 640 1702 1017 1703 640 1703 639 1703 947 1704 1009 1704 948 1704 948 1705 1009 1705 1007 1705 948 1706 1007 1706 949 1706 949 1707 1007 1707 997 1707 949 1708 997 1708 954 1708 954 1709 997 1709 995 1709 954 1710 995 1710 956 1710 956 1711 995 1711 1002 1711 956 1712 1002 1712 962 1712 962 1713 1002 1713 990 1713 962 1714 990 1714 964 1714 964 1715 990 1715 992 1715 964 1716 992 1716 967 1716 967 1717 992 1717 1018 1717 967 1718 1018 1718 970 1718 970 1719 1018 1719 1017 1719 970 1720 1017 1720 1011 1720 1011 1721 1017 1721 1016 1721 1011 1722 1016 1722 1012 1722 1012 1723 1016 1723 1015 1723 1012 1724 1015 1724 945 1724 945 1725 1015 1725 1014 1725 945 1726 1014 1726 943 1726 943 1727 1014 1727 1013 1727 943 1728 1013 1728 1019 1728 1009 1729 947 1729 1020 1729 1021 1730 1022 1730 1023 1730 1024 1731 1025 1731 1026 1731 984 1732 986 1732 1027 1732 1028 1733 1029 1733 1027 1733 1027 1734 1029 1734 1030 1734 1027 1735 1030 1735 984 1735 984 1736 1030 1736 1031 1736 984 1737 1031 1737 982 1737 1032 1738 1033 1738 1034 1738 1034 1739 1033 1739 1028 1739 1034 1740 1028 1740 1035 1740 1035 1741 1028 1741 1027 1741 1025 1742 1036 1742 1026 1742 1026 1743 1036 1743 1037 1743 1026 1744 1037 1744 1034 1744 1034 1745 1037 1745 1038 1745 1034 1746 1038 1746 1032 1746 1039 1747 1040 1747 1041 1747 1042 1748 1043 1748 1044 1748 1044 1749 1043 1749 1045 1749 1044 1750 1045 1750 1040 1750 1040 1751 1045 1751 1046 1751 1040 1752 1046 1752 1041 1752 1047 1753 1048 1753 1049 1753 1049 1754 1048 1754 1050 1754 1049 1755 1050 1755 1051 1755 1051 1756 1050 1756 1023 1756 1051 1757 1023 1757 1052 1757 1052 1758 1023 1758 1022 1758 1053 1759 1054 1759 1055 1759 1055 1760 1054 1760 1021 1760 1056 1761 1057 1761 1053 1761 946 1762 154 1762 1058 1762 1058 1763 154 1763 1059 1763 1057 1764 1056 1764 1060 1764 1060 1765 1056 1765 1058 1765 1060 1766 1058 1766 1061 1766 1061 1767 1058 1767 1059 1767 1061 1768 1059 1768 1062 1768 426 1769 1063 1769 488 1769 488 1770 1063 1770 1019 1770 488 1771 1019 1771 487 1771 426 1772 378 1772 1063 1772 1063 1773 378 1773 377 1773 1063 1774 377 1774 1064 1774 447 1775 1065 1775 448 1775 448 1776 1065 1776 1064 1776 448 1777 1064 1777 450 1777 450 1778 1064 1778 377 1778 479 1779 1066 1779 490 1779 490 1780 1066 1780 1065 1780 490 1781 1065 1781 491 1781 491 1782 1065 1782 447 1782 487 1783 1019 1783 486 1783 486 1784 1019 1784 1013 1784 486 1785 1013 1785 485 1785 986 1786 944 1786 1027 1786 1027 1787 944 1787 1067 1787 1027 1788 1067 1788 1035 1788 1035 1789 1067 1789 1068 1789 1035 1790 1068 1790 1034 1790 1034 1791 1068 1791 1069 1791 1034 1792 1069 1792 1026 1792 1026 1793 1069 1793 1039 1793 1026 1794 1039 1794 1024 1794 1024 1795 1039 1795 1041 1795 1056 1796 1070 1796 1058 1796 1058 1797 1070 1797 1020 1797 1058 1798 1020 1798 946 1798 946 1799 1020 1799 947 1799 1071 1800 244 1800 249 1800 1053 1801 1055 1801 1056 1801 1056 1802 1055 1802 1071 1802 1056 1803 1071 1803 1070 1803 1070 1804 1071 1804 249 1804 1070 1805 249 1805 248 1805 248 1806 1072 1806 1070 1806 1070 1807 1072 1807 1073 1807 1070 1808 1073 1808 1020 1808 1020 1809 1073 1809 1074 1809 1020 1810 1074 1810 1009 1810 1009 1811 1074 1811 1075 1811 1009 1812 1075 1812 1010 1812 235 1813 178 1813 1048 1813 1048 1814 178 1814 177 1814 1048 1815 177 1815 1050 1815 1050 1816 177 1816 247 1816 1050 1817 247 1817 245 1817 1021 1818 1023 1818 1055 1818 1055 1819 1023 1819 1050 1819 1055 1820 1050 1820 1071 1820 1071 1821 1050 1821 245 1821 1071 1822 245 1822 244 1822 944 1823 943 1823 1067 1823 1067 1824 943 1824 1019 1824 1067 1825 1019 1825 1068 1825 1068 1826 1019 1826 1063 1826 1068 1827 1063 1827 1069 1827 1069 1828 1063 1828 1064 1828 1069 1829 1064 1829 1039 1829 1039 1830 1064 1830 1065 1830 1039 1831 1065 1831 1040 1831 1040 1832 1065 1832 1066 1832 1040 1833 1066 1833 1044 1833 1044 1834 1066 1834 1076 1834 1047 1835 1042 1835 1048 1835 1048 1836 1042 1836 1044 1836 1048 1837 1044 1837 235 1837 235 1838 1044 1838 1076 1838 235 1839 1076 1839 236 1839 236 1840 1076 1840 238 1840 479 1841 478 1841 1066 1841 1066 1842 478 1842 1077 1842 1066 1843 1077 1843 1076 1843 1076 1844 1077 1844 243 1844 1076 1845 243 1845 238 1845 209 1846 208 1846 484 1846 210 1847 216 1847 496 1847 496 1848 216 1848 497 1848 460 1849 376 1849 187 1849 216 1850 218 1850 497 1850 497 1851 218 1851 221 1851 497 1852 221 1852 498 1852 498 1853 221 1853 220 1853 498 1854 220 1854 376 1854 376 1855 220 1855 219 1855 376 1856 219 1856 187 1856 463 1857 230 1857 465 1857 465 1858 230 1858 229 1858 465 1859 229 1859 467 1859 467 1860 229 1860 227 1860 467 1861 227 1861 473 1861 473 1862 227 1862 226 1862 473 1863 226 1863 233 1863 184 1864 477 1864 231 1864 231 1865 477 1865 476 1865 231 1866 476 1866 232 1866 180 1867 471 1867 181 1867 181 1868 471 1868 469 1868 181 1869 469 1869 234 1869 234 1870 469 1870 477 1870 234 1871 477 1871 183 1871 183 1872 477 1872 184 1872 232 1873 476 1873 233 1873 233 1874 476 1874 474 1874 233 1875 474 1875 473 1875 187 1876 186 1876 460 1876 460 1877 186 1877 225 1877 460 1878 225 1878 461 1878 461 1879 225 1879 224 1879 461 1880 224 1880 463 1880 463 1881 224 1881 223 1881 463 1882 223 1882 230 1882 373 1883 1078 1883 481 1883 481 1884 1078 1884 482 1884 1078 1885 198 1885 482 1885 482 1886 198 1886 192 1886 482 1887 192 1887 190 1887 484 1888 208 1888 480 1888 480 1889 208 1889 206 1889 480 1890 206 1890 396 1890 190 1891 189 1891 482 1891 482 1892 189 1892 204 1892 482 1893 204 1893 483 1893 483 1894 204 1894 202 1894 483 1895 202 1895 484 1895 484 1896 202 1896 201 1896 484 1897 201 1897 209 1897 243 1898 1077 1898 242 1898 242 1899 1077 1899 241 1899 1077 1900 478 1900 241 1900 241 1901 478 1901 471 1901 241 1902 471 1902 239 1902 239 1903 471 1903 180 1903 206 1904 215 1904 396 1904 396 1905 215 1905 214 1905 396 1906 214 1906 494 1906 494 1907 214 1907 495 1907 495 1908 214 1908 213 1908 495 1909 213 1909 496 1909 496 1910 213 1910 211 1910 496 1911 211 1911 210 1911 993 1912 991 1912 1079 1912 826 1913 664 1913 665 1913 1080 1914 682 1914 1081 1914 1081 1915 682 1915 681 1915 1081 1916 681 1916 1082 1916 1082 1917 681 1917 1083 1917 681 1918 679 1918 1083 1918 1083 1919 679 1919 677 1919 1083 1920 677 1920 1084 1920 1084 1921 677 1921 676 1921 1084 1922 676 1922 1085 1922 1085 1923 676 1923 1086 1923 1087 1924 765 1924 1088 1924 1088 1925 765 1925 763 1925 1088 1926 763 1926 1089 1926 1089 1927 763 1927 761 1927 1089 1928 761 1928 1090 1928 1090 1929 761 1929 760 1929 1090 1930 760 1930 1091 1930 1091 1931 760 1931 686 1931 1091 1932 686 1932 1080 1932 1080 1933 686 1933 684 1933 1080 1934 684 1934 682 1934 1092 1935 1093 1935 665 1935 665 1936 1093 1936 827 1936 665 1937 827 1937 826 1937 1094 1938 1095 1938 660 1938 660 1939 1095 1939 662 1939 662 1940 1095 1940 1096 1940 662 1941 1096 1941 669 1941 665 1942 666 1942 1092 1942 1092 1943 666 1943 668 1943 1092 1944 668 1944 1097 1944 1097 1945 668 1945 669 1945 1097 1946 669 1946 1098 1946 1098 1947 669 1947 1096 1947 759 1948 993 1948 758 1948 758 1949 993 1949 1079 1949 758 1950 1079 1950 757 1950 757 1951 1079 1951 1099 1951 757 1952 1099 1952 675 1952 675 1953 1099 1953 1100 1953 675 1954 1100 1954 673 1954 673 1955 1100 1955 1086 1955 673 1956 1086 1956 672 1956 672 1957 1086 1957 676 1957 660 1958 644 1958 1094 1958 1094 1959 644 1959 643 1959 1094 1960 643 1960 1101 1960 1101 1961 643 1961 768 1961 1101 1962 768 1962 1087 1962 1087 1963 768 1963 767 1963 1087 1964 767 1964 765 1964 1074 1965 1073 1965 1102 1965 1103 1966 1104 1966 1105 1966 1106 1967 1107 1967 1108 1967 264 1968 262 1968 1109 1968 1110 1969 1111 1969 1112 1969 1113 1970 1114 1970 1115 1970 305 1971 304 1971 1116 1971 348 1972 197 1972 847 1972 348 1973 847 1973 306 1973 310 1974 309 1974 1117 1974 1117 1975 309 1975 307 1975 1117 1976 307 1976 306 1976 1118 1977 918 1977 926 1977 844 1978 920 1978 1118 1978 1118 1979 920 1979 919 1979 1118 1980 919 1980 918 1980 306 1981 847 1981 1117 1981 1117 1982 847 1982 845 1982 1117 1983 845 1983 310 1983 304 1984 302 1984 1119 1984 1119 1985 302 1985 1118 1985 1119 1986 1118 1986 1105 1986 1105 1987 1118 1987 926 1987 845 1988 844 1988 310 1988 310 1989 844 1989 1118 1989 310 1990 1118 1990 301 1990 301 1991 1118 1991 302 1991 1120 1992 1121 1992 1122 1992 1122 1993 1121 1993 292 1993 1123 1994 292 1994 1124 1994 1124 1995 292 1995 1121 1995 1124 1996 1121 1996 1125 1996 1125 1997 1121 1997 1126 1997 298 1998 294 1998 299 1998 299 1999 294 1999 1116 1999 1127 2000 1126 2000 1128 2000 1128 2001 1126 2001 1121 2001 1128 2002 1121 2002 1129 2002 1129 2003 1121 2003 1120 2003 1129 2004 1120 2004 1130 2004 358 2005 305 2005 297 2005 297 2006 305 2006 1116 2006 297 2007 1116 2007 296 2007 296 2008 1116 2008 294 2008 1131 2009 1132 2009 1133 2009 1133 2010 1132 2010 1134 2010 1133 2011 1134 2011 1127 2011 1135 2012 1136 2012 1137 2012 1137 2013 1136 2013 1134 2013 1137 2014 1134 2014 1138 2014 1138 2015 1134 2015 1132 2015 1138 2016 1132 2016 1139 2016 1139 2017 1132 2017 1131 2017 1139 2018 1131 2018 1114 2018 1115 2019 1140 2019 1113 2019 1113 2020 1140 2020 1141 2020 1113 2021 1141 2021 1142 2021 1142 2022 1141 2022 1143 2022 1142 2023 1143 2023 1144 2023 1144 2024 1143 2024 1145 2024 1146 2025 1110 2025 1135 2025 1135 2026 1110 2026 1112 2026 1135 2027 1112 2027 1136 2027 1114 2028 1113 2028 1139 2028 1139 2029 1113 2029 1142 2029 1139 2030 1142 2030 1138 2030 1138 2031 1142 2031 1144 2031 1138 2032 1144 2032 1137 2032 1137 2033 1144 2033 1145 2033 1137 2034 1145 2034 1135 2034 1135 2035 1145 2035 1147 2035 1135 2036 1147 2036 1146 2036 1127 2037 1134 2037 1126 2037 1126 2038 1134 2038 1136 2038 1126 2039 1136 2039 1125 2039 1125 2040 1136 2040 1112 2040 1125 2041 1112 2041 1124 2041 1124 2042 1112 2042 1111 2042 1124 2043 1111 2043 1123 2043 1148 2044 1149 2044 1150 2044 1150 2045 1149 2045 1151 2045 1152 2046 1153 2046 1154 2046 1154 2047 1153 2047 1155 2047 1156 2048 1152 2048 1157 2048 1157 2049 1152 2049 1154 2049 1157 2050 1154 2050 1158 2050 1159 2051 1160 2051 1158 2051 1158 2052 1160 2052 1161 2052 1158 2053 1161 2053 1157 2053 1157 2054 1161 2054 1162 2054 1157 2055 1162 2055 1156 2055 1148 2056 1150 2056 1163 2056 1163 2057 1150 2057 1164 2057 1163 2058 1164 2058 1165 2058 1166 2059 280 2059 1167 2059 1167 2060 280 2060 283 2060 1167 2061 283 2061 282 2061 1168 2062 1169 2062 1170 2062 1170 2063 1169 2063 1171 2063 273 2064 271 2064 1172 2064 266 2065 265 2065 1173 2065 1173 2066 265 2066 274 2066 1173 2067 274 2067 1170 2067 1170 2068 274 2068 273 2068 1170 2069 273 2069 1168 2069 1168 2070 273 2070 1172 2070 1168 2071 1172 2071 1169 2071 1169 2072 1172 2072 1174 2072 259 2073 257 2073 1175 2073 1175 2074 257 2074 255 2074 1175 2075 255 2075 1109 2075 1109 2076 255 2076 319 2076 1109 2077 319 2077 264 2077 262 2078 261 2078 1109 2078 1109 2079 261 2079 269 2079 1109 2080 269 2080 1173 2080 1173 2081 269 2081 268 2081 1173 2082 268 2082 266 2082 1167 2083 1165 2083 1166 2083 1166 2084 1165 2084 1164 2084 1166 2085 1164 2085 1174 2085 1174 2086 1164 2086 1150 2086 1174 2087 1150 2087 1169 2087 1169 2088 1150 2088 1151 2088 1169 2089 1151 2089 1171 2089 271 2090 270 2090 1172 2090 1172 2091 270 2091 275 2091 1172 2092 275 2092 1174 2092 1174 2093 275 2093 277 2093 1174 2094 277 2094 1166 2094 1166 2095 277 2095 278 2095 1166 2096 278 2096 280 2096 1073 2097 1072 2097 1102 2097 1102 2098 1072 2098 1175 2098 1102 2099 1175 2099 1176 2099 1176 2100 1175 2100 1109 2100 1176 2101 1109 2101 1177 2101 1177 2102 1109 2102 1173 2102 1177 2103 1173 2103 1178 2103 1179 2104 1180 2104 1181 2104 1181 2105 1180 2105 1182 2105 1181 2106 1182 2106 1183 2106 1107 2107 1184 2107 1108 2107 1108 2108 1184 2108 1185 2108 1108 2109 1185 2109 1182 2109 1182 2110 1185 2110 1186 2110 1182 2111 1186 2111 1183 2111 1187 2112 1188 2112 1189 2112 1189 2113 1188 2113 1190 2113 1180 2114 1191 2114 1182 2114 1182 2115 1191 2115 1187 2115 1182 2116 1187 2116 1108 2116 1108 2117 1187 2117 1189 2117 1108 2118 1189 2118 1106 2118 1106 2119 1189 2119 1190 2119 1106 2120 1190 2120 1192 2120 1193 2121 1194 2121 1195 2121 1010 2122 1075 2122 1196 2122 1193 2123 1195 2123 1196 2123 1196 2124 1195 2124 1197 2124 1196 2125 1197 2125 1010 2125 1192 2126 1194 2126 1106 2126 1106 2127 1194 2127 1193 2127 1106 2128 1193 2128 1107 2128 1107 2129 1193 2129 1198 2129 1107 2130 1198 2130 1184 2130 1184 2131 1198 2131 1199 2131 1184 2132 1199 2132 1185 2132 1185 2133 1199 2133 1200 2133 1185 2134 1200 2134 1186 2134 1186 2135 1200 2135 1201 2135 1186 2136 1201 2136 1183 2136 929 2137 928 2137 1103 2137 926 2138 925 2138 1105 2138 1105 2139 925 2139 924 2139 1105 2140 924 2140 1103 2140 1103 2141 924 2141 923 2141 1103 2142 923 2142 929 2142 1104 2143 1202 2143 1105 2143 1105 2144 1202 2144 1130 2144 1105 2145 1130 2145 1119 2145 1119 2146 1130 2146 1120 2146 1119 2147 1120 2147 304 2147 304 2148 1120 2148 1122 2148 304 2149 1122 2149 1116 2149 1116 2150 1122 2150 292 2150 1116 2151 292 2151 299 2151 248 2152 250 2152 1072 2152 1072 2153 250 2153 252 2153 1072 2154 252 2154 1175 2154 1175 2155 252 2155 260 2155 1175 2156 260 2156 259 2156 1159 2157 286 2157 1160 2157 1160 2158 286 2158 285 2158 1160 2159 285 2159 1161 2159 1161 2160 285 2160 289 2160 1161 2161 289 2161 288 2161 1147 2162 1155 2162 1146 2162 1146 2163 1155 2163 1153 2163 1146 2164 1153 2164 1110 2164 1110 2165 1153 2165 1152 2165 1110 2166 1152 2166 1111 2166 1111 2167 1152 2167 1156 2167 1111 2168 1156 2168 1123 2168 1123 2169 1156 2169 1162 2169 1123 2170 1162 2170 292 2170 292 2171 1162 2171 1161 2171 292 2172 1161 2172 290 2172 290 2173 1161 2173 288 2173 290 2174 288 2174 287 2174 1075 2175 1074 2175 1196 2175 1196 2176 1074 2176 1102 2176 1196 2177 1102 2177 1193 2177 1193 2178 1102 2178 1176 2178 1193 2179 1176 2179 1198 2179 1198 2180 1176 2180 1177 2180 1198 2181 1177 2181 1199 2181 1199 2182 1177 2182 1178 2182 1199 2183 1178 2183 1200 2183 1200 2184 1178 2184 1203 2184 1200 2185 1203 2185 1201 2185 1201 2186 1203 2186 1204 2186 1201 2187 1204 2187 1183 2187 1183 2188 1204 2188 1205 2188 1183 2189 1205 2189 1181 2189 1181 2190 1205 2190 1206 2190 1181 2191 1206 2191 1179 2191 1179 2192 1206 2192 1207 2192 1202 2193 1208 2193 1130 2193 1130 2194 1208 2194 1209 2194 1130 2195 1209 2195 1129 2195 1129 2196 1209 2196 1210 2196 1129 2197 1210 2197 1128 2197 1128 2198 1210 2198 1211 2198 1128 2199 1211 2199 1212 2199 1212 2200 1207 2200 1128 2200 1128 2201 1207 2201 1206 2201 1128 2202 1206 2202 1127 2202 1127 2203 1206 2203 1205 2203 1127 2204 1205 2204 1133 2204 1133 2205 1205 2205 1204 2205 1133 2206 1204 2206 1131 2206 1131 2207 1204 2207 1203 2207 1131 2208 1203 2208 1114 2208 1114 2209 1203 2209 1178 2209 1114 2210 1178 2210 1115 2210 1115 2211 1178 2211 1173 2211 1115 2212 1173 2212 1140 2212 1140 2213 1173 2213 1170 2213 1140 2214 1170 2214 1141 2214 1141 2215 1170 2215 1171 2215 1141 2216 1171 2216 1143 2216 1143 2217 1171 2217 1151 2217 1143 2218 1151 2218 1145 2218 1145 2219 1151 2219 1149 2219 1145 2220 1149 2220 1147 2220 1147 2221 1149 2221 1148 2221 1147 2222 1148 2222 1155 2222 1155 2223 1148 2223 1163 2223 1155 2224 1163 2224 1154 2224 1154 2225 1163 2225 1165 2225 1154 2226 1165 2226 1158 2226 1158 2227 1165 2227 1167 2227 1158 2228 1167 2228 1159 2228 1159 2229 1167 2229 282 2229 1159 2230 282 2230 286 2230 1003 2231 1001 2231 1213 2231 1214 2232 836 2232 827 2232 1005 2233 1004 2233 1215 2233 1216 2234 1217 2234 1218 2234 1202 2235 1104 2235 1214 2235 836 2236 1214 2236 835 2236 1103 2237 928 2237 927 2237 835 2238 1214 2238 927 2238 927 2239 1214 2239 1104 2239 927 2240 1104 2240 1103 2240 1219 2241 1220 2241 1221 2241 1221 2242 1220 2242 1222 2242 1221 2243 1222 2243 1223 2243 1223 2244 1222 2244 1224 2244 1223 2245 1224 2245 1225 2245 1226 2246 1220 2246 1208 2246 1208 2247 1220 2247 1219 2247 1208 2248 1219 2248 1209 2248 1209 2249 1219 2249 1210 2249 1191 2250 1180 2250 1227 2250 1227 2251 1180 2251 1179 2251 1227 2252 1179 2252 1228 2252 1228 2253 1179 2253 1207 2253 1228 2254 1207 2254 1212 2254 1197 2255 1195 2255 1229 2255 1229 2256 1195 2256 1230 2256 1229 2257 1230 2257 1231 2257 996 2258 998 2258 1231 2258 994 2259 996 2259 1232 2259 1232 2260 996 2260 1231 2260 1232 2261 1231 2261 1233 2261 1233 2262 1231 2262 1234 2262 1233 2263 1234 2263 1235 2263 1235 2264 1234 2264 1236 2264 1235 2265 1236 2265 1237 2265 1237 2266 1236 2266 1238 2266 1237 2267 1238 2267 1239 2267 1239 2268 1238 2268 1240 2268 1239 2269 1240 2269 1218 2269 1195 2270 1194 2270 1230 2270 1230 2271 1194 2271 1192 2271 1230 2272 1192 2272 1241 2272 1241 2273 1192 2273 1190 2273 1241 2274 1190 2274 1242 2274 1242 2275 1190 2275 1188 2275 1242 2276 1188 2276 1187 2276 1231 2277 1230 2277 1234 2277 1234 2278 1230 2278 1241 2278 1234 2279 1241 2279 1236 2279 1236 2280 1241 2280 1242 2280 1236 2281 1242 2281 1238 2281 1238 2282 1242 2282 1187 2282 1238 2283 1187 2283 1240 2283 1218 2284 1217 2284 1239 2284 1239 2285 1217 2285 1243 2285 1239 2286 1243 2286 1237 2286 1237 2287 1243 2287 1244 2287 1237 2288 1244 2288 1235 2288 1235 2289 1244 2289 1245 2289 1235 2290 1245 2290 1233 2290 1233 2291 1245 2291 1246 2291 1233 2292 1246 2292 1232 2292 1232 2293 1246 2293 1247 2293 1232 2294 1247 2294 1213 2294 1213 2295 1001 2295 1232 2295 1232 2296 1001 2296 1000 2296 1232 2297 1000 2297 994 2297 1248 2298 1089 2298 1249 2298 1249 2299 1089 2299 1090 2299 1249 2300 1090 2300 1250 2300 1250 2301 1090 2301 1091 2301 1250 2302 1091 2302 1251 2302 1251 2303 1091 2303 1080 2303 1251 2304 1080 2304 1252 2304 1252 2305 1080 2305 1081 2305 1253 2306 1085 2306 1086 2306 1253 2307 1086 2307 1254 2307 1081 2308 1082 2308 1252 2308 1252 2309 1082 2309 1083 2309 1252 2310 1083 2310 1253 2310 1253 2311 1083 2311 1084 2311 1253 2312 1084 2312 1085 2312 991 2313 1005 2313 1079 2313 1079 2314 1005 2314 1215 2314 1079 2315 1215 2315 1099 2315 1099 2316 1215 2316 1254 2316 1099 2317 1254 2317 1100 2317 1100 2318 1254 2318 1086 2318 827 2319 1093 2319 1214 2319 1214 2320 1093 2320 1226 2320 1214 2321 1226 2321 1202 2321 1202 2322 1226 2322 1208 2322 1010 2323 1197 2323 1008 2323 1008 2324 1197 2324 1229 2324 1008 2325 1229 2325 1006 2325 1006 2326 1229 2326 1231 2326 1006 2327 1231 2327 999 2327 999 2328 1231 2328 998 2328 1210 2329 1219 2329 1211 2329 1211 2330 1219 2330 1221 2330 1211 2331 1221 2331 1212 2331 1212 2332 1221 2332 1223 2332 1212 2333 1223 2333 1228 2333 1228 2334 1223 2334 1225 2334 1228 2335 1225 2335 1227 2335 1004 2336 1003 2336 1215 2336 1215 2337 1003 2337 1213 2337 1215 2338 1213 2338 1254 2338 1254 2339 1213 2339 1247 2339 1254 2340 1247 2340 1253 2340 1253 2341 1247 2341 1246 2341 1253 2342 1246 2342 1252 2342 1252 2343 1246 2343 1245 2343 1252 2344 1245 2344 1251 2344 1251 2345 1245 2345 1244 2345 1251 2346 1244 2346 1250 2346 1250 2347 1244 2347 1243 2347 1250 2348 1243 2348 1249 2348 1249 2349 1243 2349 1217 2349 1249 2350 1217 2350 1248 2350 1248 2351 1217 2351 1216 2351 1248 2352 1216 2352 1255 2352 1093 2353 1092 2353 1226 2353 1226 2354 1092 2354 1097 2354 1226 2355 1097 2355 1220 2355 1220 2356 1097 2356 1098 2356 1220 2357 1098 2357 1222 2357 1222 2358 1098 2358 1096 2358 1222 2359 1096 2359 1095 2359 1094 2360 1101 2360 1255 2360 1255 2361 1101 2361 1087 2361 1255 2362 1087 2362 1248 2362 1248 2363 1087 2363 1088 2363 1248 2364 1088 2364 1089 2364 1095 2365 1094 2365 1222 2365 1222 2366 1094 2366 1255 2366 1222 2367 1255 2367 1224 2367 1224 2368 1255 2368 1216 2368 1224 2369 1216 2369 1225 2369 1225 2370 1216 2370 1218 2370 1225 2371 1218 2371 1227 2371 1227 2372 1218 2372 1240 2372 1227 2373 1240 2373 1191 2373 1191 2374 1240 2374 1187 2374 1256 2375 1257 2375 1258 2375 1259 2376 1260 2376 1261 2376 1262 2377 1263 2377 1264 2377 1265 2378 1266 2378 1267 2378 1268 2379 1269 2379 1270 2379 1271 2380 1272 2380 1273 2380 1273 2381 1272 2381 1274 2381 1273 2382 1274 2382 1275 2382 1276 2383 1277 2383 1278 2383 1278 2384 1279 2384 1276 2384 1276 2385 1279 2385 1280 2385 1276 2386 1280 2386 1281 2386 1270 2387 1269 2387 1280 2387 1280 2388 1269 2388 1282 2388 1280 2389 1282 2389 1281 2389 1283 2390 1284 2390 1285 2390 1283 2391 1285 2391 1286 2391 1285 2392 1287 2392 1286 2392 1286 2393 1287 2393 1288 2393 1286 2394 1288 2394 1270 2394 1270 2395 1288 2395 1289 2395 1270 2396 1289 2396 1268 2396 1290 2397 1291 2397 1292 2397 1292 2398 1291 2398 1293 2398 1294 2399 1295 2399 1296 2399 1296 2400 1295 2400 1297 2400 1296 2401 1297 2401 1292 2401 1292 2402 1297 2402 1298 2402 1292 2403 1298 2403 1290 2403 1299 2404 1300 2404 1301 2404 1302 2405 1303 2405 1299 2405 1303 2406 1304 2406 1299 2406 1299 2407 1304 2407 1305 2407 1299 2408 1305 2408 1300 2408 1306 2409 1307 2409 1308 2409 1308 2410 1307 2410 1309 2410 1308 2411 1309 2411 1310 2411 1310 2412 1309 2412 1311 2412 1310 2413 1311 2413 1312 2413 1313 2414 1314 2414 1315 2414 1315 2415 1314 2415 1316 2415 1315 2416 1316 2416 1317 2416 1313 2417 1318 2417 1314 2417 1314 2418 1318 2418 1319 2418 1314 2419 1319 2419 1308 2419 1308 2420 1319 2420 1320 2420 1308 2421 1320 2421 1306 2421 1267 2422 1266 2422 1316 2422 1316 2423 1266 2423 1321 2423 1316 2424 1321 2424 1317 2424 1322 2425 1323 2425 1324 2425 1265 2426 1267 2426 1325 2426 1325 2427 1267 2427 1326 2427 1325 2428 1326 2428 1327 2428 1327 2429 1326 2429 1322 2429 1327 2430 1322 2430 1328 2430 1328 2431 1322 2431 1324 2431 1328 2432 1324 2432 1329 2432 1330 2433 1331 2433 1332 2433 1332 2434 1331 2434 1333 2434 1330 2435 1334 2435 1335 2435 1335 2436 1334 2436 1336 2436 1337 2437 1338 2437 1339 2437 1340 2438 1338 2438 1341 2438 1341 2439 1338 2439 1337 2439 1341 2440 1337 2440 1342 2440 1342 2441 1337 2441 1264 2441 1342 2442 1264 2442 1343 2442 1343 2443 1264 2443 1263 2443 1344 2444 1345 2444 1346 2444 1346 2445 1345 2445 1347 2445 1346 2446 1347 2446 1348 2446 1349 2447 1350 2447 1351 2447 1346 2448 1352 2448 1344 2448 1344 2449 1352 2449 1349 2449 1344 2450 1349 2450 1353 2450 1353 2451 1349 2451 1351 2451 1352 2452 1354 2452 1349 2452 1349 2453 1354 2453 1355 2453 1349 2454 1355 2454 1261 2454 1260 2455 1356 2455 1261 2455 1261 2456 1356 2456 1357 2456 1261 2457 1357 2457 1349 2457 1349 2458 1357 2458 1358 2458 1349 2459 1358 2459 1350 2459 1359 2460 1360 2460 1259 2460 1361 2461 1362 2461 1363 2461 1364 2462 1365 2462 1366 2462 1366 2463 1365 2463 1367 2463 1366 2464 1367 2464 1361 2464 1361 2465 1367 2465 1368 2465 1361 2466 1368 2466 1362 2466 1369 2467 1370 2467 1371 2467 1371 2468 1370 2468 1372 2468 1373 2469 1374 2469 1366 2469 1366 2470 1374 2470 1375 2470 1366 2471 1375 2471 1364 2471 1376 2472 1377 2472 1371 2472 1371 2473 1377 2473 1378 2473 1371 2474 1378 2474 1369 2474 1379 2475 1380 2475 1381 2475 1381 2476 1380 2476 1382 2476 1381 2477 1382 2477 1258 2477 1258 2478 1382 2478 1383 2478 1258 2479 1383 2479 1256 2479 1278 2480 1384 2480 1279 2480 1279 2481 1384 2481 1385 2481 1279 2482 1385 2482 1280 2482 1280 2483 1385 2483 1386 2483 1280 2484 1386 2484 1270 2484 1270 2485 1386 2485 1387 2485 1270 2486 1387 2486 1286 2486 1286 2487 1387 2487 1388 2487 1286 2488 1388 2488 1283 2488 1283 2489 1388 2489 1389 2489 1390 2490 1296 2490 1389 2490 1389 2491 1296 2491 1292 2491 1389 2492 1292 2492 1283 2492 1283 2493 1292 2493 1293 2493 1283 2494 1293 2494 1284 2494 1391 2495 1392 2495 1393 2495 1393 2496 1392 2496 1394 2496 1393 2497 1394 2497 1395 2497 1395 2498 1394 2498 1396 2498 1395 2499 1396 2499 1397 2499 1397 2500 1396 2500 1398 2500 1397 2501 1398 2501 1399 2501 1399 2502 1398 2502 1400 2502 1399 2503 1400 2503 1401 2503 1310 2504 1391 2504 1308 2504 1308 2505 1391 2505 1393 2505 1308 2506 1393 2506 1314 2506 1314 2507 1393 2507 1395 2507 1314 2508 1395 2508 1316 2508 1316 2509 1395 2509 1397 2509 1316 2510 1397 2510 1267 2510 1267 2511 1397 2511 1399 2511 1267 2512 1399 2512 1326 2512 1326 2513 1399 2513 1401 2513 1326 2514 1401 2514 1322 2514 1348 2515 1402 2515 1346 2515 1346 2516 1402 2516 1403 2516 1346 2517 1403 2517 1352 2517 1352 2518 1403 2518 1404 2518 1352 2519 1404 2519 1354 2519 1354 2520 1404 2520 1405 2520 1354 2521 1405 2521 1355 2521 1355 2522 1405 2522 1406 2522 1407 2523 1262 2523 1408 2523 1408 2524 1262 2524 1264 2524 1408 2525 1264 2525 1409 2525 1409 2526 1264 2526 1337 2526 1409 2527 1337 2527 1334 2527 1334 2528 1337 2528 1339 2528 1334 2529 1339 2529 1336 2529 1330 2530 1332 2530 1334 2530 1334 2531 1332 2531 1410 2531 1334 2532 1410 2532 1409 2532 1409 2533 1410 2533 1403 2533 1409 2534 1403 2534 1408 2534 1408 2535 1403 2535 1402 2535 1408 2536 1402 2536 1407 2536 1312 2537 1302 2537 1310 2537 1310 2538 1302 2538 1299 2538 1310 2539 1299 2539 1391 2539 1391 2540 1299 2540 1411 2540 1391 2541 1411 2541 1392 2541 1392 2542 1411 2542 1406 2542 1392 2543 1406 2543 1394 2543 1394 2544 1406 2544 1405 2544 1394 2545 1405 2545 1396 2545 1396 2546 1405 2546 1404 2546 1396 2547 1404 2547 1398 2547 1398 2548 1404 2548 1403 2548 1398 2549 1403 2549 1400 2549 1400 2550 1403 2550 1410 2550 1400 2551 1410 2551 1401 2551 1401 2552 1410 2552 1332 2552 1401 2553 1332 2553 1322 2553 1322 2554 1332 2554 1333 2554 1322 2555 1333 2555 1323 2555 1259 2556 1261 2556 1359 2556 1359 2557 1261 2557 1355 2557 1359 2558 1355 2558 1412 2558 1412 2559 1355 2559 1406 2559 1412 2560 1406 2560 1413 2560 1413 2561 1406 2561 1411 2561 1413 2562 1411 2562 1390 2562 1390 2563 1411 2563 1299 2563 1390 2564 1299 2564 1296 2564 1296 2565 1299 2565 1301 2565 1296 2566 1301 2566 1294 2566 1275 2567 1414 2567 1273 2567 1273 2568 1414 2568 1379 2568 1273 2569 1379 2569 1415 2569 1415 2570 1379 2570 1381 2570 1415 2571 1381 2571 1416 2571 1416 2572 1381 2572 1258 2572 1416 2573 1258 2573 1417 2573 1417 2574 1258 2574 1418 2574 1417 2575 1418 2575 1419 2575 1419 2576 1418 2576 1366 2576 1419 2577 1366 2577 1420 2577 1420 2578 1366 2578 1361 2578 1420 2579 1361 2579 1421 2579 1257 2580 1422 2580 1258 2580 1258 2581 1422 2581 1376 2581 1258 2582 1376 2582 1418 2582 1418 2583 1376 2583 1371 2583 1418 2584 1371 2584 1366 2584 1366 2585 1371 2585 1372 2585 1366 2586 1372 2586 1373 2586 1277 2587 1423 2587 1278 2587 1278 2588 1423 2588 1424 2588 1278 2589 1424 2589 1384 2589 1384 2590 1424 2590 1271 2590 1384 2591 1271 2591 1385 2591 1385 2592 1271 2592 1273 2592 1385 2593 1273 2593 1386 2593 1386 2594 1273 2594 1415 2594 1386 2595 1415 2595 1387 2595 1387 2596 1415 2596 1416 2596 1387 2597 1416 2597 1388 2597 1388 2598 1416 2598 1417 2598 1388 2599 1417 2599 1389 2599 1389 2600 1417 2600 1419 2600 1389 2601 1419 2601 1390 2601 1390 2602 1419 2602 1420 2602 1390 2603 1420 2603 1413 2603 1413 2604 1420 2604 1421 2604 1413 2605 1421 2605 1412 2605 1412 2606 1421 2606 1361 2606 1412 2607 1361 2607 1359 2607 1359 2608 1361 2608 1363 2608 1359 2609 1363 2609 1360 2609 1425 2610 1426 2610 1427 2610 1428 2611 1429 2611 1430 2611 1431 2612 1432 2612 1433 2612 1433 2613 1432 2613 1434 2613 1435 2614 1436 2614 1437 2614 1438 2615 1439 2615 1440 2615 1441 2616 1442 2616 1443 2616 1443 2617 1442 2617 1444 2617 1443 2618 1444 2618 1445 2618 1446 2619 1438 2619 1447 2619 1447 2620 1438 2620 1440 2620 1447 2621 1440 2621 1448 2621 1439 2622 1449 2622 1450 2622 1450 2623 1449 2623 1451 2623 1450 2624 1451 2624 1452 2624 1453 2625 1441 2625 1454 2625 1454 2626 1441 2626 1443 2626 1454 2627 1443 2627 1455 2627 1455 2628 1443 2628 1452 2628 1455 2629 1452 2629 1456 2629 1456 2630 1452 2630 1451 2630 1457 2631 1436 2631 1458 2631 1458 2632 1436 2632 1435 2632 1458 2633 1435 2633 1459 2633 1459 2634 1435 2634 1460 2634 1461 2635 1460 2635 1462 2635 1462 2636 1460 2636 1435 2636 1462 2637 1435 2637 1463 2637 1463 2638 1435 2638 1437 2638 1463 2639 1437 2639 1464 2639 1465 2640 1466 2640 1467 2640 1468 2641 1469 2641 1470 2641 1470 2642 1469 2642 1471 2642 1470 2643 1471 2643 1472 2643 1472 2644 1471 2644 1473 2644 1472 2645 1473 2645 1467 2645 1467 2646 1473 2646 1474 2646 1467 2647 1474 2647 1465 2647 1465 2648 1475 2648 1466 2648 1466 2649 1475 2649 1476 2649 1466 2650 1476 2650 1477 2650 1477 2651 1476 2651 1478 2651 1477 2652 1478 2652 1479 2652 1429 2653 1480 2653 1430 2653 1430 2654 1480 2654 1481 2654 1430 2655 1481 2655 1482 2655 1482 2656 1481 2656 1483 2656 1482 2657 1483 2657 1484 2657 1484 2658 1483 2658 1485 2658 1484 2659 1485 2659 1486 2659 1486 2660 1485 2660 1487 2660 1486 2661 1487 2661 1488 2661 1488 2662 1487 2662 1489 2662 1488 2663 1489 2663 1490 2663 1490 2664 1489 2664 1491 2664 1490 2665 1491 2665 1492 2665 1492 2666 1491 2666 1493 2666 1492 2667 1493 2667 1494 2667 1432 2668 1494 2668 1434 2668 1434 2669 1494 2669 1493 2669 1434 2670 1493 2670 1495 2670 1495 2671 1493 2671 1491 2671 1495 2672 1491 2672 1479 2672 1479 2673 1491 2673 1489 2673 1479 2674 1489 2674 1477 2674 1477 2675 1489 2675 1487 2675 1477 2676 1487 2676 1466 2676 1466 2677 1487 2677 1485 2677 1466 2678 1485 2678 1467 2678 1467 2679 1485 2679 1483 2679 1467 2680 1483 2680 1472 2680 1472 2681 1483 2681 1481 2681 1472 2682 1481 2682 1470 2682 1496 2683 1433 2683 1497 2683 1497 2684 1433 2684 1434 2684 1497 2685 1434 2685 1498 2685 1498 2686 1434 2686 1495 2686 1498 2687 1495 2687 1499 2687 1499 2688 1495 2688 1479 2688 1499 2689 1479 2689 1500 2689 1500 2690 1479 2690 1478 2690 1501 2691 1502 2691 1503 2691 1503 2692 1502 2692 1504 2692 1504 2693 1428 2693 1503 2693 1503 2694 1428 2694 1430 2694 1503 2695 1430 2695 1505 2695 1505 2696 1430 2696 1482 2696 1505 2697 1482 2697 1506 2697 1506 2698 1482 2698 1484 2698 1506 2699 1484 2699 1507 2699 1507 2700 1484 2700 1486 2700 1507 2701 1486 2701 1508 2701 1508 2702 1486 2702 1488 2702 1508 2703 1488 2703 1509 2703 1509 2704 1488 2704 1490 2704 1509 2705 1490 2705 1510 2705 1510 2706 1490 2706 1492 2706 1510 2707 1492 2707 1511 2707 1511 2708 1492 2708 1494 2708 1511 2709 1494 2709 1512 2709 1512 2710 1494 2710 1432 2710 1512 2711 1432 2711 1513 2711 1513 2712 1432 2712 1431 2712 1427 2713 1514 2713 1425 2713 1425 2714 1514 2714 1515 2714 1425 2715 1515 2715 1516 2715 1516 2716 1515 2716 1517 2716 1516 2717 1517 2717 1518 2717 1518 2718 1517 2718 1519 2718 1518 2719 1519 2719 1520 2719 1520 2720 1519 2720 1521 2720 1522 2721 1523 2721 1524 2721 1524 2722 1523 2722 1525 2722 1524 2723 1525 2723 1526 2723 1521 2724 1527 2724 1520 2724 1520 2725 1527 2725 1528 2725 1520 2726 1528 2726 1529 2726 1529 2727 1528 2727 1530 2727 1529 2728 1530 2728 1522 2728 1522 2729 1530 2729 1531 2729 1522 2730 1531 2730 1523 2730 1525 2731 1532 2731 1533 2731 1439 2732 1450 2732 1440 2732 1440 2733 1450 2733 1534 2733 1440 2734 1534 2734 1448 2734 1445 2735 1535 2735 1443 2735 1443 2736 1535 2736 1536 2736 1443 2737 1536 2737 1452 2737 1452 2738 1536 2738 1537 2738 1452 2739 1537 2739 1450 2739 1450 2740 1537 2740 1538 2740 1450 2741 1538 2741 1534 2741 1539 2742 1468 2742 1540 2742 1540 2743 1468 2743 1470 2743 1540 2744 1470 2744 1541 2744 1541 2745 1470 2745 1481 2745 1541 2746 1481 2746 1542 2746 1542 2747 1481 2747 1480 2747 1457 2748 1543 2748 1436 2748 1436 2749 1543 2749 1446 2749 1436 2750 1446 2750 1437 2750 1437 2751 1446 2751 1447 2751 1437 2752 1447 2752 1464 2752 1525 2753 1533 2753 1526 2753 1526 2754 1533 2754 1544 2754 1526 2755 1544 2755 1545 2755 1545 2756 1501 2756 1526 2756 1526 2757 1501 2757 1503 2757 1526 2758 1503 2758 1524 2758 1524 2759 1503 2759 1505 2759 1524 2760 1505 2760 1522 2760 1522 2761 1505 2761 1506 2761 1522 2762 1506 2762 1529 2762 1529 2763 1506 2763 1507 2763 1529 2764 1507 2764 1520 2764 1520 2765 1507 2765 1508 2765 1520 2766 1508 2766 1518 2766 1518 2767 1508 2767 1509 2767 1518 2768 1509 2768 1516 2768 1516 2769 1509 2769 1510 2769 1516 2770 1510 2770 1425 2770 1425 2771 1510 2771 1511 2771 1425 2772 1511 2772 1426 2772 1426 2773 1511 2773 1512 2773 1426 2774 1512 2774 1546 2774 1546 2775 1512 2775 1513 2775 1546 2776 1513 2776 1547 2776 1548 2777 1549 2777 1547 2777 1547 2778 1549 2778 1550 2778 1547 2779 1550 2779 1546 2779 1546 2780 1550 2780 1551 2780 1546 2781 1551 2781 1426 2781 1426 2782 1551 2782 1552 2782 1426 2783 1552 2783 1427 2783 1448 2784 1548 2784 1447 2784 1447 2785 1548 2785 1547 2785 1447 2786 1547 2786 1464 2786 1464 2787 1547 2787 1513 2787 1464 2788 1513 2788 1463 2788 1463 2789 1513 2789 1431 2789 1463 2790 1431 2790 1462 2790 1462 2791 1431 2791 1433 2791 1462 2792 1433 2792 1461 2792 1461 2793 1433 2793 1496 2793 1553 2794 1554 2794 1555 2794 1556 2795 1557 2795 1558 2795 1559 2796 1560 2796 1561 2796 1562 2797 1563 2797 1564 2797 1565 2798 1566 2798 1567 2798 1566 2799 1565 2799 1568 2799 1569 2800 1570 2800 1571 2800 1572 2801 1573 2801 1574 2801 1575 2802 1576 2802 1577 2802 1578 2803 1579 2803 1580 2803 1580 2804 1579 2804 1581 2804 1582 2805 1579 2805 1583 2805 1583 2806 1579 2806 1584 2806 1582 2807 1585 2807 1579 2807 1579 2808 1585 2808 1586 2808 1579 2809 1586 2809 1581 2809 1587 2810 1588 2810 1589 2810 1589 2811 1588 2811 1590 2811 1589 2812 1590 2812 1591 2812 1591 2813 1590 2813 1592 2813 1591 2814 1592 2814 1579 2814 1593 2815 1589 2815 1594 2815 1594 2816 1589 2816 1591 2816 1594 2817 1591 2817 1595 2817 1595 2818 1591 2818 1579 2818 1595 2819 1579 2819 1596 2819 1596 2820 1579 2820 1578 2820 1597 2821 1598 2821 1599 2821 1599 2822 1598 2822 1600 2822 1599 2823 1600 2823 1601 2823 1602 2824 1603 2824 1604 2824 1604 2825 1603 2825 1605 2825 1606 2826 1607 2826 1608 2826 1608 2827 1607 2827 1609 2827 1608 2828 1609 2828 1610 2828 1610 2829 1609 2829 1611 2829 1612 2830 1611 2830 1613 2830 1613 2831 1611 2831 1609 2831 1613 2832 1609 2832 1614 2832 1614 2833 1609 2833 1607 2833 1615 2834 1612 2834 1616 2834 1616 2835 1612 2835 1613 2835 1616 2836 1613 2836 1617 2836 1617 2837 1613 2837 1614 2837 1617 2838 1614 2838 1618 2838 1618 2839 1614 2839 1607 2839 1618 2840 1607 2840 1619 2840 1619 2841 1607 2841 1606 2841 1619 2842 1606 2842 1620 2842 1621 2843 1622 2843 1605 2843 1605 2844 1622 2844 1623 2844 1571 2845 1624 2845 1625 2845 1625 2846 1624 2846 1626 2846 1625 2847 1626 2847 1627 2847 1574 2848 1628 2848 1572 2848 1572 2849 1628 2849 1629 2849 1572 2850 1629 2850 1630 2850 1630 2851 1629 2851 1631 2851 1630 2852 1631 2852 1632 2852 1573 2853 1572 2853 1633 2853 1633 2854 1572 2854 1630 2854 1633 2855 1630 2855 1634 2855 1634 2856 1630 2856 1632 2856 1634 2857 1632 2857 1635 2857 1571 2858 1570 2858 1624 2858 1624 2859 1570 2859 1636 2859 1624 2860 1636 2860 1626 2860 1637 2861 1638 2861 1639 2861 1637 2862 1639 2862 1640 2862 1639 2863 1641 2863 1640 2863 1640 2864 1641 2864 1642 2864 1640 2865 1642 2865 1643 2865 1643 2866 1642 2866 1644 2866 1643 2867 1644 2867 1567 2867 1554 2868 1562 2868 1555 2868 1555 2869 1562 2869 1564 2869 1555 2870 1564 2870 1645 2870 1645 2871 1564 2871 1646 2871 1645 2872 1646 2872 1647 2872 1647 2873 1646 2873 1637 2873 1647 2874 1637 2874 1648 2874 1648 2875 1637 2875 1640 2875 1648 2876 1640 2876 1649 2876 1649 2877 1640 2877 1643 2877 1649 2878 1643 2878 1650 2878 1650 2879 1643 2879 1567 2879 1650 2880 1567 2880 1651 2880 1651 2881 1567 2881 1566 2881 1651 2882 1566 2882 1652 2882 1652 2883 1566 2883 1568 2883 1652 2884 1568 2884 1653 2884 1653 2885 1568 2885 1654 2885 1653 2886 1654 2886 1655 2886 1644 2887 1656 2887 1567 2887 1567 2888 1656 2888 1657 2888 1567 2889 1657 2889 1565 2889 1565 2890 1657 2890 1658 2890 1565 2891 1658 2891 1659 2891 1628 2892 1655 2892 1629 2892 1629 2893 1655 2893 1654 2893 1629 2894 1654 2894 1631 2894 1631 2895 1654 2895 1568 2895 1631 2896 1568 2896 1632 2896 1632 2897 1568 2897 1565 2897 1632 2898 1565 2898 1635 2898 1635 2899 1565 2899 1659 2899 1635 2900 1659 2900 1660 2900 1496 2901 1497 2901 1661 2901 1661 2902 1497 2902 1498 2902 1661 2903 1498 2903 1662 2903 1663 2904 1664 2904 1460 2904 1626 2905 1665 2905 1664 2905 1664 2906 1665 2906 1459 2906 1664 2907 1459 2907 1460 2907 1602 2908 1665 2908 1603 2908 1603 2909 1665 2909 1626 2909 1603 2910 1626 2910 1605 2910 1605 2911 1626 2911 1666 2911 1605 2912 1666 2912 1667 2912 1667 2913 1666 2913 1576 2913 1667 2914 1576 2914 1605 2914 1605 2915 1576 2915 1575 2915 1605 2916 1575 2916 1621 2916 1560 2917 1559 2917 1668 2917 1668 2918 1559 2918 1669 2918 1668 2919 1669 2919 1670 2919 1669 2920 1671 2920 1670 2920 1670 2921 1671 2921 1672 2921 1670 2922 1672 2922 1663 2922 1663 2923 1672 2923 1673 2923 1663 2924 1673 2924 1664 2924 1664 2925 1673 2925 1674 2925 1664 2926 1674 2926 1626 2926 1498 2927 1499 2927 1662 2927 1662 2928 1499 2928 1500 2928 1662 2929 1500 2929 1675 2929 1460 2930 1461 2930 1663 2930 1663 2931 1461 2931 1496 2931 1663 2932 1496 2932 1670 2932 1670 2933 1496 2933 1661 2933 1670 2934 1661 2934 1668 2934 1668 2935 1661 2935 1662 2935 1668 2936 1662 2936 1560 2936 1560 2937 1662 2937 1675 2937 1560 2938 1675 2938 1561 2938 1676 2939 1475 2939 1465 2939 1676 2940 1465 2940 1677 2940 1475 2941 1676 2941 1476 2941 1476 2942 1676 2942 1678 2942 1476 2943 1678 2943 1478 2943 1539 2944 1679 2944 1468 2944 1468 2945 1679 2945 1680 2945 1465 2946 1474 2946 1677 2946 1677 2947 1474 2947 1473 2947 1677 2948 1473 2948 1681 2948 1681 2949 1473 2949 1471 2949 1681 2950 1471 2950 1680 2950 1680 2951 1471 2951 1469 2951 1680 2952 1469 2952 1468 2952 1500 2953 1478 2953 1675 2953 1675 2954 1478 2954 1678 2954 1675 2955 1678 2955 1561 2955 1561 2956 1678 2956 1682 2956 1561 2957 1682 2957 1559 2957 1559 2958 1682 2958 1620 2958 1559 2959 1620 2959 1669 2959 1669 2960 1620 2960 1606 2960 1669 2961 1606 2961 1671 2961 1671 2962 1606 2962 1608 2962 1671 2963 1608 2963 1672 2963 1672 2964 1608 2964 1610 2964 1672 2965 1610 2965 1673 2965 1673 2966 1610 2966 1611 2966 1673 2967 1611 2967 1674 2967 1674 2968 1611 2968 1612 2968 1674 2969 1612 2969 1626 2969 1626 2970 1612 2970 1615 2970 1596 2971 1683 2971 1595 2971 1595 2972 1683 2972 1684 2972 1595 2973 1684 2973 1685 2973 1593 2974 1451 2974 1449 2974 1449 2975 1599 2975 1593 2975 1593 2976 1599 2976 1601 2976 1593 2977 1601 2977 1589 2977 1589 2978 1601 2978 1686 2978 1589 2979 1686 2979 1587 2979 1451 2980 1593 2980 1456 2980 1456 2981 1593 2981 1594 2981 1456 2982 1594 2982 1455 2982 1455 2983 1594 2983 1595 2983 1455 2984 1595 2984 1454 2984 1454 2985 1595 2985 1685 2985 1454 2986 1685 2986 1453 2986 1638 2987 1637 2987 1687 2987 1687 2988 1637 2988 1646 2988 1687 2989 1646 2989 1688 2989 1688 2990 1646 2990 1564 2990 1688 2991 1564 2991 1558 2991 1558 2992 1564 2992 1563 2992 1558 2993 1563 2993 1556 2993 1623 2994 1689 2994 1605 2994 1605 2995 1689 2995 1690 2995 1605 2996 1690 2996 1604 2996 1604 2997 1690 2997 1691 2997 1604 2998 1691 2998 1597 2998 1597 2999 1691 2999 1692 2999 1597 3000 1692 3000 1598 3000 1679 3001 1553 3001 1680 3001 1680 3002 1553 3002 1555 3002 1680 3003 1555 3003 1681 3003 1681 3004 1555 3004 1645 3004 1681 3005 1645 3005 1677 3005 1677 3006 1645 3006 1647 3006 1677 3007 1647 3007 1676 3007 1676 3008 1647 3008 1648 3008 1676 3009 1648 3009 1678 3009 1678 3010 1648 3010 1649 3010 1678 3011 1649 3011 1682 3011 1682 3012 1649 3012 1650 3012 1682 3013 1650 3013 1620 3013 1620 3014 1650 3014 1651 3014 1620 3015 1651 3015 1619 3015 1619 3016 1651 3016 1652 3016 1619 3017 1652 3017 1618 3017 1618 3018 1652 3018 1653 3018 1618 3019 1653 3019 1617 3019 1617 3020 1653 3020 1655 3020 1617 3021 1655 3021 1616 3021 1616 3022 1655 3022 1628 3022 1616 3023 1628 3023 1615 3023 1615 3024 1628 3024 1574 3024 1615 3025 1574 3025 1626 3025 1626 3026 1574 3026 1573 3026 1626 3027 1573 3027 1627 3027 1627 3028 1573 3028 1633 3028 1627 3029 1633 3029 1625 3029 1625 3030 1633 3030 1634 3030 1625 3031 1634 3031 1571 3031 1571 3032 1634 3032 1635 3032 1571 3033 1635 3033 1569 3033 1569 3034 1635 3034 1660 3034 1449 3035 1439 3035 1599 3035 1599 3036 1439 3036 1438 3036 1599 3037 1438 3037 1597 3037 1597 3038 1438 3038 1446 3038 1597 3039 1446 3039 1604 3039 1604 3040 1446 3040 1543 3040 1604 3041 1543 3041 1602 3041 1602 3042 1543 3042 1457 3042 1602 3043 1457 3043 1665 3043 1665 3044 1457 3044 1458 3044 1665 3045 1458 3045 1459 3045 1693 3046 1694 3046 1695 3046 1696 3047 1697 3047 1698 3047 1699 3048 1700 3048 1701 3048 1702 3049 1703 3049 1704 3049 1705 3050 1584 3050 1579 3050 1706 3051 1707 3051 1708 3051 1709 3052 1710 3052 1711 3052 1709 3053 1711 3053 1712 3053 1713 3054 1714 3054 1715 3054 1715 3055 1714 3055 1716 3055 1715 3056 1716 3056 1717 3056 1718 3057 1712 3057 1719 3057 1719 3058 1712 3058 1711 3058 1719 3059 1711 3059 1720 3059 1720 3060 1711 3060 1721 3060 1720 3061 1721 3061 1722 3061 1722 3062 1721 3062 1717 3062 1722 3063 1717 3063 1723 3063 1723 3064 1717 3064 1716 3064 1724 3065 1725 3065 1726 3065 1726 3066 1725 3066 1727 3066 1727 3067 1725 3067 1728 3067 1727 3068 1728 3068 1729 3068 1726 3069 1730 3069 1724 3069 1724 3070 1730 3070 1731 3070 1724 3071 1731 3071 1732 3071 1732 3072 1731 3072 1733 3072 1732 3073 1733 3073 1734 3073 1733 3074 1735 3074 1734 3074 1734 3075 1735 3075 1736 3075 1734 3076 1736 3076 1737 3076 1737 3077 1736 3077 1738 3077 1737 3078 1738 3078 1739 3078 1739 3079 1738 3079 1740 3079 1739 3080 1740 3080 1741 3080 1689 3081 1623 3081 1742 3081 1742 3082 1623 3082 1622 3082 1622 3083 1621 3083 1743 3083 1621 3084 1575 3084 1743 3084 1743 3085 1575 3085 1577 3085 1743 3086 1577 3086 1576 3086 1622 3087 1743 3087 1742 3087 1742 3088 1743 3088 1744 3088 1742 3089 1744 3089 1689 3089 1666 3090 1745 3090 1746 3090 1666 3091 1626 3091 1745 3091 1745 3092 1626 3092 1636 3092 1745 3093 1636 3093 1747 3093 1747 3094 1636 3094 1570 3094 1748 3095 1749 3095 1750 3095 1750 3096 1749 3096 1751 3096 1752 3097 1569 3097 1753 3097 1753 3098 1569 3098 1660 3098 1753 3099 1660 3099 1659 3099 1754 3100 1755 3100 1656 3100 1749 3101 1752 3101 1751 3101 1751 3102 1752 3102 1753 3102 1751 3103 1753 3103 1756 3103 1756 3104 1753 3104 1659 3104 1756 3105 1659 3105 1757 3105 1757 3106 1659 3106 1658 3106 1757 3107 1658 3107 1755 3107 1755 3108 1658 3108 1657 3108 1755 3109 1657 3109 1656 3109 1656 3110 1644 3110 1754 3110 1754 3111 1644 3111 1642 3111 1754 3112 1642 3112 1758 3112 1758 3113 1642 3113 1641 3113 1758 3114 1641 3114 1639 3114 1759 3115 1760 3115 1638 3115 1638 3116 1687 3116 1759 3116 1759 3117 1687 3117 1688 3117 1759 3118 1688 3118 1761 3118 1761 3119 1688 3119 1558 3119 1761 3120 1558 3120 1557 3120 1557 3121 1762 3121 1761 3121 1761 3122 1762 3122 1763 3122 1761 3123 1763 3123 1764 3123 1765 3124 1766 3124 1579 3124 1579 3125 1766 3125 1767 3125 1579 3126 1767 3126 1705 3126 1768 3127 1769 3127 1579 3127 1579 3128 1769 3128 1770 3128 1579 3129 1770 3129 1765 3129 1771 3130 1772 3130 1768 3130 1768 3131 1772 3131 1773 3131 1768 3132 1773 3132 1769 3132 1587 3133 1774 3133 1588 3133 1588 3134 1774 3134 1775 3134 1588 3135 1775 3135 1590 3135 1590 3136 1775 3136 1776 3136 1777 3137 1778 3137 1779 3137 1703 3138 1771 3138 1704 3138 1704 3139 1771 3139 1768 3139 1704 3140 1768 3140 1780 3140 1587 3141 1686 3141 1774 3141 1774 3142 1686 3142 1601 3142 1774 3143 1601 3143 1781 3143 1776 3144 1775 3144 1778 3144 1778 3145 1775 3145 1774 3145 1778 3146 1774 3146 1779 3146 1779 3147 1774 3147 1781 3147 1779 3148 1781 3148 1782 3148 1783 3149 1600 3149 1598 3149 1783 3150 1598 3150 1784 3150 1598 3151 1692 3151 1784 3151 1784 3152 1692 3152 1691 3152 1784 3153 1691 3153 1744 3153 1744 3154 1691 3154 1690 3154 1744 3155 1690 3155 1689 3155 1601 3156 1600 3156 1781 3156 1781 3157 1600 3157 1783 3157 1781 3158 1783 3158 1782 3158 1782 3159 1783 3159 1784 3159 1782 3160 1784 3160 1785 3160 1785 3161 1784 3161 1744 3161 1785 3162 1744 3162 1786 3162 1786 3163 1744 3163 1743 3163 1786 3164 1743 3164 1746 3164 1746 3165 1743 3165 1576 3165 1746 3166 1576 3166 1666 3166 1777 3167 1779 3167 1787 3167 1787 3168 1779 3168 1782 3168 1787 3169 1782 3169 1788 3169 1788 3170 1782 3170 1785 3170 1788 3171 1785 3171 1789 3171 1789 3172 1785 3172 1786 3172 1789 3173 1786 3173 1790 3173 1790 3174 1786 3174 1746 3174 1790 3175 1746 3175 1748 3175 1748 3176 1746 3176 1745 3176 1748 3177 1745 3177 1749 3177 1749 3178 1745 3178 1747 3178 1749 3179 1747 3179 1752 3179 1752 3180 1747 3180 1570 3180 1752 3181 1570 3181 1569 3181 1788 3182 1791 3182 1787 3182 1787 3183 1791 3183 1780 3183 1787 3184 1780 3184 1777 3184 1777 3185 1780 3185 1768 3185 1777 3186 1768 3186 1778 3186 1778 3187 1768 3187 1579 3187 1778 3188 1579 3188 1776 3188 1776 3189 1579 3189 1592 3189 1776 3190 1592 3190 1590 3190 1750 3191 1792 3191 1748 3191 1748 3192 1792 3192 1793 3192 1748 3193 1793 3193 1790 3193 1790 3194 1793 3194 1794 3194 1790 3195 1794 3195 1789 3195 1789 3196 1794 3196 1795 3196 1789 3197 1795 3197 1788 3197 1788 3198 1795 3198 1796 3198 1788 3199 1796 3199 1791 3199 1700 3200 1702 3200 1701 3200 1701 3201 1702 3201 1704 3201 1701 3202 1704 3202 1797 3202 1797 3203 1704 3203 1780 3203 1797 3204 1780 3204 1798 3204 1798 3205 1780 3205 1791 3205 1798 3206 1791 3206 1799 3206 1799 3207 1791 3207 1796 3207 1799 3208 1796 3208 1800 3208 1800 3209 1796 3209 1795 3209 1800 3210 1795 3210 1801 3210 1801 3211 1795 3211 1794 3211 1801 3212 1794 3212 1802 3212 1802 3213 1794 3213 1793 3213 1802 3214 1793 3214 1803 3214 1803 3215 1793 3215 1792 3215 1803 3216 1792 3216 1804 3216 1804 3217 1792 3217 1750 3217 1804 3218 1750 3218 1805 3218 1805 3219 1750 3219 1751 3219 1805 3220 1751 3220 1806 3220 1806 3221 1751 3221 1756 3221 1806 3222 1756 3222 1807 3222 1807 3223 1756 3223 1757 3223 1807 3224 1757 3224 1808 3224 1808 3225 1757 3225 1755 3225 1808 3226 1755 3226 1809 3226 1809 3227 1755 3227 1754 3227 1809 3228 1754 3228 1810 3228 1810 3229 1754 3229 1758 3229 1810 3230 1758 3230 1760 3230 1760 3231 1758 3231 1639 3231 1760 3232 1639 3232 1638 3232 1729 3233 1728 3233 1811 3233 1811 3234 1728 3234 1708 3234 1811 3235 1708 3235 1812 3235 1812 3236 1708 3236 1707 3236 1812 3237 1707 3237 1813 3237 1740 3238 1814 3238 1741 3238 1741 3239 1814 3239 1815 3239 1741 3240 1815 3240 1816 3240 1816 3241 1815 3241 1817 3241 1816 3242 1817 3242 1818 3242 1818 3243 1817 3243 1819 3243 1818 3244 1819 3244 1820 3244 1820 3245 1819 3245 1821 3245 1820 3246 1821 3246 1696 3246 1696 3247 1821 3247 1822 3247 1696 3248 1822 3248 1697 3248 1694 3249 1706 3249 1695 3249 1695 3250 1706 3250 1708 3250 1695 3251 1708 3251 1823 3251 1823 3252 1708 3252 1728 3252 1823 3253 1728 3253 1824 3253 1824 3254 1728 3254 1725 3254 1824 3255 1725 3255 1825 3255 1825 3256 1725 3256 1724 3256 1825 3257 1724 3257 1826 3257 1826 3258 1724 3258 1732 3258 1826 3259 1732 3259 1827 3259 1827 3260 1732 3260 1734 3260 1827 3261 1734 3261 1828 3261 1828 3262 1734 3262 1737 3262 1828 3263 1737 3263 1829 3263 1829 3264 1737 3264 1739 3264 1829 3265 1739 3265 1830 3265 1830 3266 1739 3266 1741 3266 1830 3267 1741 3267 1831 3267 1831 3268 1741 3268 1816 3268 1831 3269 1816 3269 1832 3269 1832 3270 1816 3270 1818 3270 1832 3271 1818 3271 1833 3271 1833 3272 1818 3272 1820 3272 1833 3273 1820 3273 1834 3273 1834 3274 1820 3274 1696 3274 1834 3275 1696 3275 1713 3275 1713 3276 1696 3276 1698 3276 1713 3277 1698 3277 1714 3277 1764 3278 1693 3278 1761 3278 1761 3279 1693 3279 1695 3279 1761 3280 1695 3280 1759 3280 1759 3281 1695 3281 1823 3281 1759 3282 1823 3282 1760 3282 1760 3283 1823 3283 1824 3283 1760 3284 1824 3284 1810 3284 1810 3285 1824 3285 1825 3285 1810 3286 1825 3286 1809 3286 1809 3287 1825 3287 1826 3287 1809 3288 1826 3288 1808 3288 1808 3289 1826 3289 1827 3289 1808 3290 1827 3290 1807 3290 1807 3291 1827 3291 1828 3291 1807 3292 1828 3292 1806 3292 1806 3293 1828 3293 1829 3293 1806 3294 1829 3294 1805 3294 1805 3295 1829 3295 1830 3295 1805 3296 1830 3296 1804 3296 1804 3297 1830 3297 1831 3297 1804 3298 1831 3298 1803 3298 1803 3299 1831 3299 1832 3299 1803 3300 1832 3300 1802 3300 1802 3301 1832 3301 1833 3301 1802 3302 1833 3302 1801 3302 1801 3303 1833 3303 1834 3303 1801 3304 1834 3304 1800 3304 1800 3305 1834 3305 1713 3305 1800 3306 1713 3306 1799 3306 1799 3307 1713 3307 1715 3307 1799 3308 1715 3308 1798 3308 1798 3309 1715 3309 1717 3309 1798 3310 1717 3310 1797 3310 1797 3311 1717 3311 1721 3311 1797 3312 1721 3312 1701 3312 1701 3313 1721 3313 1711 3313 1701 3314 1711 3314 1699 3314 1699 3315 1711 3315 1710 3315 1835 3316 1836 3316 1837 3316 1453 3317 1685 3317 1838 3317 1585 3318 1582 3318 1839 3318 1840 3319 1836 3319 1841 3319 1842 3320 1843 3320 1844 3320 1845 3321 1846 3321 1847 3321 1847 3322 1846 3322 1848 3322 1847 3323 1848 3323 1849 3323 1850 3324 1851 3324 1852 3324 1852 3325 1851 3325 1853 3325 1843 3326 1842 3326 1854 3326 1849 3327 1855 3327 1847 3327 1847 3328 1855 3328 1856 3328 1847 3329 1856 3329 1845 3329 1845 3330 1856 3330 1857 3330 1858 3331 1853 3331 1857 3331 1857 3332 1853 3332 1851 3332 1857 3333 1851 3333 1845 3333 1845 3334 1851 3334 1850 3334 1845 3335 1850 3335 1846 3335 1840 3336 1841 3336 1859 3336 1860 3337 1859 3337 1861 3337 1861 3338 1859 3338 1841 3338 1861 3339 1841 3339 1862 3339 1862 3340 1841 3340 1863 3340 1862 3341 1863 3341 1864 3341 1835 3342 1865 3342 1858 3342 1858 3343 1865 3343 1866 3343 1858 3344 1866 3344 1853 3344 1442 3345 1441 3345 1867 3345 1867 3346 1441 3346 1868 3346 1839 3347 1582 3347 1869 3347 1869 3348 1582 3348 1583 3348 1869 3349 1583 3349 1584 3349 1684 3350 1683 3350 1870 3350 1870 3351 1683 3351 1596 3351 1578 3352 1580 3352 1871 3352 1871 3353 1580 3353 1581 3353 1871 3354 1581 3354 1839 3354 1839 3355 1581 3355 1586 3355 1839 3356 1586 3356 1585 3356 1872 3357 1870 3357 1871 3357 1871 3358 1870 3358 1596 3358 1871 3359 1596 3359 1578 3359 1685 3360 1684 3360 1838 3360 1838 3361 1684 3361 1870 3361 1838 3362 1870 3362 1854 3362 1854 3363 1870 3363 1872 3363 1854 3364 1872 3364 1843 3364 1842 3365 1864 3365 1854 3365 1854 3366 1864 3366 1873 3366 1854 3367 1873 3367 1838 3367 1838 3368 1873 3368 1868 3368 1838 3369 1868 3369 1453 3369 1453 3370 1868 3370 1441 3370 1835 3371 1874 3371 1865 3371 1865 3372 1874 3372 1875 3372 1865 3373 1875 3373 1866 3373 1866 3374 1875 3374 1876 3374 1866 3375 1876 3375 1853 3375 1853 3376 1876 3376 1877 3376 1853 3377 1877 3377 1852 3377 1855 3378 1863 3378 1856 3378 1856 3379 1863 3379 1841 3379 1856 3380 1841 3380 1857 3380 1857 3381 1841 3381 1836 3381 1857 3382 1836 3382 1858 3382 1858 3383 1836 3383 1835 3383 1445 3384 1444 3384 1878 3384 1878 3385 1444 3385 1849 3385 1878 3386 1849 3386 1879 3386 1879 3387 1849 3387 1848 3387 1864 3388 1863 3388 1873 3388 1873 3389 1863 3389 1855 3389 1873 3390 1855 3390 1868 3390 1868 3391 1855 3391 1849 3391 1868 3392 1849 3392 1867 3392 1867 3393 1849 3393 1444 3393 1867 3394 1444 3394 1442 3394 1880 3395 1881 3395 1882 3395 1872 3396 1871 3396 1883 3396 1884 3397 1885 3397 1886 3397 1887 3398 1888 3398 1889 3398 1889 3399 1888 3399 1890 3399 1891 3400 1835 3400 1892 3400 1893 3401 1894 3401 1895 3401 1836 3402 1896 3402 1835 3402 1862 3403 1864 3403 1897 3403 1898 3404 1899 3404 1900 3404 1900 3405 1899 3405 1901 3405 1900 3406 1901 3406 1275 3406 1864 3407 1842 3407 1902 3407 1902 3408 1842 3408 1844 3408 1902 3409 1844 3409 1843 3409 1859 3410 1861 3410 1840 3410 1840 3411 1861 3411 1903 3411 1840 3412 1903 3412 1836 3412 1836 3413 1903 3413 1904 3413 1836 3414 1904 3414 1896 3414 1905 3415 1906 3415 1907 3415 1907 3416 1906 3416 1904 3416 1907 3417 1904 3417 1897 3417 1897 3418 1904 3418 1903 3418 1897 3419 1903 3419 1862 3419 1862 3420 1903 3420 1861 3420 1908 3421 1909 3421 1910 3421 1910 3422 1909 3422 1911 3422 1835 3423 1896 3423 1911 3423 1911 3424 1896 3424 1912 3424 1911 3425 1912 3425 1910 3425 1885 3426 1913 3426 1886 3426 1886 3427 1913 3427 1914 3427 1886 3428 1914 3428 1915 3428 1915 3429 1914 3429 1916 3429 1915 3430 1916 3430 1917 3430 1918 3431 1916 3431 1919 3431 1919 3432 1916 3432 1914 3432 1919 3433 1914 3433 1920 3433 1920 3434 1914 3434 1913 3434 1917 3435 1916 3435 1921 3435 1921 3436 1916 3436 1918 3436 1921 3437 1918 3437 1922 3437 1922 3438 1918 3438 1923 3438 1922 3439 1923 3439 1924 3439 1925 3440 1926 3440 1927 3440 1927 3441 1926 3441 1923 3441 1927 3442 1923 3442 1928 3442 1928 3443 1923 3443 1918 3443 1928 3444 1918 3444 1929 3444 1929 3445 1918 3445 1919 3445 1930 3446 1917 3446 1931 3446 1931 3447 1917 3447 1921 3447 1931 3448 1921 3448 1932 3448 1932 3449 1921 3449 1922 3449 1932 3450 1922 3450 1933 3450 1933 3451 1922 3451 1924 3451 1933 3452 1924 3452 1934 3452 1891 3453 1892 3453 1935 3453 1936 3454 1937 3454 1938 3454 1938 3455 1937 3455 1939 3455 1938 3456 1939 3456 1940 3456 1940 3457 1939 3457 1941 3457 1940 3458 1941 3458 1942 3458 1943 3459 1944 3459 1945 3459 1946 3460 1947 3460 1948 3460 1948 3461 1947 3461 1949 3461 1950 3462 1941 3462 1951 3462 1951 3463 1941 3463 1939 3463 1951 3464 1939 3464 1952 3464 1952 3465 1939 3465 1937 3465 1952 3466 1937 3466 1953 3466 1953 3467 1937 3467 1936 3467 1953 3468 1936 3468 1954 3468 1946 3469 1955 3469 1947 3469 1947 3470 1955 3470 1945 3470 1947 3471 1945 3471 1949 3471 1949 3472 1945 3472 1944 3472 1906 3473 1956 3473 1904 3473 1904 3474 1956 3474 1954 3474 1904 3475 1954 3475 1896 3475 1896 3476 1954 3476 1936 3476 1896 3477 1936 3477 1912 3477 1912 3478 1936 3478 1938 3478 1912 3479 1938 3479 1910 3479 1910 3480 1938 3480 1940 3480 1910 3481 1940 3481 1908 3481 1908 3482 1940 3482 1942 3482 1935 3483 1957 3483 1891 3483 1891 3484 1957 3484 1958 3484 1891 3485 1958 3485 1835 3485 1959 3486 1960 3486 1961 3486 1961 3487 1960 3487 1962 3487 1961 3488 1962 3488 1963 3488 1957 3489 1964 3489 1958 3489 1958 3490 1964 3490 1835 3490 1935 3491 1961 3491 1957 3491 1957 3492 1961 3492 1963 3492 1957 3493 1963 3493 1964 3493 1964 3494 1963 3494 1965 3494 1964 3495 1965 3495 1966 3495 1966 3496 1965 3496 1967 3496 1950 3497 1968 3497 1941 3497 1941 3498 1968 3498 1893 3498 1941 3499 1893 3499 1942 3499 1942 3500 1893 3500 1895 3500 1942 3501 1895 3501 1969 3501 1925 3502 1970 3502 1926 3502 1926 3503 1970 3503 1944 3503 1926 3504 1944 3504 1923 3504 1923 3505 1944 3505 1943 3505 1923 3506 1943 3506 1924 3506 1924 3507 1943 3507 1971 3507 1924 3508 1971 3508 1934 3508 1972 3509 1973 3509 1900 3509 1900 3510 1973 3510 1974 3510 1900 3511 1974 3511 1898 3511 1975 3512 1976 3512 1977 3512 1977 3513 1978 3513 1975 3513 1975 3514 1978 3514 1979 3514 1975 3515 1979 3515 1980 3515 1889 3516 1981 3516 1887 3516 1887 3517 1981 3517 1982 3517 1887 3518 1982 3518 1976 3518 1976 3519 1982 3519 1983 3519 1976 3520 1983 3520 1977 3520 1984 3521 1975 3521 1900 3521 1900 3522 1975 3522 1980 3522 1900 3523 1980 3523 1972 3523 1930 3524 1888 3524 1917 3524 1917 3525 1888 3525 1887 3525 1917 3526 1887 3526 1915 3526 1915 3527 1887 3527 1976 3527 1915 3528 1976 3528 1886 3528 1886 3529 1976 3529 1975 3529 1886 3530 1975 3530 1884 3530 1884 3531 1975 3531 1984 3531 1934 3532 1985 3532 1933 3532 1933 3533 1985 3533 1986 3533 1933 3534 1986 3534 1932 3534 1932 3535 1986 3535 1987 3535 1932 3536 1987 3536 1931 3536 1931 3537 1987 3537 1988 3537 1931 3538 1988 3538 1930 3538 1930 3539 1988 3539 1989 3539 1930 3540 1989 3540 1888 3540 1888 3541 1989 3541 1882 3541 1888 3542 1882 3542 1890 3542 1890 3543 1882 3543 1881 3543 1584 3544 1705 3544 1869 3544 1869 3545 1705 3545 1839 3545 1705 3546 1767 3546 1839 3546 1839 3547 1767 3547 1766 3547 1839 3548 1766 3548 1871 3548 1871 3549 1766 3549 1765 3549 1765 3550 1770 3550 1871 3550 1871 3551 1770 3551 1769 3551 1871 3552 1769 3552 1883 3552 1883 3553 1769 3553 1773 3553 1883 3554 1773 3554 1772 3554 1772 3555 1771 3555 1883 3555 1883 3556 1771 3556 1703 3556 1883 3557 1703 3557 1990 3557 1699 3558 1991 3558 1700 3558 1700 3559 1991 3559 1990 3559 1700 3560 1990 3560 1702 3560 1702 3561 1990 3561 1703 3561 1991 3562 1992 3562 1990 3562 1990 3563 1992 3563 1993 3563 1990 3564 1993 3564 1883 3564 1883 3565 1993 3565 1902 3565 1883 3566 1902 3566 1872 3566 1872 3567 1902 3567 1843 3567 1864 3568 1902 3568 1897 3568 1897 3569 1902 3569 1993 3569 1897 3570 1993 3570 1907 3570 1907 3571 1993 3571 1992 3571 1907 3572 1992 3572 1905 3572 1905 3573 1992 3573 1991 3573 1905 3574 1991 3574 1994 3574 1994 3575 1991 3575 1699 3575 1994 3576 1699 3576 1710 3576 1710 3577 1709 3577 1994 3577 1994 3578 1709 3578 1712 3578 1994 3579 1712 3579 1718 3579 1967 3580 1995 3580 1966 3580 1966 3581 1995 3581 1996 3581 1966 3582 1996 3582 1964 3582 1964 3583 1996 3583 1835 3583 1969 3584 1959 3584 1942 3584 1942 3585 1959 3585 1961 3585 1942 3586 1961 3586 1908 3586 1908 3587 1961 3587 1935 3587 1908 3588 1935 3588 1909 3588 1909 3589 1935 3589 1892 3589 1909 3590 1892 3590 1911 3590 1911 3591 1892 3591 1835 3591 1955 3592 1968 3592 1945 3592 1945 3593 1968 3593 1950 3593 1945 3594 1950 3594 1943 3594 1943 3595 1950 3595 1951 3595 1943 3596 1951 3596 1971 3596 1971 3597 1951 3597 1952 3597 1971 3598 1952 3598 1934 3598 1934 3599 1952 3599 1953 3599 1934 3600 1953 3600 1985 3600 1985 3601 1953 3601 1954 3601 1985 3602 1954 3602 1986 3602 1986 3603 1954 3603 1956 3603 1986 3604 1956 3604 1987 3604 1987 3605 1956 3605 1906 3605 1987 3606 1906 3606 1988 3606 1988 3607 1906 3607 1905 3607 1988 3608 1905 3608 1989 3608 1989 3609 1905 3609 1994 3609 1989 3610 1994 3610 1882 3610 1882 3611 1994 3611 1718 3611 1882 3612 1718 3612 1880 3612 1997 3613 1998 3613 1999 3613 2000 3614 2001 3614 2002 3614 2003 3615 2004 3615 2005 3615 2006 3616 2007 3616 2008 3616 2008 3617 2007 3617 2003 3617 2003 3618 2005 3618 2008 3618 2008 3619 2005 3619 2009 3619 2008 3620 2009 3620 2010 3620 2011 3621 2012 3621 2013 3621 2013 3622 2012 3622 2014 3622 2013 3623 2014 3623 2015 3623 2011 3624 2016 3624 2012 3624 2012 3625 2016 3625 2017 3625 2012 3626 2017 3626 2009 3626 2009 3627 2017 3627 2018 3627 2009 3628 2018 3628 2010 3628 2002 3629 2001 3629 2019 3629 2001 3630 2020 3630 2019 3630 2019 3631 2020 3631 2021 3631 2019 3632 2021 3632 2014 3632 2014 3633 2021 3633 2022 3633 2014 3634 2022 3634 2015 3634 2000 3635 2002 3635 2023 3635 2023 3636 2002 3636 2024 3636 2023 3637 2024 3637 2025 3637 2026 3638 2027 3638 2024 3638 2024 3639 2027 3639 2028 3639 2024 3640 2028 3640 2025 3640 2029 3641 2030 3641 2031 3641 2030 3642 2029 3642 2032 3642 2032 3643 2029 3643 2033 3643 2032 3644 2033 3644 2034 3644 2034 3645 2033 3645 2035 3645 2035 3646 2033 3646 2036 3646 2035 3647 2036 3647 2037 3647 2038 3648 2039 3648 2040 3648 2040 3649 2039 3649 2041 3649 2040 3650 2041 3650 2042 3650 2037 3651 2036 3651 2043 3651 2043 3652 2036 3652 2041 3652 2043 3653 2041 3653 2044 3653 2044 3654 2041 3654 2039 3654 2044 3655 2039 3655 2045 3655 2046 3656 2047 3656 2048 3656 2048 3657 2047 3657 2049 3657 2050 3658 2051 3658 2052 3658 2052 3659 2051 3659 2053 3659 2052 3660 2053 3660 2054 3660 2054 3661 2053 3661 2055 3661 2050 3662 2056 3662 2051 3662 2051 3663 2056 3663 2057 3663 2051 3664 2057 3664 2058 3664 2057 3665 2059 3665 2058 3665 2058 3666 2059 3666 2060 3666 2058 3667 2060 3667 2046 3667 2046 3668 2060 3668 2061 3668 2046 3669 2061 3669 2047 3669 2055 3670 2053 3670 2062 3670 2062 3671 2053 3671 2063 3671 2062 3672 2063 3672 2064 3672 2064 3673 2063 3673 2065 3673 2064 3674 2065 3674 2066 3674 2031 3675 2027 3675 2029 3675 2029 3676 2027 3676 2026 3676 2029 3677 2026 3677 2033 3677 2033 3678 2026 3678 2067 3678 2033 3679 2067 3679 2036 3679 2036 3680 2067 3680 2068 3680 2036 3681 2068 3681 2041 3681 2041 3682 2068 3682 1999 3682 2041 3683 1999 3683 2042 3683 2042 3684 1999 3684 1998 3684 1539 3685 2069 3685 1679 3685 1679 3686 2069 3686 2070 3686 2071 3687 1554 3687 2070 3687 2070 3688 1554 3688 1553 3688 2070 3689 1553 3689 1679 3689 1556 3690 1563 3690 2071 3690 2071 3691 1563 3691 1562 3691 2071 3692 1562 3692 1554 3692 2072 3693 1763 3693 1762 3693 2072 3694 1762 3694 2071 3694 2071 3695 1762 3695 1557 3695 2071 3696 1557 3696 1556 3696 1763 3697 2072 3697 1764 3697 1764 3698 2072 3698 2073 3698 1764 3699 2073 3699 1693 3699 2049 3700 1813 3700 2048 3700 2048 3701 1813 3701 1707 3701 2048 3702 1707 3702 2074 3702 2074 3703 1707 3703 1706 3703 2074 3704 1706 3704 2073 3704 2073 3705 1706 3705 1694 3705 2073 3706 1694 3706 1693 3706 2004 3707 2065 3707 2005 3707 2005 3708 2065 3708 2063 3708 2005 3709 2063 3709 2009 3709 2009 3710 2063 3710 2053 3710 2009 3711 2053 3711 2012 3711 2012 3712 2053 3712 2051 3712 2012 3713 2051 3713 2014 3713 2014 3714 2051 3714 2058 3714 2014 3715 2058 3715 2019 3715 2019 3716 2058 3716 2046 3716 2019 3717 2046 3717 2002 3717 2002 3718 2046 3718 2048 3718 2002 3719 2048 3719 2024 3719 2024 3720 2048 3720 2074 3720 2024 3721 2074 3721 2026 3721 2026 3722 2074 3722 2073 3722 2026 3723 2073 3723 2067 3723 2067 3724 2073 3724 2072 3724 2067 3725 2072 3725 2068 3725 2068 3726 2072 3726 2071 3726 2068 3727 2071 3727 1999 3727 1999 3728 2071 3728 2070 3728 1999 3729 2070 3729 1997 3729 1997 3730 2070 3730 2069 3730 1997 3731 2069 3731 2075 3731 2065 3732 2004 3732 2076 3732 2077 3733 2078 3733 2079 3733 2040 3734 2042 3734 2080 3734 2081 3735 2082 3735 2083 3735 2084 3736 2085 3736 2086 3736 2086 3737 2085 3737 2087 3737 2086 3738 2087 3738 2088 3738 2088 3739 2087 3739 2089 3739 2088 3740 2089 3740 2090 3740 2091 3741 2092 3741 2093 3741 2093 3742 2092 3742 2094 3742 2093 3743 2094 3743 2095 3743 2095 3744 2094 3744 2083 3744 2095 3745 2083 3745 2096 3745 2096 3746 2083 3746 2082 3746 2097 3747 2098 3747 2099 3747 2099 3748 2098 3748 2081 3748 2100 3749 2101 3749 2097 3749 2003 3750 2007 3750 2102 3750 2102 3751 2007 3751 2103 3751 2101 3752 2100 3752 2104 3752 2104 3753 2100 3753 2102 3753 2104 3754 2102 3754 2105 3754 2105 3755 2102 3755 2103 3755 2105 3756 2103 3756 2106 3756 2038 3757 2040 3757 2107 3757 2107 3758 2040 3758 2108 3758 2040 3759 2080 3759 2108 3759 2108 3760 2080 3760 2109 3760 2108 3761 2109 3761 2110 3761 2079 3762 2078 3762 2109 3762 2109 3763 2078 3763 2111 3763 2109 3764 2111 3764 2110 3764 2112 3765 2113 3765 2114 3765 2114 3766 2113 3766 2115 3766 2114 3767 2115 3767 2079 3767 2079 3768 2115 3768 2116 3768 2079 3769 2116 3769 2077 3769 1480 3770 2117 3770 1542 3770 1542 3771 2117 3771 2075 3771 1542 3772 2075 3772 1541 3772 1480 3773 1429 3773 2117 3773 2117 3774 1429 3774 1428 3774 2117 3775 1428 3775 2118 3775 1501 3776 2119 3776 1502 3776 1502 3777 2119 3777 2118 3777 1502 3778 2118 3778 1504 3778 1504 3779 2118 3779 1428 3779 1533 3780 2120 3780 1544 3780 1544 3781 2120 3781 2119 3781 1544 3782 2119 3782 1545 3782 1545 3783 2119 3783 1501 3783 1541 3784 2075 3784 1540 3784 1540 3785 2075 3785 2069 3785 1540 3786 2069 3786 1539 3786 2042 3787 1998 3787 2080 3787 2080 3788 1998 3788 2121 3788 2080 3789 2121 3789 2109 3789 2109 3790 2121 3790 2122 3790 2109 3791 2122 3791 2079 3791 2079 3792 2122 3792 2123 3792 2079 3793 2123 3793 2114 3793 2114 3794 2123 3794 2124 3794 2114 3795 2124 3795 2112 3795 2112 3796 2124 3796 2088 3796 2112 3797 2088 3797 2125 3797 2125 3798 2088 3798 2090 3798 2100 3799 2126 3799 2102 3799 2102 3800 2126 3800 2076 3800 2102 3801 2076 3801 2003 3801 2003 3802 2076 3802 2004 3802 2127 3803 1339 3803 1338 3803 2097 3804 2099 3804 2100 3804 2100 3805 2099 3805 2127 3805 2100 3806 2127 3806 2126 3806 2126 3807 2127 3807 1338 3807 2126 3808 1338 3808 1340 3808 1340 3809 2128 3809 2126 3809 2126 3810 2128 3810 2129 3810 2126 3811 2129 3811 2076 3811 2076 3812 2129 3812 2130 3812 2076 3813 2130 3813 2065 3813 2065 3814 2130 3814 2131 3814 2065 3815 2131 3815 2066 3815 1333 3816 1331 3816 2092 3816 2092 3817 1331 3817 1330 3817 2092 3818 1330 3818 2094 3818 2094 3819 1330 3819 1335 3819 2094 3820 1335 3820 1336 3820 2081 3821 2083 3821 2099 3821 2099 3822 2083 3822 2094 3822 2099 3823 2094 3823 2127 3823 2127 3824 2094 3824 1336 3824 2127 3825 1336 3825 1339 3825 1998 3826 1997 3826 2121 3826 2121 3827 1997 3827 2075 3827 2121 3828 2075 3828 2122 3828 2122 3829 2075 3829 2117 3829 2122 3830 2117 3830 2123 3830 2123 3831 2117 3831 2118 3831 2123 3832 2118 3832 2124 3832 2124 3833 2118 3833 2119 3833 2124 3834 2119 3834 2088 3834 2088 3835 2119 3835 2120 3835 2088 3836 2120 3836 2086 3836 2086 3837 2120 3837 2132 3837 2091 3838 2084 3838 2092 3838 2092 3839 2084 3839 2086 3839 2092 3840 2086 3840 1333 3840 1333 3841 2086 3841 2132 3841 1333 3842 2132 3842 1323 3842 1323 3843 2132 3843 1324 3843 1533 3844 1532 3844 2120 3844 2120 3845 1532 3845 2133 3845 2120 3846 2133 3846 2132 3846 2132 3847 2133 3847 1329 3847 2132 3848 1329 3848 1324 3848 1288 3849 1287 3849 1538 3849 1298 3850 1297 3850 1550 3850 1550 3851 1297 3851 1551 3851 1514 3852 1427 3852 1305 3852 1297 3853 1295 3853 1551 3853 1551 3854 1295 3854 1294 3854 1551 3855 1294 3855 1552 3855 1552 3856 1294 3856 1301 3856 1552 3857 1301 3857 1427 3857 1427 3858 1301 3858 1300 3858 1427 3859 1300 3859 1305 3859 1517 3860 1311 3860 1519 3860 1519 3861 1311 3861 1309 3861 1519 3862 1309 3862 1521 3862 1521 3863 1309 3863 1307 3863 1521 3864 1307 3864 1527 3864 1315 3865 1531 3865 1313 3865 1313 3866 1531 3866 1530 3866 1265 3867 1525 3867 1266 3867 1266 3868 1525 3868 1523 3868 1266 3869 1523 3869 1321 3869 1321 3870 1523 3870 1531 3870 1321 3871 1531 3871 1317 3871 1317 3872 1531 3872 1315 3872 1307 3873 1306 3873 1527 3873 1527 3874 1306 3874 1320 3874 1527 3875 1320 3875 1528 3875 1528 3876 1320 3876 1319 3876 1528 3877 1319 3877 1530 3877 1530 3878 1319 3878 1318 3878 1530 3879 1318 3879 1313 3879 1305 3880 1304 3880 1514 3880 1514 3881 1304 3881 1303 3881 1514 3882 1303 3882 1515 3882 1515 3883 1303 3883 1302 3883 1515 3884 1302 3884 1517 3884 1517 3885 1302 3885 1312 3885 1517 3886 1312 3886 1311 3886 1445 3887 2134 3887 1535 3887 1535 3888 2134 3888 1536 3888 2134 3889 1277 3889 1536 3889 1536 3890 1277 3890 1276 3890 1536 3891 1276 3891 1281 3891 1538 3892 1287 3892 1534 3892 1534 3893 1287 3893 1285 3893 1534 3894 1285 3894 1448 3894 1281 3895 1282 3895 1536 3895 1536 3896 1282 3896 1269 3896 1536 3897 1269 3897 1537 3897 1537 3898 1269 3898 1268 3898 1537 3899 1268 3899 1538 3899 1538 3900 1268 3900 1289 3900 1538 3901 1289 3901 1288 3901 1329 3902 2133 3902 1328 3902 1328 3903 2133 3903 1327 3903 2133 3904 1532 3904 1327 3904 1327 3905 1532 3905 1525 3905 1327 3906 1525 3906 1325 3906 1325 3907 1525 3907 1265 3907 1285 3908 1284 3908 1448 3908 1448 3909 1284 3909 1293 3909 1448 3910 1293 3910 1548 3910 1548 3911 1293 3911 1549 3911 1549 3912 1293 3912 1291 3912 1549 3913 1291 3913 1550 3913 1550 3914 1291 3914 1290 3914 1550 3915 1290 3915 1298 3915 2049 3916 2047 3916 2135 3916 1880 3917 1718 3917 1719 3917 2136 3918 1736 3918 2137 3918 2137 3919 1736 3919 1735 3919 2137 3920 1735 3920 2138 3920 2138 3921 1735 3921 2139 3921 1735 3922 1733 3922 2139 3922 2139 3923 1733 3923 1731 3923 2139 3924 1731 3924 2140 3924 2140 3925 1731 3925 1730 3925 2140 3926 1730 3926 2141 3926 2141 3927 1730 3927 2142 3927 2143 3928 1819 3928 2144 3928 2144 3929 1819 3929 1817 3929 2144 3930 1817 3930 2145 3930 2145 3931 1817 3931 1815 3931 2145 3932 1815 3932 2146 3932 2146 3933 1815 3933 1814 3933 2146 3934 1814 3934 2147 3934 2147 3935 1814 3935 1740 3935 2147 3936 1740 3936 2136 3936 2136 3937 1740 3937 1738 3937 2136 3938 1738 3938 1736 3938 2148 3939 2149 3939 1719 3939 1719 3940 2149 3940 1881 3940 1719 3941 1881 3941 1880 3941 2150 3942 2151 3942 1714 3942 1714 3943 2151 3943 1716 3943 1716 3944 2151 3944 2152 3944 1716 3945 2152 3945 1723 3945 1719 3946 1720 3946 2148 3946 2148 3947 1720 3947 1722 3947 2148 3948 1722 3948 2153 3948 2153 3949 1722 3949 1723 3949 2153 3950 1723 3950 2154 3950 2154 3951 1723 3951 2152 3951 1813 3952 2049 3952 1812 3952 1812 3953 2049 3953 2135 3953 1812 3954 2135 3954 1811 3954 1811 3955 2135 3955 2155 3955 1811 3956 2155 3956 1729 3956 1729 3957 2155 3957 2156 3957 1729 3958 2156 3958 1727 3958 1727 3959 2156 3959 2142 3959 1727 3960 2142 3960 1726 3960 1726 3961 2142 3961 1730 3961 1714 3962 1698 3962 2150 3962 2150 3963 1698 3963 1697 3963 2150 3964 1697 3964 2157 3964 2157 3965 1697 3965 1822 3965 2157 3966 1822 3966 2143 3966 2143 3967 1822 3967 1821 3967 2143 3968 1821 3968 1819 3968 2158 3969 2159 3969 2160 3969 2161 3970 2162 3970 2163 3970 1348 3971 1347 3971 2164 3971 2165 3972 1367 3972 1365 3972 2166 3973 2167 3973 2168 3973 2169 3974 2170 3974 2171 3974 2172 3975 2173 3975 2171 3975 1380 3976 1379 3976 1901 3976 1901 3977 1379 3977 1414 3977 1901 3978 1414 3978 1275 3978 1380 3979 2174 3979 1382 3979 1382 3980 2174 3980 1383 3980 2175 3981 1972 3981 1980 3981 1898 3982 1974 3982 2175 3982 2175 3983 1974 3983 1973 3983 2175 3984 1973 3984 1972 3984 1380 3985 1901 3985 2174 3985 2174 3986 1901 3986 1899 3986 2174 3987 1899 3987 1383 3987 1422 3988 1257 3988 2176 3988 2176 3989 1257 3989 2175 3989 2176 3990 2175 3990 2160 3990 2160 3991 2175 3991 1980 3991 1899 3992 1898 3992 1383 3992 1383 3993 1898 3993 2175 3993 1383 3994 2175 3994 1256 3994 1256 3995 2175 3995 1257 3995 2177 3996 2178 3996 2179 3996 2179 3997 2178 3997 1373 3997 2179 3998 1373 3998 2180 3998 2170 3999 2180 3999 2171 3999 2171 4000 2180 4000 1373 4000 2171 4001 1373 4001 2172 4001 2172 4002 1373 4002 1372 4002 2181 4003 2169 4003 2182 4003 2182 4004 2169 4004 2171 4004 2182 4005 2171 4005 2183 4005 2183 4006 2171 4006 2173 4006 2183 4007 2173 4007 2184 4007 1372 4008 1370 4008 2172 4008 2172 4009 1370 4009 1369 4009 2172 4010 1369 4010 1378 4010 2185 4011 2186 4011 2187 4011 2187 4012 2186 4012 2188 4012 2167 4013 2189 4013 2185 4013 2167 4014 2166 4014 2189 4014 2189 4015 2166 4015 2190 4015 2189 4016 2190 4016 2191 4016 2191 4017 2190 4017 2192 4017 2191 4018 2192 4018 2193 4018 2194 4019 2195 4019 2196 4019 2194 4020 2164 4020 2197 4020 2197 4021 2164 4021 2198 4021 2197 4022 2198 4022 2199 4022 2168 4023 2200 4023 2166 4023 2166 4024 2200 4024 2201 4024 2166 4025 2201 4025 2190 4025 2190 4026 2201 4026 2202 4026 2190 4027 2202 4027 2192 4027 2192 4028 2202 4028 2203 4028 2192 4029 2203 4029 2193 4029 2193 4030 2203 4030 2204 4030 2177 4031 2179 4031 2205 4031 2205 4032 2179 4032 2180 4032 2205 4033 2180 4033 2206 4033 2206 4034 2180 4034 2170 4034 2206 4035 2170 4035 2207 4035 2207 4036 2170 4036 2169 4036 2207 4037 2169 4037 2188 4037 2188 4038 2169 4038 2181 4038 2188 4039 2181 4039 2187 4039 2208 4040 2209 4040 2210 4040 2210 4041 2209 4041 2211 4041 2212 4042 2213 4042 2214 4042 2214 4043 2213 4043 2215 4043 2214 4044 2215 4044 2216 4044 2217 4045 2165 4045 2218 4045 2208 4046 2210 4046 2219 4046 2219 4047 2210 4047 2220 4047 2219 4048 2220 4048 2221 4048 1368 4049 2222 4049 1362 4049 1362 4050 2222 4050 2223 4050 2224 4051 2225 4051 2226 4051 2226 4052 2225 4052 2227 4052 1357 4053 1356 4053 2228 4053 1351 4054 1350 4054 2198 4054 2198 4055 1350 4055 1358 4055 2198 4056 1358 4056 2226 4056 2226 4057 1358 4057 1357 4057 2226 4058 1357 4058 2224 4058 2224 4059 1357 4059 2228 4059 2224 4060 2228 4060 2225 4060 2225 4061 2228 4061 2229 4061 1348 4062 2164 4062 1402 4062 2194 4063 2196 4063 2164 4063 2164 4064 2196 4064 1407 4064 2164 4065 1407 4065 1402 4065 1347 4066 1345 4066 2164 4066 2164 4067 1345 4067 1344 4067 2164 4068 1344 4068 2198 4068 2198 4069 1344 4069 1353 4069 2198 4070 1353 4070 1351 4070 2222 4071 2221 4071 2223 4071 2223 4072 2221 4072 2220 4072 2223 4073 2220 4073 2229 4073 2229 4074 2220 4074 2210 4074 2229 4075 2210 4075 2225 4075 2225 4076 2210 4076 2211 4076 2225 4077 2211 4077 2227 4077 1356 4078 1260 4078 2228 4078 2228 4079 1260 4079 1259 4079 2228 4080 1259 4080 2229 4080 2229 4081 1259 4081 1360 4081 2229 4082 1360 4082 2223 4082 2223 4083 1360 4083 1363 4083 2223 4084 1363 4084 1362 4084 2230 4085 2231 4085 2232 4085 2232 4086 2231 4086 2233 4086 2232 4087 2233 4087 2234 4087 2162 4088 2235 4088 2163 4088 2163 4089 2235 4089 2236 4089 2163 4090 2236 4090 2233 4090 2233 4091 2236 4091 2237 4091 2233 4092 2237 4092 2234 4092 2238 4093 2239 4093 2240 4093 2240 4094 2239 4094 2241 4094 2231 4095 2242 4095 2233 4095 2233 4096 2242 4096 2238 4096 2233 4097 2238 4097 2163 4097 2163 4098 2238 4098 2240 4098 2163 4099 2240 4099 2161 4099 2161 4100 2240 4100 2241 4100 2161 4101 2241 4101 2243 4101 2244 4102 2245 4102 2246 4102 2066 4103 2131 4103 2247 4103 2244 4104 2246 4104 2247 4104 2247 4105 2246 4105 2248 4105 2247 4106 2248 4106 2066 4106 2243 4107 2245 4107 2161 4107 2161 4108 2245 4108 2244 4108 2161 4109 2244 4109 2162 4109 2162 4110 2244 4110 2249 4110 2162 4111 2249 4111 2235 4111 2235 4112 2249 4112 2250 4112 2235 4113 2250 4113 2236 4113 2236 4114 2250 4114 2251 4114 2236 4115 2251 4115 2237 4115 2237 4116 2251 4116 2252 4116 2237 4117 2252 4117 2234 4117 1983 4118 1982 4118 2158 4118 1980 4119 1979 4119 2160 4119 2160 4120 1979 4120 1978 4120 2160 4121 1978 4121 2158 4121 2158 4122 1978 4122 1977 4122 2158 4123 1977 4123 1983 4123 2159 4124 2253 4124 2160 4124 2160 4125 2253 4125 2184 4125 2160 4126 2184 4126 2176 4126 2176 4127 2184 4127 2173 4127 2176 4128 2173 4128 1422 4128 1422 4129 2173 4129 2172 4129 1422 4130 2172 4130 1376 4130 1376 4131 2172 4131 1378 4131 1376 4132 1378 4132 1377 4132 1342 4133 1343 4133 2196 4133 2128 4134 1340 4134 1341 4134 2130 4135 2129 4135 2195 4135 2195 4136 2129 4136 2128 4136 2195 4137 2128 4137 2196 4137 2196 4138 2128 4138 1341 4138 2196 4139 1341 4139 1342 4139 1343 4140 1263 4140 2196 4140 2196 4141 1263 4141 1262 4141 2196 4142 1262 4142 1407 4142 2203 4143 2216 4143 2204 4143 2204 4144 2216 4144 2215 4144 2204 4145 2215 4145 2254 4145 2254 4146 2215 4146 2213 4146 2254 4147 2213 4147 2255 4147 2255 4148 2213 4148 2212 4148 2255 4149 2212 4149 2256 4149 2256 4150 2212 4150 2217 4150 2256 4151 2217 4151 2257 4151 2257 4152 2217 4152 2218 4152 2257 4153 2218 4153 1375 4153 2165 4154 1365 4154 2218 4154 2218 4155 1365 4155 1364 4155 2218 4156 1364 4156 1375 4156 2185 4157 2189 4157 2186 4157 2186 4158 2189 4158 2191 4158 2186 4159 2191 4159 2188 4159 2188 4160 2191 4160 2193 4160 2188 4161 2193 4161 2207 4161 2207 4162 2193 4162 2204 4162 2207 4163 2204 4163 2206 4163 2206 4164 2204 4164 2254 4164 2206 4165 2254 4165 2205 4165 2205 4166 2254 4166 2255 4166 2205 4167 2255 4167 2177 4167 2177 4168 2255 4168 2256 4168 2177 4169 2256 4169 2178 4169 2178 4170 2256 4170 2257 4170 2178 4171 2257 4171 1373 4171 1373 4172 2257 4172 1375 4172 1373 4173 1375 4173 1374 4173 2131 4174 2130 4174 2247 4174 2247 4175 2130 4175 2195 4175 2247 4176 2195 4176 2244 4176 2244 4177 2195 4177 2194 4177 2244 4178 2194 4178 2249 4178 2249 4179 2194 4179 2197 4179 2249 4180 2197 4180 2250 4180 2250 4181 2197 4181 2199 4181 2250 4182 2199 4182 2251 4182 2251 4183 2199 4183 2258 4183 2251 4184 2258 4184 2252 4184 2252 4185 2258 4185 2259 4185 2252 4186 2259 4186 2234 4186 2234 4187 2259 4187 2260 4187 2234 4188 2260 4188 2232 4188 2232 4189 2260 4189 2261 4189 2232 4190 2261 4190 2230 4190 2230 4191 2261 4191 2262 4191 2253 4192 2263 4192 2184 4192 2184 4193 2263 4193 2264 4193 2184 4194 2264 4194 2183 4194 2183 4195 2264 4195 2265 4195 2183 4196 2265 4196 2182 4196 2182 4197 2265 4197 2266 4197 2182 4198 2266 4198 2267 4198 2267 4199 2262 4199 2182 4199 2182 4200 2262 4200 2261 4200 2182 4201 2261 4201 2181 4201 2181 4202 2261 4202 2260 4202 2181 4203 2260 4203 2187 4203 2187 4204 2260 4204 2259 4204 2187 4205 2259 4205 2185 4205 2185 4206 2259 4206 2258 4206 2185 4207 2258 4207 2167 4207 2167 4208 2258 4208 2199 4208 2167 4209 2199 4209 2168 4209 2168 4210 2199 4210 2198 4210 2168 4211 2198 4211 2200 4211 2200 4212 2198 4212 2226 4212 2200 4213 2226 4213 2201 4213 2201 4214 2226 4214 2227 4214 2201 4215 2227 4215 2202 4215 2202 4216 2227 4216 2211 4216 2202 4217 2211 4217 2203 4217 2203 4218 2211 4218 2209 4218 2203 4219 2209 4219 2216 4219 2216 4220 2209 4220 2208 4220 2216 4221 2208 4221 2214 4221 2214 4222 2208 4222 2219 4222 2214 4223 2219 4223 2212 4223 2212 4224 2219 4224 2221 4224 2212 4225 2221 4225 2217 4225 2217 4226 2221 4226 2222 4226 2217 4227 2222 4227 2165 4227 2165 4228 2222 4228 1368 4228 2165 4229 1368 4229 1367 4229 2059 4230 2057 4230 2268 4230 2269 4231 1890 4231 1881 4231 2061 4232 2060 4232 2270 4232 2271 4233 2272 4233 2273 4233 2253 4234 2159 4234 2269 4234 1890 4235 2269 4235 1889 4235 2158 4236 1982 4236 1981 4236 1889 4237 2269 4237 1981 4237 1981 4238 2269 4238 2159 4238 1981 4239 2159 4239 2158 4239 2274 4240 2275 4240 2276 4240 2276 4241 2275 4241 2277 4241 2276 4242 2277 4242 2278 4242 2278 4243 2277 4243 2279 4243 2278 4244 2279 4244 2280 4244 2281 4245 2275 4245 2263 4245 2263 4246 2275 4246 2274 4246 2263 4247 2274 4247 2264 4247 2264 4248 2274 4248 2265 4248 2242 4249 2231 4249 2282 4249 2282 4250 2231 4250 2230 4250 2282 4251 2230 4251 2283 4251 2283 4252 2230 4252 2262 4252 2283 4253 2262 4253 2267 4253 2248 4254 2246 4254 2284 4254 2284 4255 2246 4255 2285 4255 2284 4256 2285 4256 2286 4256 2052 4257 2054 4257 2286 4257 2050 4258 2052 4258 2287 4258 2287 4259 2052 4259 2286 4259 2287 4260 2286 4260 2288 4260 2288 4261 2286 4261 2289 4261 2288 4262 2289 4262 2290 4262 2290 4263 2289 4263 2291 4263 2290 4264 2291 4264 2292 4264 2292 4265 2291 4265 2293 4265 2292 4266 2293 4266 2294 4266 2294 4267 2293 4267 2295 4267 2294 4268 2295 4268 2273 4268 2246 4269 2245 4269 2285 4269 2285 4270 2245 4270 2243 4270 2285 4271 2243 4271 2296 4271 2296 4272 2243 4272 2241 4272 2296 4273 2241 4273 2297 4273 2297 4274 2241 4274 2239 4274 2297 4275 2239 4275 2238 4275 2286 4276 2285 4276 2289 4276 2289 4277 2285 4277 2296 4277 2289 4278 2296 4278 2291 4278 2291 4279 2296 4279 2297 4279 2291 4280 2297 4280 2293 4280 2293 4281 2297 4281 2238 4281 2293 4282 2238 4282 2295 4282 2273 4283 2272 4283 2294 4283 2294 4284 2272 4284 2298 4284 2294 4285 2298 4285 2292 4285 2292 4286 2298 4286 2299 4286 2292 4287 2299 4287 2290 4287 2290 4288 2299 4288 2300 4288 2290 4289 2300 4289 2288 4289 2288 4290 2300 4290 2301 4290 2288 4291 2301 4291 2287 4291 2287 4292 2301 4292 2302 4292 2287 4293 2302 4293 2268 4293 2268 4294 2057 4294 2287 4294 2287 4295 2057 4295 2056 4295 2287 4296 2056 4296 2050 4296 2303 4297 2145 4297 2304 4297 2304 4298 2145 4298 2146 4298 2304 4299 2146 4299 2305 4299 2305 4300 2146 4300 2147 4300 2305 4301 2147 4301 2306 4301 2306 4302 2147 4302 2136 4302 2306 4303 2136 4303 2307 4303 2307 4304 2136 4304 2137 4304 2308 4305 2141 4305 2142 4305 2308 4306 2142 4306 2309 4306 2137 4307 2138 4307 2307 4307 2307 4308 2138 4308 2139 4308 2307 4309 2139 4309 2308 4309 2308 4310 2139 4310 2140 4310 2308 4311 2140 4311 2141 4311 2047 4312 2061 4312 2135 4312 2135 4313 2061 4313 2270 4313 2135 4314 2270 4314 2155 4314 2155 4315 2270 4315 2309 4315 2155 4316 2309 4316 2156 4316 2156 4317 2309 4317 2142 4317 1881 4318 2149 4318 2269 4318 2269 4319 2149 4319 2281 4319 2269 4320 2281 4320 2253 4320 2253 4321 2281 4321 2263 4321 2066 4322 2248 4322 2064 4322 2064 4323 2248 4323 2284 4323 2064 4324 2284 4324 2062 4324 2062 4325 2284 4325 2286 4325 2062 4326 2286 4326 2055 4326 2055 4327 2286 4327 2054 4327 2265 4328 2274 4328 2266 4328 2266 4329 2274 4329 2276 4329 2266 4330 2276 4330 2267 4330 2267 4331 2276 4331 2278 4331 2267 4332 2278 4332 2283 4332 2283 4333 2278 4333 2280 4333 2283 4334 2280 4334 2282 4334 2060 4335 2059 4335 2270 4335 2270 4336 2059 4336 2268 4336 2270 4337 2268 4337 2309 4337 2309 4338 2268 4338 2302 4338 2309 4339 2302 4339 2308 4339 2308 4340 2302 4340 2301 4340 2308 4341 2301 4341 2307 4341 2307 4342 2301 4342 2300 4342 2307 4343 2300 4343 2306 4343 2306 4344 2300 4344 2299 4344 2306 4345 2299 4345 2305 4345 2305 4346 2299 4346 2298 4346 2305 4347 2298 4347 2304 4347 2304 4348 2298 4348 2272 4348 2304 4349 2272 4349 2303 4349 2303 4350 2272 4350 2271 4350 2303 4351 2271 4351 2310 4351 2149 4352 2148 4352 2281 4352 2281 4353 2148 4353 2153 4353 2281 4354 2153 4354 2275 4354 2275 4355 2153 4355 2154 4355 2275 4356 2154 4356 2277 4356 2277 4357 2154 4357 2152 4357 2277 4358 2152 4358 2151 4358 2150 4359 2157 4359 2310 4359 2310 4360 2157 4360 2143 4360 2310 4361 2143 4361 2303 4361 2303 4362 2143 4362 2144 4362 2303 4363 2144 4363 2145 4363 2151 4364 2150 4364 2277 4364 2277 4365 2150 4365 2310 4365 2277 4366 2310 4366 2279 4366 2279 4367 2310 4367 2271 4367 2279 4368 2271 4368 2280 4368 2280 4369 2271 4369 2273 4369 2280 4370 2273 4370 2282 4370 2282 4371 2273 4371 2295 4371 2282 4372 2295 4372 2242 4372 2242 4373 2295 4373 2238 4373

+
+
+
+
+ + + + + 0.6858805 -0.3173701 0.6548619 7.481132 0.7276338 0.3124686 -0.6106656 -6.50764 -0.01081678 0.8953432 0.4452454 5.343665 0 0 0 1 + + + + -0.2908646 -0.7711008 0.5663932 4.076245 0.9551712 -0.1998834 0.2183912 1.005454 -0.05518906 0.6045247 0.7946723 5.903862 0 0 0 1 + + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + +
\ No newline at end of file diff --git a/libraries/SITL/examples/Webots_Python/protos/textures/aruco_0.png b/libraries/SITL/examples/Webots_Python/protos/textures/aruco_0.png new file mode 100644 index 0000000000..2f337579f5 Binary files /dev/null and b/libraries/SITL/examples/Webots_Python/protos/textures/aruco_0.png differ diff --git a/libraries/SITL/examples/Webots_Python/protos/textures/aruco_1.png b/libraries/SITL/examples/Webots_Python/protos/textures/aruco_1.png new file mode 100644 index 0000000000..b57af11f55 Binary files /dev/null and b/libraries/SITL/examples/Webots_Python/protos/textures/aruco_1.png differ diff --git a/libraries/SITL/examples/Webots_Python/protos/textures/aruco_2.png b/libraries/SITL/examples/Webots_Python/protos/textures/aruco_2.png new file mode 100644 index 0000000000..c548dcc1ca Binary files /dev/null and b/libraries/SITL/examples/Webots_Python/protos/textures/aruco_2.png differ diff --git a/libraries/SITL/examples/Webots_Python/protos/textures/aruco_3.png b/libraries/SITL/examples/Webots_Python/protos/textures/aruco_3.png new file mode 100644 index 0000000000..b87ca898c2 Binary files /dev/null and b/libraries/SITL/examples/Webots_Python/protos/textures/aruco_3.png differ diff --git a/libraries/SITL/examples/Webots_Python/protos/textures/aruco_4.png b/libraries/SITL/examples/Webots_Python/protos/textures/aruco_4.png new file mode 100644 index 0000000000..0c9914e7be Binary files /dev/null and b/libraries/SITL/examples/Webots_Python/protos/textures/aruco_4.png differ diff --git a/libraries/SITL/examples/Webots_Python/protos/textures/aruco_5.png b/libraries/SITL/examples/Webots_Python/protos/textures/aruco_5.png new file mode 100644 index 0000000000..9526142f25 Binary files /dev/null and b/libraries/SITL/examples/Webots_Python/protos/textures/aruco_5.png differ diff --git a/libraries/SITL/examples/Webots_Python/protos/textures/aruco_6.png b/libraries/SITL/examples/Webots_Python/protos/textures/aruco_6.png new file mode 100644 index 0000000000..e47e26de30 Binary files /dev/null and b/libraries/SITL/examples/Webots_Python/protos/textures/aruco_6.png differ diff --git a/libraries/SITL/examples/Webots_Python/protos/textures/aruco_7.png b/libraries/SITL/examples/Webots_Python/protos/textures/aruco_7.png new file mode 100644 index 0000000000..be9dfb7691 Binary files /dev/null and b/libraries/SITL/examples/Webots_Python/protos/textures/aruco_7.png differ diff --git a/libraries/SITL/examples/Webots_Python/protos/textures/aruco_8.png b/libraries/SITL/examples/Webots_Python/protos/textures/aruco_8.png new file mode 100644 index 0000000000..27bc5243d2 Binary files /dev/null and b/libraries/SITL/examples/Webots_Python/protos/textures/aruco_8.png differ diff --git a/libraries/SITL/examples/Webots_Python/scripts/example_aruco_detection.py b/libraries/SITL/examples/Webots_Python/scripts/example_aruco_detection.py new file mode 100755 index 0000000000..a3e1046998 --- /dev/null +++ b/libraries/SITL/examples/Webots_Python/scripts/example_aruco_detection.py @@ -0,0 +1,84 @@ +#!/usr/bin/env python3 + +# +# An example script that receives images from a WebotsArduVehicle on port 5599 +# and displays them overlayed with any ArUco markers using OpenCV. +# Requires opencv-python (`pip3 install opencv-python`) +# + +import cv2 +import socket +import struct +import numpy as np + +# connect to WebotsArduVehicle +s = socket.socket(socket.AF_INET, socket.SOCK_STREAM) +s.connect(("127.0.0.1", 5599)) + +# ArUco setup +aruco_dict = cv2.aruco.Dictionary_get(cv2.aruco.DICT_4X4_50) +aruco_params = cv2.aruco.DetectorParameters_create() + +header_size = struct.calcsize("=HH") +while True: + # receive header + header = s.recv(header_size) + if len(header) != header_size: + print("Header size mismatch") + break + + # parse header + width, height = struct.unpack("=HH", header) + + # for CV applications we may want camera intrinsics such as focal length: + # https://stackoverflow.com/questions/61555182/webot-camera-default-parameters-like-pixel-size-and-focus + # cam_focal_length = 2 * np.arctan(np.tan(cam_fov * 0.5) / (cam_width / cam_height)) + + # receive image + bytes_to_read = width * height + img = bytes() + while len(img) < bytes_to_read: + img += s.recv(min(bytes_to_read - len(img), 4096)) + + # convert to numpy array + img = np.frombuffer(img, np.uint8).reshape((height, width)) + img = cv2.cvtColor(img, cv2.COLOR_GRAY2BGR) + + # detect ArUco markers + (corners, ids, rejected) = cv2.aruco.detectMarkers(img, aruco_dict, parameters=aruco_params) + if len(corners) > 0: + # flatten the ArUco IDs list + ids = ids.flatten() + # loop over the detected ArUCo corners + for (markerCorner, markerID) in zip(corners, ids): + # extract the marker corners (which are always returned in + # top-left, top-right, bottom-right, and bottom-left order) + corners = markerCorner.reshape((4, 2)) + (topLeft, topRight, bottomRight, bottomLeft) = corners + # convert each of the (x, y)-coordinate pairs to integers + topRight = (int(topRight[0]), int(topRight[1])) + bottomRight = (int(bottomRight[0]), int(bottomRight[1])) + bottomLeft = (int(bottomLeft[0]), int(bottomLeft[1])) + topLeft = (int(topLeft[0]), int(topLeft[1])) + + # draw the bounding box of the ArUCo detection + cv2.line(img, topLeft, topRight, (0, 255, 0), 2) + cv2.line(img, topRight, bottomRight, (0, 255, 0), 2) + cv2.line(img, bottomRight, bottomLeft, (0, 255, 0), 2) + cv2.line(img, bottomLeft, topLeft, (0, 255, 0), 2) + # compute and draw the center (x, y)-coordinates of the ArUco + # marker + cX = int((topLeft[0] + bottomRight[0]) / 2.0) + cY = int((topLeft[1] + bottomRight[1]) / 2.0) + cv2.circle(img, (cX, cY), 4, (0, 0, 255), -1) + # draw the ArUco marker ID on the image + cv2.putText(img, str(markerID), + (topLeft[0], topLeft[1] - 15), cv2.FONT_HERSHEY_SIMPLEX, + 0.5, (0, 255, 0), 2) + + # display image + cv2.imshow("image", img) + if cv2.waitKey(1) == ord("q"): + break + +s.close() \ No newline at end of file diff --git a/libraries/SITL/examples/Webots_Python/scripts/example_camera_receive.py b/libraries/SITL/examples/Webots_Python/scripts/example_camera_receive.py new file mode 100755 index 0000000000..c7e33a9d96 --- /dev/null +++ b/libraries/SITL/examples/Webots_Python/scripts/example_camera_receive.py @@ -0,0 +1,46 @@ +#!/usr/bin/env python3 + +# +# An example script that receives images from a WebotsArduVehicle +# on port 5599 and displays using OpenCV. +# Requires opencv-python (`pip3 install opencv-python`) +# + +import cv2 +import socket +import struct +import numpy as np + +# connect to WebotsArduVehicle +s = socket.socket(socket.AF_INET, socket.SOCK_STREAM) +s.connect(("127.0.0.1", 5599)) + +header_size = struct.calcsize("=HH") +while True: + # receive header + header = s.recv(header_size) + if len(header) != header_size: + print("Header size mismatch") + break + + # parse header + width, height = struct.unpack("=HH", header) + + # receive image + bytes_to_read = width * height + img = bytes() + while len(img) < bytes_to_read: + img += s.recv(min(bytes_to_read - len(img), 4096)) + + # convert incoming bytes to a numpy array (a grayscale image) + img = np.frombuffer(img, np.uint8).reshape((height, width)) + + # Do cool stuff with the image here + # ... + + # display image + cv2.imshow("image", img) + if cv2.waitKey(1) == ord("q"): + break + +s.close() \ No newline at end of file diff --git a/libraries/SITL/examples/Webots_Python/worlds/crazyflie.wbt b/libraries/SITL/examples/Webots_Python/worlds/crazyflie.wbt new file mode 100644 index 0000000000..24ea0a2daa --- /dev/null +++ b/libraries/SITL/examples/Webots_Python/worlds/crazyflie.wbt @@ -0,0 +1,51 @@ +#VRML_SIM R2023a utf8 + +EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2023a/projects/robots/bitcraze/crazyflie/protos/Crazyflie.proto" +EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2023a/projects/objects/backgrounds/protos/TexturedBackground.proto" +EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2023a/projects/objects/backgrounds/protos/TexturedBackgroundLight.proto" +EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2023a/projects/objects/floors/protos/Floor.proto" + +WorldInfo { + title "Crazyflie Ardupilot" + basicTimeStep 2 + FPS 20 +} +Viewpoint { + orientation -0.16896949154992233 0.7737576492025086 0.6105312532753491 0.687001624474616 + position -0.398945807007221 -0.19824950788611448 0.29284320157231725 + follow "Crazyflie" + followSmoothness 0.01 +} +TexturedBackground { +} +TexturedBackgroundLight { +} +Floor { +} +Crazyflie { + controller "ardupilot_vehicle_controller" + controllerArgs [ + "--motors" + "m1_motor, m3_motor, m4_motor, m2_motor" + "--reversed-motors" + "1, 2" + "--camera-fps" + "10" + "--camera" + "camera" + "--accel" + "accelerometer" + "--imu" + "inertial unit" + "--gyro" + "gyro" + "--gps" + "gps" + "--motor-cap" + "100" + ] + extensionSlot [ + Accelerometer { + } + ] +} diff --git a/libraries/SITL/examples/Webots_Python/worlds/crazyflie_double.wbt b/libraries/SITL/examples/Webots_Python/worlds/crazyflie_double.wbt new file mode 100644 index 0000000000..d6843e9a0c --- /dev/null +++ b/libraries/SITL/examples/Webots_Python/worlds/crazyflie_double.wbt @@ -0,0 +1,76 @@ +#VRML_SIM R2023a utf8 + +EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2023a/projects/robots/bitcraze/crazyflie/protos/Crazyflie.proto" +EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2023a/projects/objects/backgrounds/protos/TexturedBackground.proto" +EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2023a/projects/objects/backgrounds/protos/TexturedBackgroundLight.proto" +EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2023a/projects/objects/floors/protos/Floor.proto" + +WorldInfo { + title "Crazyflie Ardupilot" + basicTimeStep 2 + FPS 30 +} +Viewpoint { + orientation -0.0593532354440745 0.9880332410323718 0.14236399845953884 0.798588127989691 + position -0.5248689288960577 0.1043842791985661 0.5678333324847978 + follow "Crazyflie 0" + followSmoothness 0.01 +} +TexturedBackground { +} +TexturedBackgroundLight { +} +Floor { +} +Crazyflie { + hidden linearVelocity_0 -4.637218965709596e-19 -4.196252875038606e-19 3.352873534367973e-16 + hidden angularVelocity_0 4.956352788505185e-17 6.199137112878587e-17 -7.59922590549506e-18 + translation -1.2560172892842563e-17 0.2 0.014998773749999996 + rotation 0.0006423841504381482 0.0009061380955760532 -0.9999993831279872 3.0862235845634213e-16 + name "Crazyflie 0" + controller "ardupilot_vehicle_controller" + controllerArgs [ + "--reversed-motors" + "1, 2" + "--camera" + "camera" + "--camera-fps" + "10" + "--motors" + "m1_motor, m3_motor, m4_motor, m2_motor" + "--motor-cap" + "100" + "--instance" + "0" + ] + extensionSlot [ + Accelerometer { + } + ] +} +Crazyflie { + hidden linearVelocity_0 1.1290302625479896e-18 -4.326730364482081e-19 3.352873534367973e-16 + hidden angularVelocity_0 5.546676845014852e-31 2.0628843433230186e-17 -7.9532317962812e-18 + translation -3.7742147020501796e-18 -1.921003416687696e-17 0.014998773749999996 + rotation -0.0017125758688741218 0.0002306643848911165 -0.9999985069378028 3.183501628356045e-16 + name "Crazyflie 1" + controller "ardupilot_vehicle_controller" + controllerArgs [ + "--reversed-motors" + "1, 2" + "--camera-fps" + "10" + "--camera" + "camera" + "--motors" + "m1_motor, m3_motor, m4_motor, m2_motor" + "--motor-cap" + "100" + "--instance" + "1" + ] + extensionSlot [ + Accelerometer { + } + ] +} diff --git a/libraries/SITL/examples/Webots_Python/worlds/iris.wbt b/libraries/SITL/examples/Webots_Python/worlds/iris.wbt new file mode 100644 index 0000000000..0f7e4d920b --- /dev/null +++ b/libraries/SITL/examples/Webots_Python/worlds/iris.wbt @@ -0,0 +1,63 @@ +# VRML_SIM R2023a utf8 + +EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2023a/projects/objects/backgrounds/protos/TexturedBackground.proto" +EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2023a/projects/objects/backgrounds/protos/TexturedBackgroundLight.proto" +EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2023a/projects/objects/road/protos/StraightRoadSegment.proto" +EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2023a/projects/objects/floors/protos/Floor.proto" +EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2023a/projects/appearances/protos/Grass.proto" +EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2023a/projects/objects/advertising_board/protos/AdvertisingBoard.proto" +EXTERNPROTO "../protos/Iris.proto" + +WorldInfo { + title "Iris Ardupilot" + basicTimeStep 2 + FPS 20 +} +Viewpoint { + orientation 0.15554153350599548 -0.8879632385984604 -0.4328141844398555 5.514055516141922 + position -2.719806534182175 -0.9451744343683601 2.1727182111093915 + follow "Iris" + followSmoothness 0.01 +} +TexturedBackground { +} +TexturedBackgroundLight { +} +Floor { + size 300 100 + appearance Grass { + } +} +AdvertisingBoard { + translation 13.1012 17.8267 0 + rotation 0 0 1 -1.469 + frontTexture [ + "../../../../../Tools/autotest/web-firmware/images/logo.png" + ] + backTexture [ + "../../../../../Tools/autotest/web-firmware/images/logo.png" + ] + displayWidth 16.28 + displayHeight 6 + poleNumber 2 + poleType "H-shape" + poleHeight 10 +} +StraightRoadSegment { + translation -15 0.3 0.02 + rotation 0 0 1 0.105 + width 16.5 + rightBorder FALSE + leftBorder FALSE + length 140 +} +Iris { + translation 0 0 0.09 + controller "ardupilot_vehicle_controller" + controllerArgs [ + "--motors" + "m1_motor, m2_motor, m3_motor, m4_motor" + ] + extensionSlot [ + ] +} diff --git a/libraries/SITL/examples/Webots_Python/worlds/iris_camera.wbt b/libraries/SITL/examples/Webots_Python/worlds/iris_camera.wbt new file mode 100644 index 0000000000..f4abc5f171 --- /dev/null +++ b/libraries/SITL/examples/Webots_Python/worlds/iris_camera.wbt @@ -0,0 +1,118 @@ +#VRML_SIM R2023a utf8 + +EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2023a/projects/objects/backgrounds/protos/TexturedBackground.proto" +EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2023a/projects/objects/backgrounds/protos/TexturedBackgroundLight.proto" +EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2023a/projects/objects/road/protos/StraightRoadSegment.proto" +EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2023a/projects/objects/floors/protos/Floor.proto" +EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2023a/projects/appearances/protos/Grass.proto" +EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2023a/projects/objects/tables/protos/Table.proto" +EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2023a/projects/objects/advertising_board/protos/AdvertisingBoard.proto" +EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2023a/projects/objects/obstacles/protos/OilBarrel.proto" +EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2023a/projects/objects/animals/protos/Dog.proto" +EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2023a/projects/objects/animals/protos/Rabbit.proto" +EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2023a/projects/objects/garden/protos/Gnome.proto" +EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2023a/projects/objects/factory/forklift/protos/Forklift.proto" +EXTERNPROTO "../protos/Iris.proto" +EXTERNPROTO "../protos/ArucoMarker.proto" + +WorldInfo { + title "Iris Ardupilot" + basicTimeStep 2 + FPS 20 +} +Viewpoint { + orientation 0.10264123808602478 -0.7648124131744727 -0.6360241732028804 5.867275660921915 + position -2.488925008027789 0.29237831017431365 2.067754838508868 + follow "Iris" + followSmoothness 0.01 +} +TexturedBackground { +} +TexturedBackgroundLight { +} +Floor { + size 300 100 + appearance Grass { + } +} +StraightRoadSegment { + translation -15 0.3 0.02 + rotation 0 0 1 0.105 + width 16.5 + rightBorder FALSE + leftBorder FALSE + length 140 +} +Rabbit { + translation 4.68362 1.88178 0.88 + rotation 0 0 1 2.61799 + name "nibbles" +} +Gnome { + translation 5.87588 0.590355 3.6788e-21 + rotation 0 0 1 2.61799 +} +Forklift { + translation 9.19827 2.56008 0.81 + rotation 0 0 1 -2.3561953071795863 + enablePhysics FALSE +} +Dog { + translation 5.97592 3.52 1.77636e-15 + rotation 0 0 1 -2.6179953071795863 + name "bentley" +} +OilBarrel { + translation 4.54625 1.79835 0.44 +} +AdvertisingBoard { + translation 13.1012 17.8267 0 + rotation 0 0 1 -1.469 + frontTexture [ + "../../../../../Tools/autotest/web-firmware/images/logo.png" + ] + backTexture [ + "../../../../../Tools/autotest/web-firmware/images/logo.png" + ] + displayWidth 16.28 + displayHeight 6 + poleNumber 2 + poleType "H-shape" + poleHeight 10 +} +Table { + translation 0 0.92 0 +} +Iris { + translation 0.0702495 1.45039 0.8 + controller "ardupilot_vehicle_controller" + controllerArgs [ + "--motors" + "m1_motor, m2_motor, m3_motor, m4_motor" + "--camera" + "camera" + "--camera-port" + "5599" + ] + extensionSlot [ + Camera { + translation 0.05 0 0.05 + rotation 0 1 0 0 + width 640 + height 480 + } + ] +} +ArucoMarker { + translation 4.23295 1.80428 0.72 + rotation 0 1 0 -1.5707953071795862 + name "aruco 0" + size 0.2 +} +ArucoMarker { + translation 4.39446 1.53182 0.44 + rotation 0.44721372362178063 -0.7745965212991105 0.44721372362178063 1.82348 + name "aruco 1" + size 0.2 + markerId "1" +} diff --git a/libraries/SITL/examples/Webots_Python/worlds/iris_depth_camera.wbt b/libraries/SITL/examples/Webots_Python/worlds/iris_depth_camera.wbt new file mode 100644 index 0000000000..0b4b2bac82 --- /dev/null +++ b/libraries/SITL/examples/Webots_Python/worlds/iris_depth_camera.wbt @@ -0,0 +1,97 @@ +#VRML_SIM R2023a utf8 + +EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2023a/projects/objects/backgrounds/protos/TexturedBackground.proto" +EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2023a/projects/objects/backgrounds/protos/TexturedBackgroundLight.proto" +EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2023a/projects/objects/road/protos/StraightRoadSegment.proto" +EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2023a/projects/objects/floors/protos/Floor.proto" +EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2023a/projects/appearances/protos/Grass.proto" +EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2023a/projects/humans/pedestrian/protos/Pedestrian.proto" +EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2023a/projects/objects/buildings/protos/Warehouse.proto" +EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2023a/projects/objects/advertising_board/protos/AdvertisingBoard.proto" +EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2023a/projects/objects/tables/protos/Table.proto" +EXTERNPROTO "../protos/Iris.proto" + +WorldInfo { + title "Iris Ardupilot" + basicTimeStep 2 + FPS 20 +} +Viewpoint { + orientation -0.08123827592100609 -0.8844702112073417 0.45947011656061265 5.888579928177443 + position -13.153423548832741 2.5290211453100055 6.931773501208396 + follow "Iris" + followSmoothness 0.01 +} +TexturedBackground { +} +TexturedBackgroundLight { +} +Floor { + size 300 100 + appearance Grass { + } +} +StraightRoadSegment { + translation -15 0.3 0.02 + rotation 0 0 1 0.105 + width 16.5 + rightBorder FALSE + leftBorder FALSE + length 140 +} +Warehouse { + translation 22.0473 -12.6792 0 + rotation 0 0 1 1.671 +} +Warehouse { + translation 61.8844 -8.67468 0 + rotation 0 0 1 1.671 + name "warehouse(1)" +} +Pedestrian { + translation 2.49 0 1.27 + controllerArgs [ + "--speed=0.75" + "--trajectory= 2.5 0, 5 2.5, 7.5 0, 5 -2.5" + ] +} +Table { + translation 0 0.92 0 +} +AdvertisingBoard { + translation 13.1012 17.8267 0 + rotation 0 0 1 -1.469 + frontTexture [ + "../../../../../Tools/autotest/web-firmware/images/logo.png" + ] + backTexture [ + "../../../../../Tools/autotest/web-firmware/images/logo.png" + ] + displayWidth 16.28 + displayHeight 6 + poleNumber 2 + poleType "H-shape" + poleHeight 10 +} +Iris { + translation 0.0702495 1.45039 0.8 + rotation 0 0 1 -0.523595307179586 + controller "ardupilot_vehicle_controller" + controllerArgs [ + "--motors" + "m1_motor, m2_motor, m3_motor, m4_motor" + "--rangefinder" + "range-finder" + "--rangefinder-port" + "5599" + ] + extensionSlot [ + RangeFinder { + translation 0.1 0 0 + fieldOfView 1.57 + width 640 + height 480 + maxRange 20 + } + ] +} \ No newline at end of file diff --git a/libraries/SITL/examples/Webots_Python/worlds/pioneer3at.wbt b/libraries/SITL/examples/Webots_Python/worlds/pioneer3at.wbt new file mode 100644 index 0000000000..af3ad3f3ed --- /dev/null +++ b/libraries/SITL/examples/Webots_Python/worlds/pioneer3at.wbt @@ -0,0 +1,62 @@ +#VRML_SIM R2023a utf8 + +EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/released/projects/robots/adept/pioneer3/protos/Pioneer3at.proto" +EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2023a/projects/objects/backgrounds/protos/TexturedBackground.proto" +EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2023a/projects/objects/backgrounds/protos/TexturedBackgroundLight.proto" +EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2023a/projects/objects/road/protos/StraightRoadSegment.proto" +EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2023a/projects/objects/floors/protos/Floor.proto" +EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2023a/projects/appearances/protos/Grass.proto" + +WorldInfo { + title "Pioneer3at Ardupilot" + basicTimeStep 2 + FPS 20 +} +Viewpoint { + orientation 0.12905547789670888 -0.9264705889754452 -0.353549050894418 5.532540449151996 + position -2.921033113316591 -0.8540816786630955 2.693602881281485 + follow "Pioneer 3-AT" + followSmoothness 0.01 +} +TexturedBackground { +} +TexturedBackgroundLight { +} +Floor { + size 300 100 + appearance Grass { + } +} +StraightRoadSegment { + translation -15 0.3 0.02 + rotation 0 0 1 0.105 + width 16.5 + rightBorder FALSE + leftBorder FALSE + length 140 +} +Pioneer3at { + controller "ardupilot_vehicle_controller" + controllerArgs [ + "--motors" + "front left wheel, back left wheel, front right wheel, back right wheel" + "--camera-fps" + "10" + "--motor-cap" + "100" + "--bidirectional-motors" + "true" + "--uses-propellers" + "false" + ] + extensionSlot [ + Accelerometer { + } + InertialUnit { + } + Gyro { + } + GPS { + } + ] +}